Skip to content
Snippets Groups Projects

Compare revisions

Changes are shown as if the source revision was being merged into the target revision. Learn more about comparing revisions.

Source

Select target project
No results found

Target

Select target project
  • danc/MicroCART
  • snawerdt/MicroCART_17-18
  • bbartels/MicroCART_17-18
  • jonahu/MicroCART
4 results
Show changes
Showing
with 14940 additions and 0 deletions
/*
* || ____ _ __
* +------+ / __ )(_) /_______________ _____ ___
* | 0xBC | / __ / / __/ ___/ ___/ __ `/_ / / _ \
* +------+ / /_/ / / /_/ /__/ / / /_/ / / /_/ __/
* || || /_____/_/\__/\___/_/ \__,_/ /___/\___/
*
* Crazyflie control firmware
*
* Copyright (C) 2015 Bitcraze AB
*
* This program is free software: you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation, in version 3.
*
* This program is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with this program. If not, see <http://www.gnu.org/licenses/>.
*
* deck_test.h - Deck test utility functions
*/
#ifndef __DECK_TEST_H__
#define __DECK_TEST_H__
#include <stdint.h>
#include "stm32fxxx.h"
typedef struct
{
GPIO_TypeDef gpioBuffA;
GPIO_TypeDef gpioBuffB;
GPIO_TypeDef gpioBuffC;
} GpioRegBuf;
/**
* Deck test evaluation function which makes evaluation
* a bit less messy. Outputs failstring on console if test
* failed.
*
* param[in] result The result of the test.
* param[in] failstring Pointer to fail string.
* param[out] status Saves the test result.
*/
void decktestEval(bool result, char *failString, bool *status);
/**
* Save GPIO registers into buffer so it can be restored later
*
* param[out] gpioRegBuf Buffer to which registers will be copied
*/
void decktestSaveGPIOStatesABC(GpioRegBuf *gpioRegBuf);
/**
* Restore saved GPIO registers
*
* param[in] gpioRegBuf Buffer of saved registers
*/
void decktestRestoreGPIOStatesABC(GpioRegBuf *gpioRegBuf);
#endif
Deck API
========
This folder contains files implementing the deck I/O API. Currently only the
Crazyflie 2.0 implements this api for the Deck expantion port I/Os.
The API is inspired by the Arduino API. It implements the arduino API mapping
C++ to C function in a consistent way.
/**
* Copyright (C) 2015 - 2016 Bosch Sensortec GmbH
*
* 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.
*
* @file bmi055.h
* @date 19 Apr, 2017
* @version 1.1.0
* @brief Sensor Driver for BMI055 sensor
*
*/
#ifndef BMI055_H_
#define BMI055_H_
#ifdef __cplusplus
extern "C"
{
#endif
/********************************************************/
/* header includes */
#include "../interface/bmi055_defs.h"
/***************************************************************************/
/**\name BMI055 User Accelerometer function prototypes
****************************************************************************/
/*!
* @brief This API is the entry point for accelerometer sensor.
* It performs the selection of I2C/SPI read mechanism according to the
* selected interface and reads the chip-id of accelerometer sensor.
*
* @param[in,out] dev : Structure instance of bmi055_dev.
* @note : Refer user guide for detailed info.
*
* @return Result of API execution status
* @retval zero -> Success / -ve value -> Error
*/
int8_t bmi055_accel_init(struct bmi055_dev *dev);
/*!
* @brief This API reads the data from the given register address of
* accelerometer sensor.
*
* @param[in] reg_addr : Register address from where the data to be read
* @param[out] data : Pointer to data buffer to store the read data.
* @param[in] len : No. of bytes of data to be read.
* @param[in] dev : Structure instance of bmi055_dev.
*
* @return Result of API execution status
* @retval zero -> Success / -ve value -> Error
*/
int8_t bmi055_get_accel_regs(uint8_t reg_addr, uint8_t *data, uint16_t len, const struct bmi055_dev *dev);
/*!
* @brief This API writes the given data to the register address
* of accel sensor.
*
* @param[in] reg_addr : Register address to where the data to be written.
* @param[in] data : Pointer to data buffer which is to be written
* in the sensor.
* @param[in] len : No. of bytes of data to write.
* @param[in] dev : Structure instance of bmi055_dev.
*
* @return Result of API execution status
* @retval zero -> Success / -ve value -> Error
*/
int8_t bmi055_set_accel_regs(uint8_t reg_addr, uint8_t *data, uint16_t len, const struct bmi055_dev *dev);
/*!
* @brief This API resets and restarts the accelerometer sensor.All register
* values are overwritten with default parameters.
*
* @param[in] dev : Structure instance of bmi055_dev.
*
* @return Result of API execution status
* @retval zero -> Success / -ve value -> Error.
*/
int8_t bmi055_accel_soft_reset(const struct bmi055_dev *dev);
/*!
* @brief This API sets the power mode of the accelerometer sensor.
*
* @param[in] dev : Structure instance of bmi055_dev.
* [in] power : power to be set
*
* @return Result of API execution status
* @retval zero -> Success / -ve value -> Error.
*/
int8_t bmi055_set_accel_power_mode(const struct bmi055_dev *dev);
/*!
* @brief This API sets the range and bandwidth
* of accel sensor.
*
* @param[in] dev : Structure instance of bmi055_dev.
* @param[in] bmi055_config : Decides the parameter to be tested
*
* @note : Refer user guide for detailed info.
*
* @return Result of API execution status
* @retval zero -> Success / -ve value -> Error.
*/
int8_t bmi055_set_accel_sensor_config(uint8_t bmi055_config, const struct bmi055_dev *dev);
/*!
* @brief This API reads the accelerometer data from the sensor,
* store it in the bmi055_sensor_data structure instance
* passed by the user.
*
* @param[out] accel : Structure pointer to store accelerometer data
* @param[in] dev : Structure instance of bmi055_dev.
*
*
* @return Result of API execution status
* @retval zero -> Success / -ve value -> Error
*/
int8_t bmi055_get_accel_data(struct bmi055_sensor_data *accel, const struct bmi055_dev *dev);
/*!
* @brief This API configures the necessary accelerometer interrupt
* based on the user settings in the bmi055_accel_int_sett
* structure instance.
*
* @param[in] acc_int_config : Structure instance of bmi055_accel_int_sett.
* @param[in] dev : Structure instance of bmi055_dev.
*
* @note : Refer user guide for detailed info.
*
* @return Result of API execution status
* @retval zero -> Success / -ve value -> Error
*/
int8_t bmi055_set_accel_int_config(struct bmi055_accel_int_sett *acc_int_config, const struct bmi055_dev *dev);
/*!
* @brief This API retrieves the status of accelerometer interrupts
* when set
*
* @param[in, out] intr_status : Pointer to get interrupt status.
* @param[in] dev : Structure instance of bmi055_dev.
*
* @note : Refer bmi055_defs.h for status masks :
*
* BMI055_ACC_LOW_G_INT_STATUS_MASK - For low-g status
* BMI055_ACC_HIGH_G_INT_STATUS_MASK - For high-g status
* BMI055_ACC_SLOPE_INT_STATUS_MASK - For slope status
* BMI055_ACC_SLOW_NO_MOT_INT_STATUS_MASK - For slow-motion interrupt
* BMI055_ACC_DOUBLE_TAP_INT_STATUS_MASK - For double tap
* BMI055_ACC_SINGLE_TAP_INT_STATUS_MASK - For single tap
* BMI055_ACC_ORIENT_INT_STATUS_MASK - For orient interrupt
* BMI055_ACC_TAP_INT_STATUS_MASK - For tap interrupt
* BMI055_ACC_FIFO_FULL_INT_STATUS_MASK - For fifo full interrupt
* BMI055_ACC_FIFO_WM_INT_STATUS_MASK - For fifo watermark interrupt
* BMI055_ACC_NEW_DATA_INT_STATUS_MASK - For new data interrupt
* BMI055_ACC_SLOPE_X_INT_STATUS_MASK - For slope interrupt in x-axis
* BMI055_ACC_SLOPE_Y_INT_STATUS_MASK - For slope interrupt in y-axis
* BMI055_ACC_SLOPE_Z_INT_STATUS_MASK - For slope interrupt in z-axis
* BMI055_ACC_SLOPE_SIGN_INT_STATUS_MASK - direction of slope interrupt
* BMI055_ACC_TAP_X_INT_STATUS_MASK - For tap interrupt in x-axis
* BMI055_ACC_TAP_Y_INT_STATUS_MASK - For tap interrupt in y-axis
* BMI055_ACC_TAP_Z_INT_STATUS_MASK - For tap interrupt in z-axis
* BMI055_ACC_TAP_SIGN_INT_STATUS_MASK - direction of slope interrupt
* BMI055_ACC_HIGH_G_X_INT_STATUS_MASK - For high-g interrupt in x-axis
* BMI055_ACC_HIGH_G_Y_INT_STATUS_MASK - For high-g interrupt in y-axis
* BMI055_ACC_HIGH_G_Z_INT_STATUS_MASK - For high-g interrupt in z-axis
* BMI055_ACC_HIGH_G_SIGN_INT_STATUS_MASK - direction of high-g interrupt
* BMI055_ACC_ORIENT_BIT_MASK - interrupt for orient modes
* BMI055_ACC_ORIENT_PORTRAIT_UPRIGHT_MASK- orientation is portrait upright
* BMI055_ACC_ORIENT_PORTRAIT_DOWN_MASK - orientation is portrait down
* BMI055_ACC_ORIENT_LANDSACPE_LEFT_MASK - orientation is landscape left
* BMI055_ACC_ORIENT_LANDSACPE_RIGHT_MASK - orientation is landscape right
* BMI055_ACC_ORIENT_Z_AXIS_DIR_MASK - direction of z axis
* BMI055_ACC_FLAT_INT_STATUS_MASK - For flat interrupt
*
* @return Result of API execution status
* @retval zero -> Success / -ve value -> Error
*/
int8_t bmi055_get_accel_int_status(uint32_t *intr_status, const struct bmi055_dev *dev);
/*!
* @brief This API clears all the latched interrupts of the accelerometer.
*
* @param[in] acc_int_config : Structure instance of bmi055_accel_int_sett.
* @param[in] dev : Structure instance of bmi055_dev.
*
* @note : Refer user guide for detailed info.
*
* @return Result of API execution status
* @retval zero -> Success / -ve value -> Error
*/
int8_t bmi055_reset_accel_latch_int(struct bmi055_accel_int_sett *acc_int_config, const struct bmi055_dev *dev);
/*!
* @brief This API enables/disables individual or all accelerometer interrupts.
*
* @param[in] acc_int_config : Structure instance of bmi055_accel_int_sett.
* @param[in] dev : Structure instance of bmi055_dev.
* @param[in] set_en_bit : Enable or disable bit.
*
* @note : Refer user guide for detailed info.
*
* @return Result of API execution status
* @retval zero -> Success / -ve value -> Error
*/
int8_t bmi055_set_reset_accel_int(struct bmi055_accel_int_sett *acc_int_config, const struct bmi055_dev *dev,
uint8_t set_en_bit);
/***************************************************************************/
/**\name BMI055 Gyroscope User function prototypes
****************************************************************************/
/*!
* @brief This API is the entry point for gyroscope sensor.
* It performs the selection of I2C/SPI read mechanism according to the
* selected interface and reads the chip-id of gyroscope sensor.
*
* @param[in,out] dev : Structure instance of bmi055_dev.
* @note : Refer user guide for detailed info.
*
* @return Result of API execution status
* @retval zero -> Success / -ve value -> Error
*/
int8_t bmi055_gyro_init(struct bmi055_dev *dev);
/*!
* @brief This API reads the data from the given register address of \
* gyroscope sensor.
*
* @param[in] reg_addr : Register address from where the data to be read
* @param[out] data : Pointer to data buffer to store the read data.
* @param[in] len : No. of bytes of data to be read.
* @param[in] dev : Structure instance of bmi055_dev.
*
* @return Result of API execution status
* @retval zero -> Success / -ve value -> Error
*/
int8_t bmi055_get_gyro_regs(uint8_t reg_addr, uint8_t *data, uint16_t len, const struct bmi055_dev *dev);
/*!
* @brief This API writes the given data to the register address
* of gyroscope sensor.
*
* @param[in] reg_addr : Register address to where the data to be written.
* @param[in] data : Pointer to data buffer which is to be written
* in the sensor.
* @param[in] len : No. of bytes of data to write.
* @param[in] dev : Structure instance of bmi055_dev.
*
* @return Result of API execution status
* @retval zero -> Success / -ve value -> Error
*/
int8_t bmi055_set_gyro_regs(uint8_t reg_addr, uint8_t *data, uint16_t len, const struct bmi055_dev *dev);
/*!
* @brief This API resets and restarts the gyroscope sensor.All
* register values are overwritten with default values.
*
* @param[in] dev : Structure instance of bmi055_dev.
*
* @return Result of API execution status
* @retval zero -> Success / -ve value -> Error.
*/
int8_t bmi055_gyro_soft_reset(const struct bmi055_dev *dev);
/*!
* @brief This API sets the power mode of the gyroscope sensor.
*
* @param[in] dev : Structure instance of bmi055_dev.
*
* @return Result of API execution status
* @retval zero -> Success / -ve value -> Error.
*/
int8_t bmi055_set_gyro_power_mode(const struct bmi055_dev *dev);
/*!
* @brief This API sets the range and bandwidth
* of gyroscope sensor.
*
* @param[in] dev : Structure instance of bmi055_dev.
* @param[in] bmi055_config : Decides the parameter to be tested
*
* @note : Refer user guide for detailed info.
*
* @return Result of API execution status
* @retval zero -> Success / -ve value -> Error.
*/
int8_t bmi055_set_gyro_sensor_config(uint8_t bmi055_config, const struct bmi055_dev *dev);
/*!
* @brief This API reads the gyroscope data from the sensor,
* store it in the bmi055_sensor_data structure instance
* passed by the user.
*
* @param[out] gyro : Structure pointer to store gyroscope data
* @param[in] dev : Structure instance of bmi055_dev.
*
* @return Result of API execution status
* @retval zero -> Success / -ve value -> Error
*/
int8_t bmi055_get_gyro_data(struct bmi055_sensor_data *gyro, const struct bmi055_dev *dev);
/*!
* @brief This API configures the necessary gyroscope interrupt
* based on the user settings in the bmi055_accel_int_sett
* structure instance.
*
* @param[in, out] acc_int_config : Structure instance of bmi055_accel_int_sett.
* @param[in] dev : Structure instance of bmi055_dev.
* @note : Refer user guide for detailed info.
*
* @return Result of API execution status
* @retval zero -> Success / -ve value -> Error
*/
int8_t bmi055_set_gyro_int_config(struct bmi055_gyro_int_sett *gyr_int_config, struct bmi055_dev *dev);
#ifdef __cplusplus
}
#endif
#endif /* BMI055_H_ */
/**
* Copyright (C) 2015 - 2016 Bosch Sensortec GmbH
*
* 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.
*
* @file bmi055_defs.h
* @date 19 Apr, 2017
* @version 1.1.0
* @brief Sensor driver for BMI055 sensor *
*/
#ifndef BMI055_DEFS_H_
#define BMI055_DEFS_H_
/******************************************************************************/
/*! Header includes */
/******************************************************************************/
#ifdef __KERNEL__
#include <linux/types.h>
#else
#include <stdint.h>
#include <stddef.h>
#endif
/******************************************************************************/
/*! C++ guard macro */
/******************************************************************************/
#ifdef __cplusplus
extern "C"
{
#endif
/******************************************************************************/
/*! Common macros */
/******************************************************************************/
/*
#if (LONG_MAX) > 0x7fffffff
#define __have_long64 1
#elif (LONG_MAX) == 0x7fffffff
#define __have_long32 1
#endif
*/
#if !defined(UINT8_C)
#define INT8_C(x) x
#if (INT_MAX) > 0x7f
#define UINT8_C(x) x
#else
#define UINT8_C(x) x##U
#endif
#endif
#if !defined(UINT16_C)
#define INT16_C(x) x
#if (INT_MAX) > 0x7fff
#define UINT16_C(x) x
#else
#define UINT16_C(x) x##U
#endif
#endif
#if !defined(INT32_C) && !defined(UINT32_C)
#if __have_long32
#define INT32_C(x) x##L
#define UINT32_C(x) x##UL
#else
#define INT32_C(x) x
#define UINT32_C(x) x##U
#endif
#endif
#if !defined(INT64_C) && !defined(UINT64_C)
#if __have_long64
#define INT64_C(x) x##L
#define UINT64_C(x) x##UL
#else
#define INT64_C(x) x##LL
#define UINT64_C(x) x##ULL
#endif
#endif
/******************************************************************************/
/*! Sensor macros */
/******************************************************************************/
/* Test for an endian machine */
#if __BYTE_ORDER__ == __ORDER_LITTLE_ENDIAN__
#define LITTLE_ENDIAN 1
#elif __BYTE_ORDER__ == __ORDER_BIG_ENDIAN__
#define BIG_ENDIAN 1
#else
#error "Code does not support Endian format of the processor"
#endif
/******************************************************************************/
/*! Utility macros */
/******************************************************************************/
#define BMI055_SET_BITS(reg_data, bitname, data) ((reg_data & ~(bitname##_MASK)) | \
((data << bitname##_POS) & bitname##_MASK))
#define BMI055_GET_BITS(reg_data, bitname) ((reg_data & (bitname##_MASK)) >> \
(bitname##_POS))
#define BMI055_SET_BIT_POS0(reg_data, bitname, data) ((reg_data & ~(bitname##_MASK)) | \
(data & bitname##_MASK))
#define BMI055_GET_BIT_POS0(reg_data, bitname) (reg_data & (bitname##_MASK))
/******************************************************************************/
/*! Macros for defining version number */
/******************************************************************************/
#define BMI055_VER_MAJOR UINT8_C(1)
#define BMI055_VER_MINOR UINT8_C(1)
#define BMI055_VER_PATCH UINT8_C(0)
/******************************************************************************/
/*! Macros for parameter settings */
/******************************************************************************/
/*! Bandwidth settings */
#define BANDWIDTH_CONFIG UINT8_C(0x01)
/*! Range settings */
#define RANGE_CONFIG UINT8_C(0x02)
/*! Range plus bandwidth settings */
#define CONFIG_ALL UINT8_C(BANDWIDTH_CONFIG | RANGE_CONFIG)
/******************************************************************************/
/*! Macros for defining enable or disable */
/******************************************************************************/
#define BMI055_ENABLE UINT8_C(0x01)
#define BMI055_DISABLE UINT8_C(0x00)
#define CODE_UNDER_MODIFICATION UINT8_C(0x00)
#define BMI055_FILTERED UINT8_C(0x00)
#define BMI055_UNFILTERED UINT8_C(0x01)
/******************************************************************************/
/*! BMI055 Accelerometer Macros */
/******************************************************************************/
/*! Macros to define the types of interrupts */
/* Slope/ Any-motion interrupt */
#define BMI055_ACC_SLOPE_INT UINT8_C(0x00)
/* double tap interrupt */
#define BMI055_ACC_DOUBLE_TAP_INT UINT8_C(0x01)
/* single tap interrupt */
#define BMI055_ACC_SINGLE_TAP_INT UINT8_C(0x02)
/* orientation interrupt */
#define BMI055_ACC_ORIENT_INT UINT8_C(0x03)
/* flat interrupt */
#define BMI055_ACC_FLAT_INT UINT8_C(0x04)
/* low-g interrupt */
#define BMI055_ACC_LOW_G_INT UINT8_C(0x05)
/* high-g interrupt */
#define BMI055_ACC_HIGH_G_INT UINT8_C(0x06)
/* slow/ no-motion interrupt */
#define BMI055_ACC_SLOW_NO_MOTION_INT UINT8_C(0x07)
/* New data interrupt */
#define BMI055_ACC_NEW_DATA_INT UINT8_C(0x08)
/* All accelerometer interrupts */
#define BMI055_ALL_ACCEL_INT UINT8_C(0x09)
/*! Macros to define the channel number of interrupts */
/* Interrupt Channel 1 for accelerometer sensor */
#define BMI055_INT_CHANNEL_1 UINT8_C(0x00)
/* Interrupt Channel 2 for accelerometer sensor */
#define BMI055_INT_CHANNEL_2 UINT8_C(0x01)
/*! Register map of accelerometer registers */
#define BMI055_ACC_CHIP_ID_ADDR UINT8_C(0x00)
#define BMI055_ACC_X_L_ADDR UINT8_C(0x02)
#define BMI055_ACC_X_H_ADDR UINT8_C(0x03)
#define BMI055_ACC_Y_L_ADDR UINT8_C(0x04)
#define BMI055_ACC_Y_H_ADDR UINT8_C(0x05)
#define BMI055_ACC_Z_L_ADDR UINT8_C(0x06)
#define BMI055_ACC_Z_H_ADDR UINT8_C(0x07)
#define BMI055_ACC_TEMP_ADDR UINT8_C(0x08)
#define BMI055_ACC_INT_STATUS_0_ADDR UINT8_C(0x09)
#define BMI055_ACC_INT_STATUS_1_ADDR UINT8_C(0x0A)
#define BMI055_ACC_INT_STATUS_2_ADDR UINT8_C(0x0B)
#define BMI055_ACC_INT_STATUS_3_ADDR UINT8_C(0x0C)
#define BMI055_ACC_FIFO_STATUS_ADDR UINT8_C(0x0E)
#define BMI055_ACC_RANGE_ADDR UINT8_C(0x0F)
#define BMI055_ACC_BW_ADDR UINT8_C(0x10)
#define BMI055_ACC_PMU_LPW_ADDR UINT8_C(0x11)
#define BMI055_ACC_PMU_LOW_POWER_ADDR UINT8_C(0x12)
#define BMI055_ACC_DATA_CTRL_ADDR UINT8_C(0x13)
#define BMI055_ACC_SOFTRESET_ADDR UINT8_C(0x14)
#define BMI055_ACC_INT_EN_0_ADDR UINT8_C(0x16)
#define BMI055_ACC_INT_EN_1_ADDR UINT8_C(0x17)
#define BMI055_ACC_INT_EN_2_ADDR UINT8_C(0x18)
#define BMI055_ACC_INT_MAP_0_ADDR UINT8_C(0x19)
#define BMI055_ACC_INT_MAP_1_ADDR UINT8_C(0x1A)
#define BMI055_ACC_INT_MAP_2_ADDR UINT8_C(0x1B)
#define BMI055_ACC_INT_SRC_ADDR UINT8_C(0x1E)
#define BMI055_ACC_INT_OUT_CTRL_ADDR UINT8_C(0x20)
#define BMI055_ACC_INT_LATCH_ADDR UINT8_C(0x21)
#define BMI055_ACC_INT_LH_0_ADDR UINT8_C(0x22)
#define BMI055_ACC_INT_LH_1_ADDR UINT8_C(0x23)
#define BMI055_ACC_INT_LH_2_ADDR UINT8_C(0x24)
#define BMI055_ACC_INT_LH_3_ADDR UINT8_C(0x25)
#define BMI055_ACC_INT_LH_4_ADDR UINT8_C(0x26)
#define BMI055_ACC_INT_MOT_0_ADDR UINT8_C(0x27)
#define BMI055_ACC_INT_MOT_1_ADDR UINT8_C(0x28)
#define BMI055_ACC_INT_MOT_2_ADDR UINT8_C(0x29)
#define BMI055_ACC_INT_TAP_0_ADDR UINT8_C(0x2A)
#define BMI055_ACC_INT_TAP_1_ADDR UINT8_C(0x2B)
#define BMI055_ACC_INT_ORIENT_0_ADDR UINT8_C(0x2C)
#define BMI055_ACC_INT_ORIENT_1_ADDR UINT8_C(0x2D)
#define BMI055_ACC_INT_FLAT_0_ADDR UINT8_C(0x2E)
#define BMI055_ACC_INT_FLAT_1_ADDR UINT8_C(0x2F)
#define BMI055_ACC_FIFO_CONFIG_0_ADDR UINT8_C(0x30)
#define BMI055_ACC_SELFTEST_ADDR UINT8_C(0x32)
#define BMI055_ACC_EEPROM_CTRL_ADDR UINT8_C(0x33)
#define BMI055_ACC_SERIAL_CTRL_ADDR UINT8_C(0x34)
#define BMI055_ACC_OFFSET_CTRL_ADDR UINT8_C(0x36)
#define BMI055_ACC_OFC_SETTING_ADDR UINT8_C(0x37)
#define BMI055_ACC_OFFSET_X_ADDR UINT8_C(0x38)
#define BMI055_ACC_OFFSET_Y_ADDR UINT8_C(0x39)
#define BMI055_ACC_OFFSET_Z_ADDR UINT8_C(0x3A)
#define BMI055_ACC_TRIM_GPO_ADDR UINT8_C(0x3B)
#define BMI055_ACC_TRIM_GP1_ADDR UINT8_C(0x3C)
#define BMI055_ACC_FIFO_CONFIG_1_ADDR UINT8_C(0x3E)
#define BMI055_ACC_FIFO_DATA_ADDR UINT8_C(0x3F)
/*! Mask definitions for range, bandwidth and power */
#define BMI055_ACC_RANGE_MASK UINT8_C(0x0F)
#define BMI055_ACC_BW_MASK UINT8_C(0x1F)
#define BMI055_ACC_POWER_MASK UINT8_C(0xE0)
/*! Bit positions for range, bandwidth and power */
#define BMI055_ACC_POWER_POS UINT8_C(0x05)
/*! Mask definitions for INT_EN 0 registers */
#define BMI055_ACC_ANY_MOTION_X_INT_EN_0_MASK UINT8_C(0x01)
#define BMI055_ACC_ANY_MOTION_Y_INT_EN_0_MASK UINT8_C(0x02)
#define BMI055_ACC_ANY_MOTION_Z_INT_EN_0_MASK UINT8_C(0x04)
#define BMI055_ACC_DOUBLE_TAP_INT_EN_0_MASK UINT8_C(0x10)
#define BMI055_ACC_SINGLE_TAP_INT_EN_0_MASK UINT8_C(0x20)
#define BMI055_ACC_ORIENT_INT_EN_0_MASK UINT8_C(0x40)
#define BMI055_ACC_FLAT_INT_EN_0_MASK UINT8_C(0x80)
/*! Bit positions for INT_EN 0 registers */
#define BMI055_ACC_ANY_MOTION_Y_INT_EN_0_POS UINT8_C(0x01)
#define BMI055_ACC_ANY_MOTION_Z_INT_EN_0_POS UINT8_C(0x02)
#define BMI055_ACC_ORIENT_INT_EN_0_POS UINT8_C(0x06)
/*! Mask definitions for INT_EN 1 registers */
#define BMI055_ACC_HIGH_G_X_INT_EN_1_MASK UINT8_C(0x01)
#define BMI055_ACC_HIGH_G_Y_INT_EN_1_MASK UINT8_C(0x02)
#define BMI055_ACC_HIGH_G_Z_INT_EN_1_MASK UINT8_C(0x04)
#define BMI055_ACC_LOW_G_INT_EN_1_MASK UINT8_C(0x08)
#define BMI055_ACC_NEW_DATA_INT_EN_1_MASK UINT8_C(0x10)
#define BMI055_ACC_FIFO_FULL_INT_EN_1_MASK UINT8_C(0x20)
#define BMI055_ACC_FIFO_WM_INT_EN_1_MASK UINT8_C(0x40)
/*! Bit positions for INT_EN 1 registers */
#define BMI055_ACC_NEW_DATA_INT_EN_1_POS UINT8_C(0x04)
#define BMI055_ACC_LOW_G_INT_EN_1_POS UINT8_C(0x03)
#define BMI055_ACC_HIGH_G_Y_INT_EN_1_POS UINT8_C(0x01)
#define BMI055_ACC_HIGH_G_Z_INT_EN_1_POS UINT8_C(0x02)
/*! Mask definitions for INT_EN 2 registers */
#define BMI055_ACC_SLOW_NO_MOT_X_INT_EN_2_MASK UINT8_C(0x01)
#define BMI055_ACC_SLOW_NO_MOT_Y_INT_EN_2_MASK UINT8_C(0x02)
#define BMI055_ACC_SLOW_NO_MOT_Z_INT_EN_2_MASK UINT8_C(0x04)
#define BMI055_ACC_SLOW_NO_MOT_SEL_INT_EN_2_MASK UINT8_C(0x08)
/*! Bit positions for INT_EN 2 registers */
#define BMI055_ACC_SLOW_NO_MOT_X_INT_EN_2_POS0
#define BMI055_ACC_SLOW_NO_MOT_Y_INT_EN_2_POS UINT8_C(0x01)
#define BMI055_ACC_SLOW_NO_MOT_Z_INT_EN_2_POS UINT8_C(0x02)
#define BMI055_ACC_SLOW_NO_MOT_SEL_INT_EN_2_POS UINT8_C(0x03)
/*! Mask definitions for INT_MAP 0 registers */
#define BMI055_ACC_INT1_MAP_0_LOW_G_MASK UINT8_C(0x01)
#define BMI055_ACC_INT1_MAP_0_HIGH_G_MASK UINT8_C(0x02)
#define BMI055_ACC_INT1_MAP_0_SLOPE_MASK UINT8_C(0x04)
#define BMI055_ACC_INT1_MAP_0_SLOW_NO_MOT_MASK UINT8_C(0x08)
#define BMI055_ACC_INT1_MAP_0_DOUBLE_TAP_MASK UINT8_C(0x10)
#define BMI055_ACC_INT1_MAP_0_SINGLE_TAP_MASK UINT8_C(0x20)
#define BMI055_ACC_INT1_MAP_0_ORIENT_MASK UINT8_C(0x40)
#define BMI055_ACC_INT1_MAP_0_FLAT_MASK UINT8_C(0x80)
/*! Bit positions for INT_MAP 0 registers */
#define BMI055_ACC_INT1_MAP_0_HIGH_G_POS UINT8_C(0x01)
#define BMI055_ACC_INT1_MAP_0_SLOW_NO_MOT_POS UINT8_C(0x03)
#define BMI055_ACC_INT1_MAP_0_SLOPE_POS UINT8_C(0x02)
#define BMI055_ACC_INT1_MAP_0_ORIENT_POS UINT8_C(0x06)
/*! Mask definitions for INT_MAP 1 registers */
#define BMI055_ACC_INT1_MAP_1_NEW_DATA_MASK UINT8_C(0x01)
#define BMI055_ACC_INT1_MAP_1_FIFO_WM_MASK UINT8_C(0x02)
#define BMI055_ACC_INT1_MAP_1_FIFO_FULL_MASK UINT8_C(0x04)
#define BMI055_ACC_INT2_MAP_1_FIFO_FULL_MASK UINT8_C(0x20)
#define BMI055_ACC_INT2_MAP_1_FIFO_WM_MASK UINT8_C(0x40)
#define BMI055_ACC_INT2_MAP_1_NEW_DATA_MASK UINT8_C(0x80)
/*! Bit positions for INT_MAP 1 registers */
#define BMI055_ACC_INT2_MAP_1_NEW_DATA_POS UINT8_C(0x07)
/*! Mask definitions for INT_MAP 2 registers */
#define BMI055_ACC_INT2_MAP_2_LOW_G_MASK UINT8_C(0x01)
#define BMI055_ACC_INT2_MAP_2_HIGH_G_MASK UINT8_C(0x02)
#define BMI055_ACC_INT2_MAP_2_SLOPE_MASK UINT8_C(0x04)
#define BMI055_ACC_INT2_MAP_2_SLOW_NO_MOT_MASK UINT8_C(0x08)
#define BMI055_ACC_INT2_MAP_2_DOUBLE_TAP_MASK UINT8_C(0x10)
#define BMI055_ACC_INT2_MAP_2_SINGLE_TAP_MASK UINT8_C(0x20)
#define BMI055_ACC_INT2_MAP_2_ORIENT_MASK UINT8_C(0x40)
#define BMI055_ACC_INT2_MAP_2_FLAT_MASK UINT8_C(0x80)
/*! Bit positions for INT_MAP 2 registers */
#define BMI055_ACC_INT2_MAP_2_HIGH_G_POS UINT8_C(0x01)
#define BMI055_ACC_INT2_MAP_2_SLOW_NO_MOT_POS UINT8_C(0x03)
#define BMI055_ACC_INT2_MAP_2_SLOPE_POS UINT8_C(0x02)
#define BMI055_ACC_INT2_MAP_2_ORIENT_POS UINT8_C(0x06)
/*! Mask definitions for INT_OUT_CTRL register */
#define BMI055_ACC_INT1_LVL_MASK UINT8_C(0x01)
#define BMI055_ACC_INT1_OD_MASK UINT8_C(0x02)
#define BMI055_ACC_INT2_LVL_MASK UINT8_C(0x04)
#define BMI055_ACC_INT2_OD_MASK UINT8_C(0x08)
/*! Bit position for INT_OUT_CTRL register */
#define BMI055_ACC_INT1_OD_POS UINT8_C(0x01)
#define BMI055_ACC_INT2_LVL_POS UINT8_C(0x02)
#define BMI055_ACC_INT2_OD_POS UINT8_C(0x03)
/*! Mask definitions for INT_RST_LATCH register */
#define BMI055_ACC_LATCH_DUR_MASK UINT8_C(0x0F)
#define BMI055_ACC_RESET_INT_MASK UINT8_C(0x80)
/*! Bit position for INT_RST_LATCH register */
#define BMI055_ACC_RESET_INT_POS UINT8_C(0x07)
/*! Mask definitions for INT_SRC register */
#define BMI055_ACC_SRC_LOW_G_MASK UINT8_C(0x01)
#define BMI055_ACC_SRC_HIGH_G_MASK UINT8_C(0x02)
#define BMI055_ACC_SRC_SLOPE_MASK UINT8_C(0x04)
#define BMI055_ACC_SRC_SLOW_NO_MOT_MASK UINT8_C(0x08)
#define BMI055_ACC_SRC_TAP_MASK UINT8_C(0x10)
#define BMI055_ACC_SRC_NEW_DATA_MASK UINT8_C(0x20)
/*! Bit positions for INT_SRC register */
#define BMI055_ACC_SRC_NEW_DATA_POS UINT8_C(0x05)
#define BMI055_ACC_SRC_HIGH_G_POS UINT8_C(0x01)
#define BMI055_ACC_SRC_SLOW_NO_MOT_POS UINT8_C(0x03)
#define BMI055_ACC_SRC_SLOPE_POS UINT8_C(0x02)
/*! Mask definitions for slope/ Any-motion Interrupt */
#define BMI055_ACC_SLOPE_DUR_MASK UINT8_C(0x03)
/*! Mask definitions for single/ double tap Interrupts */
#define BMI055_ACC_TAP_DUR_MASK UINT8_C(0x07)
#define BMI055_ACC_TAP_SHOCK_MASK UINT8_C(0x40)
#define BMI055_ACC_TAP_QUIET_MASK UINT8_C(0x80)
#define BMI055_ACC_TAP_THRES_MASK UINT8_C(0x1F)
#define BMI055_ACC_TAP_SAMP_MASK UINT8_C(0xC0)
/*! Mask definitions for Orientation Interrupt */
#define BMI055_ACC_ORIENT_MODE_MASK UINT8_C(0x03)
#define BMI055_ACC_ORIENT_BLOCKING_MASK UINT8_C(0x0C)
#define BMI055_ACC_ORIENT_HYST_MASK UINT8_C(0x70)
#define BMI055_ACC_ORIENT_THETA_MASK UINT8_C(0x3F)
#define BMI055_ACC_ORIENT_UD_EN_MASK UINT8_C(0x40)
/*! Bit position for Orientation Interrupt */
#define BMI055_ACC_ORIENT_BLOCKING_POS UINT8_C(0x02)
#define BMI055_ACC_ORIENT_HYST_POS UINT8_C(0x04)
#define BMI055_ACC_ORIENT_UD_EN_POS UINT8_C(0x06)
/*! Mask definitions for Flat Interrupt */
#define BMI055_ACC_FLAT_THETA_MASK UINT8_C(0x3F)
#define BMI055_ACC_FLAT_HYST_MASK UINT8_C(0x07)
#define BMI055_ACC_FLAT_HOLD_TIME_MASK UINT8_C(0x30)
/*! Mask definitions for Low-g Interrupt */
#define BMI055_ACC_LOW_MODE_MASK UINT8_C(0x04)
#define BMI055_ACC_LOW_HYST_MASK UINT8_C(0x03)
/*! Bit position for Low-g Interrupt */
#define BMI055_ACC_LOW_MODE_POS UINT8_C(0x02)
/*! Mask definitions for High-g Interrupt */
#define BMI055_ACC_HIGH_HYST_MASK UINT8_C(0xC0)
/*! Bit position for High-g Interrupt */
#define BMI055_ACC_HIGH_HYST_POS UINT8_C(0x06)
/*! Mask definitions for Slow/ No motion Interrupt */
/* Defines no of consecutive slope data points */
#define BMI055_ACC_SLOW_DUR_MASK UINT8_C(0x0C)
/* Defines delay before interrupt is triggered */
#define BMI055_ACC_NO_MOTION_DUR_MASK UINT8_C(0xFC)
/*! Bit position for Slow/ No motion Interrupt */
#define BMI055_ACC_SLOW_DUR_POS UINT8_C(0x02)
#define BMI055_ACC_NO_MOTION_DUR_POS UINT8_C(0x02)
/*! Mask definitions for FIFO water-mark Interrupt */
#define BMI055_ACC_FIFO_WM_LEVEL_TRIG_MASK UINT8_C(0x3F)
/*! Mask definitions for Interrupt status bits */
#define BMI055_ACC_LOW_G_INT_STATUS_MASK UINT32_C(1)
#define BMI055_ACC_HIGH_G_INT_STATUS_MASK UINT32_C(1 << 1)
#define BMI055_ACC_SLOPE_INT_STATUS_MASK UINT32_C(1 << 2)
#define BMI055_ACC_SLOW_NO_MOT_INT_STATUS_MASK UINT32_C(1 << 3)
#define BMI055_ACC_DOUBLE_TAP_INT_STATUS_MASK UINT32_C(1 << 4)
#define BMI055_ACC_SINGLE_TAP_INT_STATUS_MASK UINT32_C(1 << 5)
#define BMI055_ACC_ORIENT_INT_STATUS_MASK UINT32_C(1 << 6)
#define BMI055_ACC_TAP_INT_STATUS_MASK UINT32_C(1 << 7)
#define BMI055_ACC_FIFO_FULL_INT_STATUS_MASK UINT32_C(1 << 13)
#define BMI055_ACC_FIFO_WM_INT_STATUS_MASK UINT32_C(1 << 14)
#define BMI055_ACC_NEW_DATA_INT_STATUS_MASK UINT32_C(1 << 15)
#define BMI055_ACC_SLOPE_X_INT_STATUS_MASK UINT32_C(1 << 16)
#define BMI055_ACC_SLOPE_Y_INT_STATUS_MASK UINT32_C(1 << 17)
#define BMI055_ACC_SLOPE_Z_INT_STATUS_MASK UINT32_C(1 << 18)
#define BMI055_ACC_SLOPE_SIGN_INT_STATUS_MASK UINT32_C(1 << 19)
#define BMI055_ACC_TAP_X_INT_STATUS_MASK UINT32_C(1 << 20)
#define BMI055_ACC_TAP_Y_INT_STATUS_MASK UINT32_C(1 << 21)
#define BMI055_ACC_TAP_Z_INT_STATUS_MASK UINT32_C(1 << 22)
#define BMI055_ACC_TAP_SIGN_INT_STATUS_MASK UINT32_C(1 << 23)
#define BMI055_ACC_HIGH_G_X_INT_STATUS_MASK UINT32_C(1 << 24)
#define BMI055_ACC_HIGH_G_Y_INT_STATUS_MASK UINT32_C(1 << 25)
#define BMI055_ACC_HIGH_G_Z_INT_STATUS_MASK UINT32_C(1 << 26)
#define BMI055_ACC_HIGH_G_SIGN_INT_STATUS_MASK UINT32_C(1 << 27)
#define BMI055_ACC_ORIENT_BIT_MASK UINT32_C(7 << 28)
#define BMI055_ACC_ORIENT_PORTRAIT_UPRIGHT_MASK UINT32_C(0 << 28)
#define BMI055_ACC_ORIENT_PORTRAIT_DOWN_MASK UINT32_C(1 << 28)
#define BMI055_ACC_ORIENT_LANDSACPE_LEFT_MASK UINT32_C(2 << 28)
#define BMI055_ACC_ORIENT_LANDSACPE_RIGHT_MASK UINT32_C(3 << 28)
#define BMI055_ACC_ORIENT_Z_AXIS_DIR_MASK UINT32_C(1 << 30)
#define BMI055_ACC_FLAT_INT_STATUS_MASK UINT32_C(1 << 31)
/*! BMI055 Accelerometer unique chip identifier */
#define BMI055_ACCEL_CHIP_ID UINT8_C(0xFA)
/*! BMI055 Accelerometer Bandwidth */
#define BMI055_ACCEL_BW_7_81_HZ UINT8_C(0x08)
#define BMI055_ACCEL_BW_15_63_HZ UINT8_C(0x09)
#define BMI055_ACCEL_BW_31_25_HZ UINT8_C(0x0A)
#define BMI055_ACCEL_BW_62_5_HZ UINT8_C(0x0B)
#define BMI055_ACCEL_BW_125_HZ UINT8_C(0x0C)
#define BMI055_ACCEL_BW_250_HZ UINT8_C(0x0D)
#define BMI055_ACCEL_BW_500_HZ UINT8_C(0x0E)
#define BMI055_ACCEL_BW_1000_HZ UINT8_C(0x0F)
/*! BMI055 Accelerometer Range */
#define BMI055_ACCEL_RANGE_2G UINT8_C(0x03)
#define BMI055_ACCEL_RANGE_4G UINT8_C(0x05)
#define BMI055_ACCEL_RANGE_8G UINT8_C(0x08)
#define BMI055_ACCEL_RANGE_16G UINT8_C(0x0C)
/*! BMI055 Accelerometer Power */
#define BMI055_ACCEL_PM_NORMAL UINT8_C(0x00)
#define BMI055_ACCEL_PM_DEEP_SUSPEND UINT8_C(0x01)
#define BMI055_ACCEL_PM_LOW_POWER UINT8_C(0x02)
#define BMI055_ACCEL_INVALID_POWER UINT8_C(0x03)
#define BMI055_ACCEL_PM_SUSPEND UINT8_C(0x04)
/*! Maximum limits definition */
#define BMI055_ACC_BW_MAX UINT8_C(0x1F)
#define BMI055_ACC_POWER_MAX UINT8_C(0x05)
/******************************************************************************/
/*! BMI055 Gyroscope Macros */
/******************************************************************************/
/*! Interrupt types of gyroscope */
/* Slope/ Any-motion interrupt */
#define BMI055_GYRO_ANY_MOTION_INT UINT8_C(0x00)
/* High-rate Interrupt */
#define BMI055_GYRO_HIGH_RATE_INT UINT8_C(0x01)
/* data-ready interrupt */
#define BMI055_GYRO_DATA_RDY_INT UINT8_C(0x02)
/* Auto-offset interrupt */
#define BMI055_GYRO_AUTO_OFFSET_INT UINT8_C(0x03)
/* Slow-offset interrupt */
#define BMI055_GYRO_SLOW_OFFSET_INT UINT8_C(0x04)
/* Fast-offset interrupt */
#define BMI055_GYRO_FAST_OFFSET_INT UINT8_C(0x05)
/*! Interrupt channels of gyroscope */
/* Interrupt Channel 3 for gyroscope sensor*/
#define BMI055_INT_CHANNEL_3 UINT8_C(0x00)
/* Interrupt Channel 4 for gyroscope sensor*/
#define BMI055_INT_CHANNEL_4 UINT8_C(0x01)
/*! Register map of Gyroscope registers */
#define BMI055_GYR_CHIP_ID_ADDR UINT8_C(0x00)
#define BMI055_GYR_X_L_ADDR UINT8_C(0x02)
#define BMI055_GYR_X_H_ADDR UINT8_C(0x03)
#define BMI055_GYR_Y_L_ADDR UINT8_C(0x04)
#define BMI055_GYR_Y_H_ADDR UINT8_C(0x05)
#define BMI055_GYR_Z_L_ADDR UINT8_C(0x06)
#define BMI055_GYR_Z_H_ADDR UINT8_C(0x07)
#define BMI055_GYR_INT_STATUS_0_ADDR UINT8_C(0x09)
#define BMI055_GYR_INT_STATUS_1_ADDR UINT8_C(0x0A)
#define BMI055_GYR_INT_STATUS_2_ADDR UINT8_C(0x0B)
#define BMI055_GYR_INT_STATUS_3_ADDR UINT8_C(0x0C)
#define BMI055_GYR_FIFO_STATUS_ADDR UINT8_C(0x0E)
#define BMI055_GYR_RANGE_ADDR UINT8_C(0x0F)
#define BMI055_GYR_BW_ADDR UINT8_C(0x10)
#define BMI055_GYR_LPM1_ADDR UINT8_C(0x11)
#define BMI055_GYR_LPM2_ADDR UINT8_C(0x12)
#define BMI055_GYR_RATE_HBW_ADDR UINT8_C(0x13)
#define BMI055_GYR_SOFTRESET_ADDR UINT8_C(0x14)
#define BMI055_GYR_INT_EN_0_ADDR UINT8_C(0x15)
#define BMI055_GYR_INT_EN_1_ADDR UINT8_C(0x16)
#define BMI055_GYR_INT_MAP_0_ADDR UINT8_C(0x17)
#define BMI055_GYR_INT_MAP_1_ADDR UINT8_C(0x18)
#define BMI055_GYR_INT_MAP_2_ADDR UINT8_C(0x19)
#define BMI055_GYRO_0_REG UINT8_C(0x1A)
#define BMI055_GYRO_1_REG UINT8_C(0x1B)
#define BMI055_GYRO_2_REG UINT8_C(0x1C)
#define BMI055_GYRO_3_REG UINT8_C(0x1E)
#define BMI055_GYR_INT_LATCH_ADDR UINT8_C(0x21)
#define BMI055_GYR_INT_HR_0_ADDR UINT8_C(0x22)
#define BMI055_GYR_INT_HR_1_ADDR UINT8_C(0x23)
#define BMI055_GYR_INT_HR_2_ADDR UINT8_C(0x24)
#define BMI055_GYR_INT_HR_3_ADDR UINT8_C(0x25)
#define BMI055_GYR_INT_HR_4_ADDR UINT8_C(0x26)
#define BMI055_GYR_INT_HR_5_ADDR UINT8_C(0x27)
#define BMI055_GYR_SOC_ADDR UINT8_C(0x31)
#define BMI055_GYR_A_FOC_ADDR UINT8_C(0x32)
#define BMI055_GYR_TRIM_NVM_CTRL_ADDR UINT8_C(0x33)
#define BMI055_BGW_SPI3_WDT_ADDR UINT8_C(0x34)
#define BMI055_GYR_OFFSET_COMP_ADDR UINT8_C(0x36)
#define BMI055_GYR_OFFSET_COMP_X_ADDR UINT8_C(0x37)
#define BMI055_GYR_OFFSET_COMP_Y_ADDR UINT8_C(0x38)
#define BMI055_GYR_OFFSET_COMP_Z_ADDR UINT8_C(0x39)
#define BMI055_GYR_TRIM_GPO_ADDR UINT8_C(0x3A)
#define BMI055_GYR_TRIM_GP1_ADDR UINT8_C(0x3B)
#define BMI055_GYR_SELFTEST_ADDR UINT8_C(0x3C)
#define BMI055_GYR_FIFO_CONFIG_0_ADDR UINT8_C(0x3D)
#define BMI055_GYR_FIFO_CONFIG_1_ADDR UINT8_C(0x3E)
#define BMI055_GYR_FIFO_DATA_ADDR UINT8_C(0x3F)
/*! Mask definitions for range, bandwidth and power */
#define BMI055_GYRO_RANGE_MASK UINT8_C(0x07)
#define BMI055_GYRO_BW_MASK UINT8_C(0x0F)
#define BMI055_GYRO_POWER_MASK UINT8_C(0xA0)
/*! Mask definitions for INT_EN 0 register */
#define BMI055_GYR_AUTO_OFF_INT_EN_0_MASK UINT8_C(0x04)
#define BMI055_GYR_FIFO_INT_EN_0_MASK UINT8_C(0x40)
#define BMI055_GYR_DATA_INT_EN_0_MASK UINT8_C(0x80)
/*! Mask definitions for INT_EN 1 register */
#define BMI055_GYR_INT1_LVL_INT_EN_1_MASK UINT8_C(0x01)
#define BMI055_GYR_INT1_OD_INT_EN_1_MASK UINT8_C(0x02)
#define BMI055_GYR_INT2_LVL_INT_EN_1_MASK UINT8_C(0x04)
#define BMI055_GYR_INT2_OD_INT_EN_1_MASK UINT8_C(0x08)
/*! Mask definitions for INT_MAP 0 register */
#define BMI055_GYR_INT1_MAP_0_ANY_MOT_MASK UINT8_C(0x02)
#define BMI055_GYR_INT1_MAP_0_HIGHRATE_MASK UINT8_C(0x08)
/*! Mask definitions for INT_MAP 1 register */
#define BMI055_GYR_INT1_MAP_1_DATA_MASK UINT8_C(0x01)
#define BMI055_GYR_INT1_MAP_1_FAST_OFF_MASK UINT8_C(0x02)
#define BMI055_GYR_INT1_MAP_1_FIFO_MASK UINT8_C(0x04)
#define BMI055_GYR_INT1_MAP_1_AUTO_OFF_MASK UINT8_C(0x08)
#define BMI055_GYR_INT2_MAP_1_AUTO_OFF_MASK UINT8_C(0x10)
#define BMI055_GYR_INT2_MAP_1_FIFO_MASK UINT8_C(0x20)
#define BMI055_GYR_INT2_MAP_1_FAST_OFF_MASK UINT8_C(0x40)
#define BMI055_GYR_INT2_MAP_1_DATA_MASK UINT8_C(0x80)
/*! Mask definitions for INT_MAP 2 register */
#define BMI055_GYR_INT2_MAP_2_ANY_MOT_MASK UINT8_C(0x02)
#define BMI055_GYR_INT2_MAP_2_HIGHRATE_MASK UINT8_C(0x08)
/*! Mask definitions for Data Source 0 Register */
#define BMI055_GYR_SRC_ANY_MOT_MASK UINT8_C(0x02)
#define BMI055_GYR_SRC_HIGHRATE_MASK UINT8_C(0x08)
#define BMI055_GYR_SRC_SLOW_OFFSET_MASK UINT8_C(0x20)
/*! Mask definitions for Data Source 1 Register */
#define BMI055_GYR_SRC_FAST_OFFSET_MASK UINT8_C(0x80)
/*! Mask definitions for INT_RST_LATCH */
#define BMI055_GYR_LATCH_DUR_MASK UINT8_C(0x0F)
#define BMI055_GYR_OFFSET_RESET_MASK UINT8_C(0x40)
#define BMI055_GYR_RESET_INT_MASK UINT8_C(0x80)
/*! Mask definitions for GYRO_3_REG */
#define BMI055_GYR_FIFO_WM_EN_MASK UINT8_C(0x80)
/*! Mask definitions for Any-motion Interrupt */
#define BMI055_GYR_ANY_THRES_MASK UINT8_C(0x7F)
#define BMI055_GYR_ANY_EN_X_MASK UINT8_C(0x01)
#define BMI055_GYR_ANY_EN_Y_MASK UINT8_C(0x02)
#define BMI055_GYR_ANY_EN_Z_MASK UINT8_C(0x04)
#define BMI055_GYR_ANY_DURSAMPLE_MASK UINT8_C(0x30)
#define BMI055_GYR_AWAKE_DUR_MASK UINT8_C(0xC0)
/*! Mask definitions for High-Rate Interrupt */
#define BMI055_GYR_HIGH_EN_X_MASK UINT8_C(0x01)
#define BMI055_GYR_HIGH_TH_X_MASK UINT8_C(0x3E)
#define BMI055_GYR_HIGH_HY_X_MASK UINT8_C(0xC0)
#define BMI055_GYR_HIGH_EN_Y_MASK UINT8_C(0x01)
#define BMI055_GYR_HIGH_TH_Y_MASK UINT8_C(0x3E)
#define BMI055_GYR_HIGH_HY_Y_MASK UINT8_C(0xC0)
#define BMI055_GYR_HIGH_EN_Z_MASK UINT8_C(0x01)
#define BMI055_GYR_HIGH_TH_Z_MASK UINT8_C(0x3E)
#define BMI055_GYR_HIGH_HY_Z_MASK UINT8_C(0xC0)
/*! Mask definitions for Auto-offset Interrupt */
#define BMI055_GYR_AUTO_OFF_WORD_LEN_MASK UINT8_C(0xC0)
/*! Mask definitions for Slow-offset Interrupt */
#define BMI055_GYR_SLOW_OFF_EN_X_MASK UINT8_C(0x01)
#define BMI055_GYR_SLOW_OFF_EN_Y_MASK UINT8_C(0x02)
#define BMI055_GYR_SLOW_OFF_EN_Z_MASK UINT8_C(0x04)
#define BMI055_GYR_SLOW_OFF_DUR_MASK UINT8_C(0x38)
#define BMI055_GYR_SLOW_OFF_THR_MASK UINT8_C(0xC0)
/*! Mask definitions for Fast-offset Interrupt */
#define BMI055_GYR_FAST_OFF_EN_X_MASK UINT8_C(0x01)
#define BMI055_GYR_FAST_OFF_EN_Y_MASK UINT8_C(0x02)
#define BMI055_GYR_FAST_OFF_EN_Z_MASK UINT8_C(0x04)
#define BMI055_GYR_FAST_OFF_EN_MASK UINT8_C(0x08)
#define BMI055_GYR_FAST_OFF_WORD_LEN_MASK UINT8_C(0x30)
/*! Mask definitions for FIFO Water-mark Interrupt */
#define BMI055_FIFO_WATERMARK_LEVEL_MASK UINT8_C(0x7F)
/*! BMI055 Gyroscope unique chip identifier */
#define BMI055_GYRO_CHIP_ID UINT8_C(0x0F)
/*! BMI055 Gyroscope Bandwidth */
#define BMI055_GYRO_BW_32_HZ UINT8_C(0x07)
#define BMI055_GYRO_BW_64_HZ UINT8_C(0x06)
#define BMI055_GYRO_BW_12_HZ UINT8_C(0x05)
#define BMI055_GYRO_BW_23_HZ UINT8_C(0x04)
#define BMI055_GYRO_BW_47_HZ UINT8_C(0x03)
#define BMI055_GYRO_BW_116_HZ UINT8_C(0x02)
#define BMI055_GYRO_BW_230_HZ UINT8_C(0x01)
#define BMI055_GYRO_BW_523_HZ UINT8_C(0x00)
/*! BMI055 Gyroscope range */
#define BMI055_GYRO_RANGE_2000_DPS UINT8_C(0x00)
#define BMI055_GYRO_RANGE_1000_DPS UINT8_C(0x01)
#define BMI055_GYRO_RANGE_500_DPS UINT8_C(0x02)
#define BMI055_GYRO_RANGE_250_DPS UINT8_C(0x03)
#define BMI055_GYRO_RANGE_125_DPS UINT8_C(0x04)
/*! BMI055 Gyroscope power */
#define BMI055_GYRO_PM_NORMAL UINT8_C(0x00)
#define BMI055_GYRO_PM_DEEP_SUSPEND UINT8_C(0x01)
#define BMI055_GYRO_PM_SUSPEND UINT8_C(0x02)
/******************************************************************************/
/*! Common macros for both accelerometer and gyroscope */
/******************************************************************************/
/*! Delay in ms settings */
#define BMI055_ONE_MS_DELAY UINT8_C(1)
/*! Interface settings */
#define BMI055_SPI_INTF UINT8_C(1)
#define BMI055_I2C_INTF UINT8_C(0)
/*! SPI read/write mask to configure address */
#define BMI055_SPI_RD_MASK UINT8_C(0x80)
#define BMI055_SPI_WR_MASK UINT8_C(0x7F)
/*! BMI055 I2C addresses */
#define BMI055_ACCEL_I2C_ADDR UINT8_C(0x18)
#define BMI055_GYRO_I2C_ADDR UINT8_C(0x68)
/*! Error Codes */
#define BMI055_OK INT8_C(0)
#define BMI055_E_NULL_PTR INT8_C(-1)
#define BMI055_E_COM_FAIL INT8_C(-2)
#define BMI055_E_DEV_NOT_FOUND INT8_C(-3)
#define BMI055_E_OUT_OF_RANGE INT8_C(-4)
#define BMI055_E_INVALID_INPUT INT8_C(-5)
#define BMI055_E_CONFIG_FAIL INT8_C(-6)
#define BMI055_E_INVALID_CHANNEL INT8_C(-6)
/*! Soft reset Value */
#define BMI055_SOFT_RESET_VAL UINT8_C(0xB6)
/*! Interrupt pin configuration macros */
/*! Open drain */
#define BMI055_INT_PIN_OPEN_DRAIN UINT8_C(0x01)
#define BMI055_INT_PIN_PUSH_PULL UINT8_C(0x00)
/*! Level */
#define BMI055_INT_PIN_ACTIVE_HIGH UINT8_C(0x01)
#define BMI055_INT_PIN_ACTIVE_LOW UINT8_C(0x00)
/*! Latch */
#define BMI055_INT_PIN_LATCH UINT8_C(0x01)
#define BMI055_INT_PIN_NON_LATCH UINT8_C(0x00)
/*! Reset */
#define BMI055_INT_LATCH_CLEAR UINT8_C(0x01)
#define BMI055_INT_LATCH_ACTIVE UINT8_C(0x00)
/*! Interrupt Latch duration */
#define BMI055_LATCH_DUR_NONE_1 UINT8_C(0x00)
#define BMI055_LATCH_DUR_250_MS UINT8_C(0x01)
#define BMI055_LATCH_DUR_500_MS UINT8_C(0x02)
#define BMI055_LATCH_DUR_1_S UINT8_C(0x03)
#define BMI055_LATCH_DUR_2_S UINT8_C(0x04)
#define BMI055_LATCH_DUR_4_S UINT8_C(0x05)
#define BMI055_LATCH_DUR_8_S UINT8_C(0x06)
#define BMI055_LATCHED_1 UINT8_C(0x07)
#define BMI055_LATCH_DUR_NONE_2 UINT8_C(0x08)
#define BMI055_LATCH_DUR_250_US UINT8_C(0x09)
#define BMI055_LATCH_DUR_500_US UINT8_C(0x0A)
#define BMI055_LATCH_DUR_1_MS UINT8_C(0x0B)
#define BMI055_LATCH_DUR_12_5_MS UINT8_C(0x0C)
#define BMI055_LATCH_DUR_25_MS UINT8_C(0x0D)
#define BMI055_LATCH_DUR_50_MS UINT8_C(0x0E)
#define BMI055_LATCHED_2 UINT8_C(0x0F)
/******************************************************************************/
/*! Function Pointers*/
/******************************************************************************/
/* For read and write communication through i2c or spi */
typedef int8_t (*bmi055_com_fptr_t)(uint8_t dev_addr, uint8_t reg_addr, uint8_t *data, uint16_t len);
/* For delay */
typedef void (*bmi055_delay_fptr_t)(uint32_t period);
/******************************************************************************/
/*! Data Structures */
/******************************************************************************/
/*! Structure to define x, y and z axis of the sensor */
struct bmi055_sensor_data {
/*! X-axis sensor data */
int16_t x;
/*! Y-axis sensor data */
int16_t y;
/*! Z-axis sensor data */
int16_t z;
};
/*! Structure to define bmi055 configuration details */
struct bmi055_cfg {
/*! power mode */
uint8_t power;
/*! range */
uint8_t range;
/*! bandwidth */
uint8_t bw;
};
/*! Structure to define bmi055 interrupt pin settings, for both
* little and big endian.
*/
struct bmi055_int_pin_sett {
#ifdef LITTLE_ENDIAN
/*! 0 - push-pull, 1 - open drain */
uint8_t output_mode : 1;
/*! 0 - active low, 1 - active high level */
uint8_t output_type : 1;
/*! 1 - clears any latched interrupts, 0 - keeps latched
interrupts active */
uint8_t reset_int : 1;
/*! 1 - resets offset value calculated with FastOffset,
SlowOffset & AutoOffset */
uint8_t offset_reset : 1;
/*! latch duration */
uint8_t latch_dur : 4;
#else
/*! latch duration */
uint8_t latch_dur : 4;
/*! 1 - resets offset value calculated with FastOffset,
SlowOffset & AutoOffset */
uint8_t offset_reset : 1;
/*! 1 - clears any latched interrupts, 0 - keeps latched
interrupts active */
uint8_t reset_int : 1;
/*! 0 - active low, 1 - active high level */
uint8_t output_type : 1;
/*! 0 - push-pull, 1 - open drain */
uint8_t output_mode : 1;
#endif
};
/*! Structure to define bmi055 accelerometer slope interrupt configurations,
* for both little and big endian.
*/
struct bmi055_acc_slop_int_cfg {
#ifdef LITTLE_ENDIAN
/*! slope interrupt, x-axis */
uint8_t slope_en_x : 1;
/*! slope interrupt, y-axis */
uint8_t slope_en_y : 1;
/*! slope interrupt, z-axis */
uint8_t slope_en_z : 1;
/*! slope duration */
uint8_t slope_dur : 2;
/*! slope threshold */
uint8_t slope_thr;
#else
/*! slope threshold */
uint8_t slope_thr;
/*! slope duration */
uint8_t slope_dur : 2;
/*! slope interrupt, z-axis */
uint8_t slope_en_z : 1;
/*! slope interrupt, y-axis */
uint8_t slope_en_y : 1;
/*! slope interrupt, x-axis */
uint8_t slope_en_x : 1;
#endif
};
/*! Structure to define bmi055 accelerometer tap interrupt configurations,
* for both little and big endian.
*/
struct bmi055_acc_tap_int_cfg {
#ifdef LITTLE_ENDIAN
/*! tap duration */
uint16_t tap_dur : 3;
/*! tap shock */
uint16_t tap_shock : 1;
/*! tap quiet */
uint16_t tap_quiet : 1;
/*! tap threshold */
uint16_t tap_thr : 5;
/*! tap sample */
uint16_t tap_sample : 2;
#else
/*! tap sample */
uint16_t tap_sample : 2;
/*! tap threshold */
uint16_t tap_thr : 5;
/*! tap quiet */
uint16_t tap_quiet : 1;
/*! tap shock */
uint16_t tap_shock : 1;
/*! tap duration */
uint16_t tap_dur : 3;
#endif
};
/*! Structure to define bmi055 accelerometer orient interrupt configurations,
* for both little and big endian.
*/
struct bmi055_acc_orient_int_cfg {
#ifdef LITTLE_ENDIAN
/*! Enable orientation interrupt */
uint16_t orient_en : 1;
/*! thresholds for switching between the different orientations */
uint16_t orient_mode : 2;
/*! blocking_mode */
uint16_t orient_blocking : 2;
/*! Orientation interrupt hysteresis */
uint16_t orient_hyst : 3;
/*! Orientation interrupt theta */
uint16_t orient_theta : 6;
/*! 1 / 0 - Enable/ disable Orientation interrupt */
uint16_t orient_ud_en : 1;
#else
/*! 1 / 0 - Enable/ disable Orientation interrupt */
uint16_t orient_ud_en : 1;
/*! Orientation interrupt theta */
uint16_t orient_theta : 6;
/*! Orientation interrupt hysteresis */
uint16_t orient_hyst : 3;
/*! blocking_mode */
uint16_t orient_blocking : 2;
/*! thresholds for switching between the different orientations */
uint16_t orient_mode : 2;
/*! Enable orientation interrupt */
uint16_t orient_en : 1;
#endif
};
/*! Structure to define bmi055 accelerometer flat detect interrupt
* configurations, for both little and big endian.
*/
struct bmi055_acc_flat_detect_int_cfg {
#ifdef LITTLE_ENDIAN
/*! flat threshold */
uint16_t flat_theta : 6;
/*! flat interrupt hysteresis */
uint16_t flat_hy : 3;
/*! delay time for which the flat value must remain stable
for the flat interrupt to be generated */
uint16_t flat_hold_time : 2;
#else
/*! delay time for which the flat value must remain stable
for the flat interrupt to be generated */
uint16_t flat_hold_time : 2;
/*! flat interrupt hysteresis */
uint16_t flat_hy : 3;
/*! flat threshold */
uint16_t flat_theta : 6;
#endif
};
/*! Structure to define bmi055 accelerometer low-g interrupt configurations,
* for both little and big endian.
*/
struct bmi055_acc_low_g_int_cfg {
#ifdef LITTLE_ENDIAN
/*! low-g interrupt enable */
uint8_t low_g_en : 1;
/*! low-g interrupt trigger delay */
uint8_t low_dur;
/*! low-g interrupt trigger threshold */
uint8_t low_thres;
/*! hysteresis of low-g interrupt */
uint8_t low_hyst : 2;
/*! 0 - single-axis mode, 1 - axis-summing mode */
uint8_t low_mode : 1;
#else
/*! 0 - single-axis mode, 1 - axis-summing mode */
uint8_t low_mode : 1;
/*! hysteresis of low-g interrupt */
uint8_t low_hyst : 2;
/*! low-g interrupt trigger threshold - ranges from 0 to 1992 mg*/
uint16_t low_thres;
/*! low-g interrupt trigger delay ranges from 2 to 512 msec */
uint16_t low_dur;
/*! low-g interrupt enable */
uint8_t low_g_en : 1;
#endif
};
/*! Structure to define bmi055 accelerometer high-g interrupt configurations,
* for both little and big endian.
*/
struct bmi055_acc_high_g_int_cfg {
#ifdef LITTLE_ENDIAN
/*! High-g interrupt x */
uint8_t high_g_en_x : 1;
/*! High-g interrupt y */
uint8_t high_g_en_y : 1;
/*! High-g interrupt z */
uint8_t high_g_en_z : 1;
/*! High-g hysteresis */
uint8_t high_hy : 2;
/*! High-g threshold */
uint8_t high_thres;
/*! High-g duration */
uint8_t high_dur;
#else
/*! High-g duration */
uint8_t high_dur;
/*! High-g threshold */
uint8_t high_thres;
/*! High-g hysteresis */
uint8_t high_hy : 2;
/*! High-g interrupt z */
uint8_t high_g_en_z : 1;
/*! High-g interrupt y */
uint8_t high_g_en_y : 1;
/*! High-g interrupt x */
uint8_t high_g_en_x : 1;
#endif
};
/*! Structure to define bmi055 accelerometer slow/no motion interrupt
* configurations, for both little and big endian.
*/
struct bmi055_acc_slow_no_mot_int_cfg {
#ifdef LITTLE_ENDIAN
/*! slow/ no motion interrupt, x-axis */
uint16_t slow_no_mot_en_x :1;
/*! slow/ no motion interrupt, y-axis */
uint16_t slow_no_mot_en_y :1;
/*! slow/ no motion interrupt, z-axis */
uint16_t slow_no_mot_en_z :1;
/*! 1 - enable no-motion, 0 - enable slow-motion */
uint16_t slow_no_mot_sel : 1;
/*! Slow motion duration */
uint16_t slow_mot_dur : 2;
/*! No motion duration */
uint16_t no_mot_dur : 6;
/*! slow/ no motion threshold */
uint8_t slow_no_mot_thres;
#else
/*! slow/ no motion threshold */
uint8_t slow_no_mot_thres;
/*! No motion duration */
uint16_t no_mot_dur : 6;
/*! Slow motion duration */
uint16_t slow_mot_dur : 2;
/*! 1 - enable no-motion, 0 - enable slow-motion */
uint16_t slow_no_mot_sel : 1;
/*! slow/no motion interrupt, z-axis */
uint16_t slow_no_mot_en_z :1;
/*! slow/no motion interrupt, y-axis */
uint16_t slow_no_mot_en_y :1;
/*! slow/no motion interrupt, x-axis */
uint16_t slow_no_mot_en_x :1;
#endif
};
/*! Structure to define bmi055 gyroscope any motion interrupt configurations,
* for both little and big endian.
*/
struct bmi055_gyr_any_mot_int_cfg {
#ifdef LITTLE_ENDIAN
/*! any motion interrupt, x-axis */
uint8_t any_en_x : 1;
/*! any motion interrupt, y-axis */
uint8_t any_en_y : 1;
/*! any motion interrupt, z-axis */
uint8_t any_en_z : 1;
/*! any motion sample duration */
uint8_t any_dursample : 2;
/*! awake duration */
uint8_t awake_dur : 2;
/*! any motion threshold */
uint8_t any_thr;
#else
/*! any motion threshold */
uint8_t any_thr;
/*! awake duration */
uint8_t awake_dur : 2;
/*! any motion sample duration */
uint8_t any_dursample : 2;
/*! any motion interrupt, z-axis */
uint8_t any_en_z : 1;
/*! any motion interrupt, y-axis */
uint8_t any_en_y : 1;
/*! any motion interrupt, x-axis */
uint8_t any_en_x : 1;
#endif
};
/*! Structure to define bmi055 gyroscope high rate interrupt configurations,
* for both little and big endian.
*/
struct bmi055_gyr_high_rate_int_cfg {
#ifdef LITTLE_ENDIAN
/*! 1 / 0 - enables/disables high-rate interrupt for x-axis */
uint8_t high_en_x : 1;
/*! high rate threshold for x-axis */
uint8_t high_thr_x : 5;
/*! high rate hysteresis for x-axis*/
uint8_t high_hy_x : 2;
/*! High rate duration for x-axis*/
uint8_t high_dur_x;
/*! 1 / 0 - enables/disables high-rate interrupt for y-axis */
uint8_t high_en_y : 1;
/*! high rate threshold for y-axis */
uint8_t high_thr_y : 5;
/*! high rate hysteresis for y-axis*/
uint8_t high_hy_y : 2;
/*! High rate duration for y-axis*/
uint8_t high_dur_y;
/*! 1 / 0 - enables/disables high-rate interrupt for z-axis */
uint8_t high_en_z : 1;
/*! high rate threshold for z-axis */
uint8_t high_thr_z : 5;
/*! high rate hysteresis for z-axis*/
uint8_t high_hy_z : 2;
/*! High rate duration for z-axis*/
uint8_t high_dur_z;
#else
/*! High rate duration for z-axis*/
uint8_t high_dur_z;
/*! high rate hysteresis for z-axis*/
uint8_t high_hy_z : 2;
/*! high rate threshold for z-axis */
uint8_t high_thr_z : 5;
/*! 1 / 0 - enables/disables high-rate interrupt for z-axis */
uint8_t high_en_z : 1;
/*! High rate duration for y-axis*/
uint8_t high_dur_y;
/*! high rate hysteresis for y-axis*/
uint8_t high_hy_y : 2;
/*! high rate threshold for y-axis */
uint8_t high_thr_y : 5;
/*! 1 / 0 - enables/disables high-rate interrupt for y-axis */
uint8_t high_en_y : 1;
/*! High rate duration for x-axis*/
uint8_t high_dur_x;
/*! high rate hysteresis for x-axis*/
uint8_t high_hy_x : 2;
/*! high rate threshold for x-axis */
uint8_t high_thr_x : 5;
/*! 1 / 0 - enables/disables high-rate interrupt for x-axis */
uint8_t high_en_x : 1;
#endif
};
/*! Structure to define bmi055 gyroscope auto offset interrupt configurations,
* for both little and big endian.
*/
struct bmi055_gyr_auto_offset_int_cfg {
/*! Auto-offset word length */
uint8_t auto_offset_wordlen;
};
struct bmi055_gyr_slow_offset_int_cfg {
#ifdef LITTLE_ENDIAN
/*! 1 / 0 - enables/disables slow offset compensation for x-axis */
uint8_t slow_offset_en_x : 1;
/*! 1 / 0 - enables/disables slow offset compensation for y-axis */
uint8_t slow_offset_en_y : 1;
/*! 1 / 0 - enables/disables slow offset compensation for z-axis */
uint8_t slow_offset_en_z : 1;
/*! Slow offset duration */
uint8_t slow_offset_dur : 3;
/*! Slow_offset threshold */
uint8_t slow_offset_thres : 2;
#else
/*! Slow_offset threshold */
uint8_t slow_offset_thres : 2;
/*! Slow offset duration */
uint8_t slow_offset_dur : 3;
/*! 1 / 0 - enables/disables slow offset compensation for z-axis */
uint8_t slow_offset_en_z : 1;
/*! 1 / 0 - enables/disables slow offset compensation for y-axis */
uint8_t slow_offset_en_y : 1;
/*! 1 / 0 - enables/disables slow offset compensation for x-axis */
uint8_t slow_offset_en_x : 1;
#endif
};
/*! Structure to define bmi055 gyroscope fast offset interrupt configurations,
* for both little and big endian.
*/
struct bmi055_gyr_fast_offset_int_cfg {
#ifdef LITTLE_ENDIAN
/*! 1 / 0 - enables/disables fast offset compensation for x-axis */
uint8_t fast_offset_en_x : 1;
/*! 1 / 0 - enables/disables fast offset compensation for y-axis */
uint8_t fast_offset_en_y : 1;
/*! 1 / 0 - enables/disables fast offset compensation for z-axis */
uint8_t fast_offset_en_z : 1;
/*! triggers fast offset compensation for the enabled axes */
uint8_t fast_offset_en : 1;
/*! fast_offset wordlength */
uint8_t fast_offset_wordlen : 2;
#else
/*! fast_offset wordlength */
uint8_t fast_offset_wordlen : 2;
/*! triggers fast offset compensation for the enabled axes */
uint8_t fast_offset_en : 1;
/*! 1 / 0 - enables/disables fast offset compensation for z-axis */
uint8_t fast_offset_en_z : 1;
/*! 1 / 0 - enables/disables fast offset compensation for y-axis */
uint8_t fast_offset_en_y : 1;
/*! 1 / 0 - enables/disables fast offset compensation for x-axis */
uint8_t fast_offset_en_x : 1;
#endif
};
/*!
* Union that defines bmi055 structures for accelerometer interrupt
* configurations.
*/
union bmi055_accel_int_type_cfg {
/*! New data enable */
uint8_t accel_new_data_en;
/*! Tap interrupt structure */
struct bmi055_acc_tap_int_cfg acc_tap_int;
/*! Slope/ Any motion interrupt structure */
struct bmi055_acc_slop_int_cfg acc_slope_int;
/*! No-motion/ Slow motion interrupt structure */
struct bmi055_acc_slow_no_mot_int_cfg acc_slow_no_mot_int;
/*! Orientation interrupt structure */
struct bmi055_acc_orient_int_cfg acc_orient_int;
/*! Flat interrupt structure */
struct bmi055_acc_flat_detect_int_cfg acc_flat_int;
/*! Low-g interrupt structure */
struct bmi055_acc_low_g_int_cfg acc_low_g_int;
/*! High-g interrupt structure */
struct bmi055_acc_high_g_int_cfg acc_high_g_int;
};
/*!
* Union that defines bmi055 structures for gyroscope interrupt configurations.
*/
union bmi055_gyro_int_type_cfg {
/*! New data enable */
uint8_t gyro_new_data_en;
/*! Any-motion interrupt structure */
struct bmi055_gyr_any_mot_int_cfg gyr_any_mot_int;
/*! High-Rate interrupt structure */
struct bmi055_gyr_high_rate_int_cfg gyr_high_rate_int;
/*! Auto-Offset interrupt structure */
struct bmi055_gyr_auto_offset_int_cfg gyr_auto_offset_int;
/*! Slow-Offset interrupt structure */
struct bmi055_gyr_slow_offset_int_cfg gyr_slow_offset_int;
/*! Fast-Offset interrupt structure */
struct bmi055_gyr_fast_offset_int_cfg gyr_fast_offset_int;
};
/*!
* Structure to define bmi055 accelerometer interrupt settings
*/
struct bmi055_accel_int_sett {
/*! Select Interrupt channel */
uint8_t acc_int_channel;
/*! Select Interrupt type */
uint8_t acc_int_types;
/*! Select interrupt source type */
uint8_t int_data_src_type;
/*! Structure configuring Interrupt pins */
struct bmi055_int_pin_sett int_pin_sett;
/*! Union configures required interrupt */
union bmi055_accel_int_type_cfg acc_int_type_cfg;
};
/*!
* Structure to define bmi055 gyroscope interrupt settings
*/
struct bmi055_gyro_int_sett {
/*! Select Interrupt channel */
uint8_t gyr_int_channel;
/*! Select Interrupt type */
uint8_t gyr_int_types;
/*! Select interrupt source type */
uint8_t int_data_src_type;
/*! Structure configuring Interrupt pins */
struct bmi055_int_pin_sett int_pin_sett;
/*! Union configures required interrupt */
union bmi055_gyro_int_type_cfg gyro_int_type_cfg;
};
/*!
* Structure to define bmi055 sensor configurations
*/
struct bmi055_dev {
/*! Accel chip Id */
uint8_t accel_chip_id;
/*! Gyro chip Id */
uint8_t gyro_chip_id;
/*! Accel device Id */
uint8_t accel_id;
/*! Gyro device Id */
uint8_t gyro_id;
/*! 0 - I2C , 1 - SPI Interface */
uint8_t interface;
/*! Structure to configure accelerometer sensor */
struct bmi055_cfg accel_cfg;
/*! Structure to configure gyroscope sensor */
struct bmi055_cfg gyro_cfg;
/*! Read function pointer */
bmi055_com_fptr_t read;
/*! Write function pointer */
bmi055_com_fptr_t write;
/*! Delay function pointer */
bmi055_delay_fptr_t delay_ms;
};
/******************************************************************************/
/*! C++ Guard Macros */
/******************************************************************************/
#ifdef __cplusplus
}
#endif
#endif /* BMI055_DEFS_H_ */
/*
*
****************************************************************************
* Copyright (C) 2015 - 2016 Bosch Sensortec GmbH
*
* File : bmi088.h
*
* Date: 30 Oct 2017
*
* Revision: $
*
* Usage: Sensor Driver for BMI088 family of sensors
*
****************************************************************************
*
* Disclaimer
*
* Common:
* Bosch Sensortec products are developed for the consumer goods industry.
* They may only be used within the parameters of the respective valid
* product data sheet. Bosch Sensortec products are provided with the
* express understanding that there is no warranty of fitness for a
* particular purpose.They are not fit for use in life-sustaining,
* safety or security sensitive systems or any system or device
* that may lead to bodily harm or property damage if the system
* or device malfunctions. In addition,Bosch Sensortec products are
* not fit for use in products which interact with motor vehicle systems.
* The resale and or use of products are at the purchasers own risk and
* his own responsibility. The examination of fitness for the intended use
* is the sole responsibility of the Purchaser.
*
* The purchaser shall indemnify Bosch Sensortec from all third party
* claims, including any claims for incidental, or consequential damages,
* arising from any product use not covered by the parameters of
* the respective valid product data sheet or not approved by
* Bosch Sensortec and reimburse Bosch Sensortec for all costs in
* connection with such claims.
*
* The purchaser must monitor the market for the purchased products,
* particularly with regard to product safety and inform Bosch Sensortec
* without delay of all security relevant incidents.
*
* Engineering Samples are marked with an asterisk (*) or (e).
* Samples may vary from the valid technical specifications of the product
* series. They are therefore not intended or fit for resale to third
* parties or for use in end products. Their sole purpose is internal
* client testing. The testing of an engineering sample may in no way
* replace the testing of a product series. Bosch Sensortec assumes
* no liability for the use of engineering samples.
* By accepting the engineering samples, the Purchaser agrees to indemnify
* Bosch Sensortec from all claims arising from the use of engineering
* samples.
*
* Special:
* This software module (hereinafter called "Software") and any information
* on application-sheets (hereinafter called "Information") is provided
* free of charge for the sole purpose to support your application work.
* The Software and Information is subject to the following
* terms and conditions:
*
* The Software is specifically designed for the exclusive use for
* Bosch Sensortec products by personnel who have special experience
* and training. Do not use this Software if you do not have the
* proper experience or training.
*
* This Software package is provided `` as is `` and without any expressed
* or implied warranties,including without limitation, the implied warranties
* of merchantability and fitness for a particular purpose.
*
* Bosch Sensortec and their representatives and agents deny any liability
* for the functional impairment
* of this Software in terms of fitness, performance and safety.
* Bosch Sensortec and their representatives and agents shall not be liable
* for any direct or indirect damages or injury, except as
* otherwise stipulated in mandatory applicable law.
*
* The Information provided is believed to be accurate and reliable.
* Bosch Sensortec 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 Bosch. Specifications mentioned in the Information are
* subject to change without notice.
**************************************************************************/
/*! \file bmi088.h
\brief Sensor Driver for BMI088 family of sensors */
#ifndef BMI088_H_
#define BMI088_H_
#ifdef __cplusplus
extern "C"
{
#endif
/*********************************************************************/
/* header files */
#include "bmi088_defs.h"
/*********************************************************************/
/* (extern) variable declarations */
/*********************************************************************/
/* function prototype declarations */
/*********************** BMI088 Accelerometer function prototypes ************************/
/*!
* @brief This API is the entry point for accel sensor.
* It performs the selection of I2C/SPI read mechanism according to the
* selected interface and reads the chip-id of accel sensor.
*
* @param[in,out] dev : Structure instance of bmi088_dev.
* @note : Refer user guide for detailed info.
*
* @return Result of API execution status
* @retval zero -> Success
* @retval Any non zero value -> Fail
*/
uint16_t bmi088_accel_init(struct bmi088_dev *dev);
/*!
* @brief This API is used to write the binary configuration in the sensor
*
* @param[in] dev : Structure instance of bmi088_dev.
*
* @return Result of API execution status
* @retval 0 -> Success
* @retval Any non zero value -> Fail
*
*/
uint16_t bmi088_write_config_file(struct bmi088_dev *dev);
/*!
* @brief This API reads the data from the given register address of accel sensor.
*
* @param[in] reg_addr : Register address from where the data to be read
* @param[out] data : Pointer to data buffer to store the read data.
* @param[in] len : No. of bytes of data to be read.
* @param[in] dev : Structure instance of bmi088_dev.
*
* @return Result of API execution status
* @retval zero -> Success
* @retval Any non zero value -> Fail
*/
uint16_t bmi088_get_accel_regs(uint8_t reg_addr, uint8_t *data, uint16_t len, struct bmi088_dev *dev);
/*!
* @brief This API writes the given data to the register address
* of accel sensor.
*
* @param[in] reg_addr : Register address to where the data to be written.
* @param[in] data : Pointer to data buffer which is to be written
* in the sensor.
* @param[in] len : No. of bytes of data to write.
* @param[in] dev : Structure instance of bmi088_dev.
*
* @return Result of API execution status
* @retval zero -> Success
* @retval Any non zero value -> Fail
*/
uint16_t bmi088_set_accel_regs(uint8_t reg_addr, uint8_t *data, uint16_t len, struct bmi088_dev *dev);
/*!
* @brief This API reads the error status from the accel sensor.
*
* Below table mention the types of error which can occur in the sensor
*@verbatim
*************************************************************************
* Error | Description
*************************|***********************************************
* | Fatal Error, chip is not in operational
* fatal | state (Boot-, power-system).
* | This flag will be reset only by
* | power-on-reset or soft reset.
*************************|***********************************************
* cmd | Command execution failed.
*************************|***********************************************
* | Value Name Description
* error_code | 000 no_error no error
* | 001 accel_err error in
* | ACCEL_CONF
*************************************************************************
*@endverbatim
*
* @param[in,out] err_reg : Pointer to structure variable which stores the
* error status read from the sensor.
* @param[in] dev : Structure instance of bmi088_dev.
*
* @return Result of API execution status
* @retval 0 -> Success
* @retval Any non zero value -> Fail
*/
uint16_t bmi088_get_accel_error_status(struct bmi088_err_reg *err_reg, struct bmi088_dev *dev);
/*!
* @brief This API reads the status of the accel sensor.
*
* Below table lists the sensor status flags
*@verbatim
*************************************************************************
* Status | Description
***********************************|*************************************
* drdy_accel | Data ready for Accel.
*************************************************************************
*@endverbatim
*
* @param[in] status : Variable used to store the sensor status flags
* which is read from the sensor.
* @param[in] dev : Structure instance of bmi088_dev.
*
* @return Result of API execution status
* @retval 0 -> Success
* @retval Any non zero value -> Fail
*
*/
uint16_t bmi088_get_accel_status(uint8_t *status, struct bmi088_dev *dev);
/*!
* @brief This API resets the accel sensor.
*
* @param[in] dev : Structure instance of bmi088_dev.
*
* @return Result of API execution status
* @retval zero -> Success
* @retval Any non zero value -> Fail
*/
uint16_t bmi088_accel_soft_reset(struct bmi088_dev *dev);
/*!
* @brief This API sets the Output data rate, range and bandwidth
* of accel sensor.
*
* @param[in] dev : Structure instance of bmi088_dev.
* @note : Refer user guide for detailed info.
*
* @return Result of API execution status
* @retval zero -> Success
* @retval Any non zero value -> Fail
*/
uint16_t bmi088_set_accel_meas_conf(struct bmi088_dev *dev);
/*!
* @brief This API sets the power mode of the accel sensor.
*
* @param[in] dev : Structure instance of bmi088_dev.
*
* @return Result of API execution status
* @retval zero -> Success
* @retval Any non zero value -> Fail
*/
uint16_t bmi088_set_accel_power_mode(struct bmi088_dev *dev);
/*!
* @brief This API reads the accel data from the sensor,
* store it in the bmi088_sensor_data structure instance
* passed by the user.
*
* @param[out] accel : Structure pointer to store accel data
* @param[in] dev : Structure instance of bmi088_dev.
*
*
* @return Result of API execution status
* @retval zero -> Success
* @retval Any non zero value -> Fail
*/
uint16_t bmi088_get_accel_data(struct bmi088_sensor_data *accel, struct bmi088_dev *dev);
/*!
* @brief This API configures the necessary accel interrupt
* based on the user settings in the bmi088_int_cfg
* structure instance.
*
* @param[in] int_config : Structure instance of bmi088_int_cfg.
* @param[in] dev : Structure instance of bmi088_dev.
* @note : Refer user guide for detailed info.
*
* @return Result of API execution status
* @retval zero -> Success
* @retval Any non zero value -> Fail
*/
uint16_t bmi088_set_accel_int_config(const struct bmi088_int_cfg *int_config, struct bmi088_dev *dev);
/*!
* @brief This API switches accel sensor on or off.
*
* @param[in] dev : Structure instance of bmi088_dev.
* @param[in] switch_input : Input to switch accel on or off
* Value | Description
* ---------|--------------------
* 0 | BMI088_ACCEL_POWER_DISABLE
* 4 | BMI088_ACCEL_POWER_ENABLE
*
*
* @return Result of API execution status
* @retval zero -> Success
* @retval Any non zero value -> Fail
*/
uint16_t bmi088_accel_switch_control(struct bmi088_dev *dev, uint8_t switch_input);
/*!
* @brief This API reads the temperature of the sensor in ° Celcius.
*
* @param[in] dev : Structure instance of bmi088_dev.
* @param[out] sensor_temp : Pointer to store sensor temperature in ° Celcius
*
* @return Result of API execution status
* @retval zero -> Success
* @retval Any non zero value -> Fail
*/
uint16_t bmi088_get_sensor_temperature(struct bmi088_dev *dev, float *sensor_temp);
/*!
* @brief This API reads the sensor time of the sensor.
*
* @param[in] dev : Structure instance of bmi088_dev.
* @param[out] sensor_time : Pointer to store sensor time
*
* @return Result of API execution status
* @retval zero -> Success
* @retval Any non zero value -> Fail
*/
uint16_t bmi088_get_sensor_time(struct bmi088_dev *dev, uint32_t *sensor_time);
/*!
* @brief This API checks whether the self test functionality of the sensor
* is working or not
*
* @param[in] result : Pointer variable used to store the result of self test
* operation.
* result | Description
* ---------|--------------------
* 0 | BMI088_SELFTEST_PASS
* -1 | BMI088_SELFTEST_FAIL
*
* @param[in] dev : Structure instance of bmi088_dev
*
* @return results of self test
* @retval 0 -> Success
* @retval Any non zero value -> Fail
*/
uint16_t bmi088_perform_accel_selftest(int8_t *result, struct bmi088_dev *dev);
/*!
* @brief This API enables or disables the Accel Self test feature in the
* sensor.
*
* @param[in] selftest : Variable used to enable or disable
* the Accel self test feature
* Value | Description
* --------|---------------
* 0x00 | BMI088_ACCEL_SWITCH_OFF_SELF_TEST
* 0x0D | BMI088_ACCEL_POSITIVE_SELF_TEST
* 0x09 | BMI088_ACCEL_NEGATIVE_SELF_TEST
*
* @param[in] dev : Structure instance of bmi088_dev
*
* @return Result of API execution status
* @retval 0 -> Success
* @retval Any non zero value -> Fail
*/
uint16_t bmi088_set_accel_selftest(uint8_t selftest, struct bmi088_dev *dev);
/*********************** BMI088 Gyroscope function prototypes ************************/
/*!
* @brief This API is the entry point for gyro sensor.
* It performs the selection of I2C/SPI read mechanism according to the
* selected interface and reads the chip-id of gyro sensor.
*
* @param[in,out] dev : Structure instance of bmi088_dev.
* @note : Refer user guide for detailed info.
*
* @return Result of API execution status
* @retval zero -> Success
* @retval Any non zero value -> Fail
*/
uint16_t bmi088_gyro_init(struct bmi088_dev *dev);
/*!
* @brief This API reads the data from the given register address of gyro sensor.
*
* @param[in] reg_addr : Register address from where the data to be read
* @param[out] data : Pointer to data buffer to store the read data.
* @param[in] len : No. of bytes of data to be read.
* @param[in] dev : Structure instance of bmi088_dev.
*
* @return Result of API execution status
* @retval zero -> Success
* @retval Any non zero value -> Fail
*/
uint16_t bmi088_get_gyro_regs(uint8_t reg_addr, uint8_t *data, uint16_t len, struct bmi088_dev *dev);
/*!
* @brief This API writes the given data to the register address
* of gyro sensor.
*
* @param[in] reg_addr : Register address to where the data to be written.
* @param[in] data : Pointer to data buffer which is to be written
* in the sensor.
* @param[in] len : No. of bytes of data to write.
* @param[in] dev : Structure instance of bmi088_dev.
*
* @return Result of API execution status
* @retval zero -> Success
* @retval Any non zero value -> Fail
*/
uint16_t bmi088_set_gyro_regs(uint8_t reg_addr, uint8_t *data, uint16_t len, struct bmi088_dev *dev);
/*!
* @brief This API resets the gyro sensor.
*
* @param[in] dev : Structure instance of bmi088_dev.
*
* @return Result of API execution status
* @retval zero -> Success
* @retval Any non zero value -> Fail
*/
uint16_t bmi088_gyro_soft_reset(struct bmi088_dev *dev);
/*!
* @brief This API sets the output data rate, range and bandwidth
* of gyro sensor.
*
* @param[in] dev : Structure instance of bmi088_dev.
* @note : Refer user guide for detailed info.
*
* @return Result of API execution status
* @retval zero -> Success
* @retval Any non zero value -> Fail
*/
uint16_t bmi088_set_gyro_meas_conf(struct bmi088_dev *dev);
/*!
* @brief This API sets the power mode of the gyro sensor.
*
* @param[in] dev : Structure instance of bmi088_dev.
*
* @return Result of API execution status
* @retval zero -> Success
* @retval Any non zero value -> Fail
*/
uint16_t bmi088_set_gyro_power_mode(struct bmi088_dev *dev);
/*!
* @brief This API reads the gyro data from the sensor,
* store it in the bmi088_sensor_data structure instance
* passed by the user.
*
* @param[out] gyro : Structure pointer to store gyro data
* @param[in] dev : Structure instance of bmi088_dev.
*
* @return Result of API execution status
* @retval zero -> Success
* @retval Any non zero value -> Fail
*/
uint16_t bmi088_get_gyro_data(struct bmi088_sensor_data *gyro, struct bmi088_dev *dev);
/*!
* @brief This API configures the necessary gyro interrupt
* based on the user settings in the bmi088_int_cfg
* structure instance.
*
* @param[in] int_config : Structure instance of bmi088_int_cfg.
* @param[in] dev : Structure instance of bmi088_dev.
* @note : Refer user guide for detailed info.
*
* @return Result of API execution status
* @retval zero -> Success
* @retval Any non zero value -> Fail
*/
uint16_t bmi088_set_gyro_int_config(const struct bmi088_int_cfg *int_config, struct bmi088_dev *dev);
/*!
* @brief This API enables or disables the Gyro Self test feature in the
* sensor.
*
* @param[in] selftest : Variable used to enable or disable
* the Gyro self test feature
* Value | Description
* --------|---------------
* 0x00 | BMI088_DISABLE
* 0x01 | BMI088_ENABLE
*
* @param[in] dev : Structure instance of bmi088_dev
*
* @return Result of API execution status
* @retval 0 -> Success
* @retval Any non zero value -> Fail
*
*/
uint16_t bmi088_set_gyro_selftest(uint8_t selftest, struct bmi088_dev *dev);
/*!
* @brief This API checks whether the self test functionality of the
* gyro sensor is working or not
*
* @param[in] result : Pointer variable used to store the result of
* self test operation
* result | Description
* ---------|--------------------
* 0 | BMI088_SELFTEST_PASS
* -1 | BMI088_SELFTEST_FAIL
*
* @param[in] dev : Structure instance of bmi088_dev.
*
* @return Result of API execution status
* @retval zero -> Success
* @retval Any non zero value -> Fail
*/
uint16_t bmi088_perform_gyro_selftest(int8_t *result, struct bmi088_dev *dev);
#ifdef __cplusplus
}
#endif
#endif
/* End of BMI088_H_ */
/**
* Copyright (C) 2015 - 2016 Bosch Sensortec GmbH
*
* 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.
*
* @file bmi088_defs.h
* @date Oct 5, 2016
* @version
* @brief
*
*/
/*!
* @defgroup bmi088_defs
* @brief
* @{*/
#ifndef BMI088_DEFS_H_
#define BMI088_DEFS_H_
/*********************************************************************/
/**\ header files */
#ifdef __KERNEL__
#include <linux/types.h>
#else
#include <stdint.h>
#include <stddef.h>
#include <stdbool.h>
#endif
/*********************************************************************/
/* macro definitions */
#ifdef __cplusplus
extern "C"
{
#endif
/*
#if (LONG_MAX) > 0x7fffffff
#define __have_long64 1
#elif (LONG_MAX) == 0x7fffffff
#define __have_long32 1
#endif
*/
#if !defined(UINT8_C)
#define INT8_C(x) x
#if (INT_MAX) > 0x7f
#define UINT8_C(x) x
#else
#define UINT8_C(x) x##U
#endif
#endif
#if !defined(UINT16_C)
#define INT16_C(x) x
#if (INT_MAX) > 0x7fff
#define UINT16_C(x) x
#else
#define UINT16_C(x) x##U
#endif
#endif
#if !defined(INT32_C) && !defined(UINT32_C)
#if __have_long32
#define INT32_C(x) x##L
#define UINT32_C(x) x##UL
#else
#define INT32_C(x) x
#define UINT32_C(x) x##U
#endif
#endif
#if !defined(INT64_C) && !defined(UINT64_C)
#if __have_long64
#define INT64_C(x) x##L
#define UINT64_C(x) x##UL
#else
#define INT64_C(x) x##LL
#define UINT64_C(x) x##ULL
#endif
#endif
/*************************** Sensor macros *****************************/
/* Test for an endian machine */
#if __BYTE_ORDER__ == __ORDER_LITTLE_ENDIAN__
#define LITTLE_ENDIAN 1
#elif __BYTE_ORDER__ == __ORDER_BIG_ENDIAN__
#define BIG_ENDIAN 1
#else
#error "Code does not support Endian format of the processor"
#endif
/*************************** BMI088 Accelerometer Macros *****************************/
/** Register map */
/* Accel registers */
/**\name Accel Chip Id register */
#define BMI088_ACCEL_CHIP_ID_REG UINT8_C(0x00)
/**\name Accel Error condition register */
#define BMI088_ACCEL_ERR_REG UINT8_C(0x02)
/**\name Accel Status flag register */
#define BMI088_ACCEL_STATUS_REG UINT8_C(0x03)
/**\name Accel X LSB data register */
#define BMI088_ACCEL_X_LSB_REG UINT8_C(0x12)
/**\name Accel X MSB data register */
#define BMI088_ACCEL_X_MSB_REG UINT8_C(0x13)
/**\name Accel Y LSB data register */
#define BMI088_ACCEL_Y_LSB_REG UINT8_C(0x14)
/**\name Accel Y MSB data register */
#define BMI088_ACCEL_Y_MSB_REG UINT8_C(0x15)
/**\name Accel Z LSB data register */
#define BMI088_ACCEL_Z_LSB_REG UINT8_C(0x16)
/**\name Accel Z MSB data register */
#define BMI088_ACCEL_Z_MSB_REG UINT8_C(0x17)
/**\name Sensor time byte 0 register */
#define BMI088_ACCEL_SENSORTIME_0_REG UINT8_C(0x18)
/**\name Sensor time byte 1 register */
#define BMI088_ACCEL_SENSORTIME_1_REG UINT8_C(0x19)
/**\name Sensor time byte 2 register */
#define BMI088_ACCEL_SENSORTIME_2_REG UINT8_C(0x1A)
/**\name Accel Interrupt status register */
#define BMI088_ACCEL_INT_STAT_1_REG UINT8_C(0x1D)
/**\name Sensor temperature MSB data register */
#define BMI088_TEMP_MSB_REG UINT8_C(0x22)
/**\name Sensor temperature LSB data register */
#define BMI088_TEMP_LSB_REG UINT8_C(0x23)
/**\name Accel Fifo Length 0 register */
#define BMI088_ACCEL_FIFO_LENGTH_0_REG UINT8_C(0x24)
/**\name Accel Fifo Length 1 register */
#define BMI088_ACCEL_FIFO_LENGTH_1_REG UINT8_C(0x25)
/**\name Accel Fifo data register */
#define BMI088_ACCEL_FIFO_DATA_REG UINT8_C(0x26)
/**\name Accel Internal status register */
#define BMI088_ACCEL_INTERNAL_STAT_REG UINT8_C(0x2A)
/**\name Accel configuration register */
#define BMI088_ACCEL_CONF_REG UINT8_C(0x40)
/**\name Accel range setting register */
#define BMI088_ACCEL_RANGE_REG UINT8_C(0x41)
/**\name Accel Fifo Down register */
#define BMI088_ACCEL_FIFO_DOWN_REG UINT8_C(0x45)
/**\name Accel Fifo Watermark 0 register */
#define BMI088_ACCEL_FIFO_WTM_0_REG UINT8_C(0x46)
/**\name Accel Fifo Watermark 1 register */
#define BMI088_ACCEL_FIFO_WTM_1_REG UINT8_C(0x47)
/**\name Accel Fifo Config 0 register */
#define BMI088_ACCEL_FIFO_CONFIG_0_REG UINT8_C(0x48)
/**\name Accel Fifo Config 1 register */
#define BMI088_ACCEL_FIFO_CONFIG_1_REG UINT8_C(0x49)
/**\name Accel Interrupt pin 1 configuration register */
#define BMI088_ACCEL_INT1_IO_CONF_REG UINT8_C(0x53)
/**\name Accel Interrupt pin 2 configuration register */
#define BMI088_ACCEL_INT2_IO_CONF_REG UINT8_C(0x54)
/**\name Accel Interrupt map register */
#define BMI088_ACCEL_INT1_INT2_MAP_DATA_REG UINT8_C(0x58)
/**\name Accel Init control register */
#define BMI088_ACCEL_INIT_CTRL_REG UINT8_C(0x59)
/**\name Accel Self test register */
#define BMI088_ACCEL_SELF_TEST_REG UINT8_C(0x6D)
/**\name Accel Power mode configuration register */
#define BMI088_ACCEL_PWR_CONF_REG UINT8_C(0x7C)
/**\name Accel Power control (switch on or off ) register */
#define BMI088_ACCEL_PWR_CTRL_REG UINT8_C(0x7D)
/**\name Accel Soft reset register */
#define BMI088_ACCEL_SOFTRESET_REG UINT8_C(0x7E)
/**\name Accel unique chip identifier */
#define BMI088_ACCEL_CHIP_ID UINT8_C(0x1E)
/**\name Accel I2C slave address */
#define BMI088_ACCEL_I2C_ADDR_PRIMARY UINT8_C(0x18)
#define BMI088_ACCEL_I2C_ADDR_SECONDARY UINT8_C(0x19)
/**\name Feature Config related Registers */
#define BMI088_ACCEL_RESERVED_5B_REG UINT8_C(0x5B)
#define BMI088_ACCEL_RESERVED_5C_REG UINT8_C(0x5C)
#define BMI088_ACCEL_FEATURE_CFG_REG UINT8_C(0x5E)
/**\name Interrupt masks */
#define BMI088_ACCEL_DATA_READY_INT UINT8_C(0x80)
/**\name Accel Bandwidth */
#define BMI088_ACCEL_BW_OSR4 UINT8_C(0x00)
#define BMI088_ACCEL_BW_OSR2 UINT8_C(0x01)
#define BMI088_ACCEL_BW_NORMAL UINT8_C(0x02)
/**\name Accel Range */
#define BMI088_ACCEL_RANGE_3G UINT8_C(0x00)
#define BMI088_ACCEL_RANGE_6G UINT8_C(0x01)
#define BMI088_ACCEL_RANGE_12G UINT8_C(0x02)
#define BMI088_ACCEL_RANGE_24G UINT8_C(0x03)
/**\name Accel Output data rate */
#define BMI088_ACCEL_ODR_12_5_HZ UINT8_C(0x05)
#define BMI088_ACCEL_ODR_25_HZ UINT8_C(0x06)
#define BMI088_ACCEL_ODR_50_HZ UINT8_C(0x07)
#define BMI088_ACCEL_ODR_100_HZ UINT8_C(0x08)
#define BMI088_ACCEL_ODR_200_HZ UINT8_C(0x09)
#define BMI088_ACCEL_ODR_400_HZ UINT8_C(0x0A)
#define BMI088_ACCEL_ODR_800_HZ UINT8_C(0x0B)
#define BMI088_ACCEL_ODR_1600_HZ UINT8_C(0x0C)
/**\name Accel Self test */
#define BMI088_ACCEL_SWITCH_OFF_SELF_TEST UINT8_C(0x00)
#define BMI088_ACCEL_POSITIVE_SELF_TEST UINT8_C(0x0D)
#define BMI088_ACCEL_NEGATIVE_SELF_TEST UINT8_C(0x09)
/**\name Accel Power mode */
#define BMI088_ACCEL_PM_ACTIVE UINT8_C(0x00)
#define BMI088_ACCEL_PM_SUSPEND UINT8_C(0x03)
/**\name Accel Power control settings */
#define BMI088_ACCEL_POWER_DISABLE UINT8_C(0x00)
#define BMI088_ACCEL_POWER_ENABLE UINT8_C(0x04)
/**\name Accel Soft reset delay */
#define BMI088_ACCEL_SOFTRESET_DELAY UINT8_C(1)
/**\name Mask definitions for ACCEL_ERR_REG register */
#define BMI088_FATAL_ERR_MASK UINT8_C(0x01)
#define BMI088_CMD_ERR_MASK UINT8_C(0x02)
#define BMI088_ERR_CODE_MASK UINT8_C(0x1C)
/**\name Position definitions for ACCEL_ERR_REG register */
#define BMI088_FATAL_ERR_POS UINT8_C(0)
#define BMI088_CMD_ERR_POS UINT8_C(1)
#define BMI088_ERR_CODE_POS UINT8_C(2)
/**\name Mask definition for FIFO BYTE COUNTER register */
#define BMI088_FIFO_BYTE_COUNTER_MSB_MASK UINT8_C(0x3F)
/**\name Position definition for FIFO BYTE COUNTER register */
#define BMI088_FIFO_BYTE_COUNTER_MSB_POS UINT8_C(0)
/**\name Mask definitions for odr, bandwidth and range */
#define BMI088_ACCEL_ODR_MASK UINT8_C(0x0F)
#define BMI088_ACCEL_BW_MASK UINT8_C(0x70)
#define BMI088_ACCEL_RANGE_MASK UINT8_C(0x03)
/**\name Position definitions for odr, bandwidth and range */
#define BMI088_ACCEL_ODR_POS UINT8_C(0)
#define BMI088_ACCEL_BW_POS UINT8_C(4)
#define BMI088_ACCEL_RANGE_POS UINT8_C(0)
/**\name Mask definitions for FIFO_DOWNS register */
#define BMI088_ACCEL_FIFO_FILT_DOWN_MASK UINT8_C(0x70)
#define BMI088_ACCEL_FIFO_FILT_DATA_MASK UINT8_C(0x80)
/**\name Position definitions for FIFO_DOWNS register */
#define BMI088_ACCEL_FIFO_FILT_DOWN_POS UINT8_C(4)
#define BMI088_ACCEL_FIFO_FILT_DATA_POS UINT8_C(7)
/**\name Mask definitions for INT1_IO_CONF register */
#define BMI088_ACCEL_INT1_LVL_MASK UINT8_C(0x02)
#define BMI088_ACCEL_INT1_OD_MASK UINT8_C(0x04)
#define BMI088_ACCEL_INT1_IO_MASK UINT8_C(0x08)
/**\name Position definitions for INT1_IO_CONF register */
#define BMI088_ACCEL_INT1_LVL_POS UINT8_C(1)
#define BMI088_ACCEL_INT1_OD_POS UINT8_C(2)
#define BMI088_ACCEL_INT1_IO_POS UINT8_C(3)
/**\name Mask definitions for INT2_IO_CONF register */
#define BMI088_ACCEL_INT2_LVL_MASK UINT8_C(0x02)
#define BMI088_ACCEL_INT2_OD_MASK UINT8_C(0x04)
#define BMI088_ACCEL_INT2_IO_MASK UINT8_C(0x08)
/**\name Position definitions for INT2_IO_CONF register */
#define BMI088_ACCEL_INT2_LVL_POS UINT8_C(1)
#define BMI088_ACCEL_INT2_OD_POS UINT8_C(2)
#define BMI088_ACCEL_INT2_IO_POS UINT8_C(3)
/**\name Mask definitions for INT1_INT2_MAP_DATA register */
#define BMI088_ACCEL_INT1_FIFO_FULL_MASK UINT8_C(0x01)
#define BMI088_ACCEL_INT1_FIFO_WM_MASK UINT8_C(0x02)
#define BMI088_ACCEL_INT1_DRDY_MASK UINT8_C(0x04)
#define BMI088_ACCEL_INT2_FIFO_FULL_MASK UINT8_C(0x10)
#define BMI088_ACCEL_INT2_FIFO_WM_MASK UINT8_C(0x20)
#define BMI088_ACCEL_INT2_DRDY_MASK UINT8_C(0x40)
/**\name Position definitions for INT1_INT2_MAP_DATA register */
#define BMI088_ACCEL_INT1_FIFO_FULL_POS UINT8_C(0)
#define BMI088_ACCEL_INT1_FIFO_WM_POS UINT8_C(1)
#define BMI088_ACCEL_INT1_DRDY_POS UINT8_C(2)
#define BMI088_ACCEL_INT2_FIFO_FULL_POS UINT8_C(4)
#define BMI088_ACCEL_INT2_FIFO_WM_POS UINT8_C(5)
#define BMI088_ACCEL_INT2_DRDY_POS UINT8_C(6)
/**\name Maximum Accel Fifo filter value */
#define BMI088_MAX_VALUE_FIFO_FILTER UINT8_C(1)
/**\name Maximum Accel Fifo down value */
#define BMI088_MAX_VALUE_FIFO_DOWN UINT8_C(7)
/**\name Asic Initialization value */
#define BMI088_ASIC_INITIALIZED UINT8_C(0x01)
/*************************** BMI088 Gyroscope Macros *****************************/
/** Register map */
/* Gyro registers */
/**\name Gyro Chip Id register */
#define BMI088_GYRO_CHIP_ID_REG UINT8_C(0x00)
/**\name Gyro X LSB data register */
#define BMI088_GYRO_X_LSB_REG UINT8_C(0x02)
/**\name Gyro X MSB data register */
#define BMI088_GYRO_X_MSB_REG UINT8_C(0x03)
/**\name Gyro Y LSB data register */
#define BMI088_GYRO_Y_LSB_REG UINT8_C(0x04)
/**\name Gyro Y MSB data register */
#define BMI088_GYRO_Y_MSB_REG UINT8_C(0x05)
/**\name Gyro Z LSB data register */
#define BMI088_GYRO_Z_LSB_REG UINT8_C(0x06)
/**\name Gyro Z MSB data register */
#define BMI088_GYRO_Z_MSB_REG UINT8_C(0x07)
/**\name Gyro Interrupt status register */
#define BMI088_GYRO_INT_STAT_1_REG UINT8_C(0x0A)
/**\name Gyro Fifo status register */
#define BMI088_GYRO_FIFO_STAT_REG UINT8_C(0x0E)
/**\name Gyro Range register */
#define BMI088_GYRO_RANGE_REG UINT8_C(0x0F)
/**\name Gyro Bandwidth register */
#define BMI088_GYRO_BANDWIDTH_REG UINT8_C(0x10)
/**\name Gyro Power register */
#define BMI088_GYRO_LPM1_REG UINT8_C(0x11)
/**\name Gyro Soft reset register */
#define BMI088_GYRO_SOFTRESET_REG UINT8_C(0x14)
/**\name Gyro Interrupt control register */
#define BMI088_GYRO_INT_CTRL_REG UINT8_C(0x15)
/**\name Gyro Interrupt Pin configuration register */
#define BMI088_GYRO_INT3_INT4_IO_CONF_REG UINT8_C(0x16)
/**\name Gyro Interrupt Map register */
#define BMI088_GYRO_INT3_INT4_IO_MAP_REG UINT8_C(0x18)
/**\name Gyro Interrupt Enable Register */
#define BMI088_GYRO_INT_EN_REG UINT8_C(0x1E)
/**\name Gyro Self test register */
#define BMI088_GYRO_SELF_TEST_REG UINT8_C(0x3C)
/**\name Gyro Fifo Config 0 register */
#define BMI088_GYRO_FIFO_CONFIG_0_REG UINT8_C(0x3D)
/**\name Gyro Fifo Config 1 register */
#define BMI088_GYRO_FIFO_CONFIG_1_REG UINT8_C(0x3E)
/**\name Gyro Fifo Data register */
#define BMI088_GYRO_FIFO_DATA_REG UINT8_C(0x3F)
/**\name Gyro unique chip identifier */
#define BMI088_GYRO_CHIP_ID UINT8_C(0x0F)
/**\name Gyro I2C slave address */
#define BMI088_GYRO_I2C_ADDR_PRIMARY UINT8_C(0x68)
#define BMI088_GYRO_I2C_ADDR_SECONDARY UINT8_C(0x69)
/**\name Gyro Range */
#define BMI088_GYRO_RANGE_2000_DPS UINT8_C(0x00)
#define BMI088_GYRO_RANGE_1000_DPS UINT8_C(0x01)
#define BMI088_GYRO_RANGE_500_DPS UINT8_C(0x02)
#define BMI088_GYRO_RANGE_250_DPS UINT8_C(0x03)
#define BMI088_GYRO_RANGE_125_DPS UINT8_C(0x04)
/**\name Gyro Output data rate and bandwidth */
#define BMI088_GYRO_BW_532_ODR_2000_HZ UINT8_C(0x00)
#define BMI088_GYRO_BW_230_ODR_2000_HZ UINT8_C(0x01)
#define BMI088_GYRO_BW_116_ODR_1000_HZ UINT8_C(0x02)
#define BMI088_GYRO_BW_47_ODR_400_HZ UINT8_C(0x03)
#define BMI088_GYRO_BW_23_ODR_200_HZ UINT8_C(0x04)
#define BMI088_GYRO_BW_12_ODR_100_HZ UINT8_C(0x05)
#define BMI088_GYRO_BW_64_ODR_200_HZ UINT8_C(0x06)
#define BMI088_GYRO_BW_32_ODR_100_HZ UINT8_C(0x07)
#define BMI088_GYRO_ODR_RESET_VAL UINT8_C(0x80)
/**\name Gyro Power mode */
#define BMI088_GYRO_PM_NORMAL UINT8_C(0x00)
#define BMI088_GYRO_PM_DEEP_SUSPEND UINT8_C(0x20)
#define BMI088_GYRO_PM_SUSPEND UINT8_C(0x80)
/**\name Gyro data ready interrupt enable value */
#define BMI088_GYRO_DRDY_INT_ENABLE_VAL UINT8_C(0x80)
/**\name Gyro data ready map values */
#define BMI088_GYRO_MAP_DRDY_TO_INT3 UINT8_C(0x01)
#define BMI088_GYRO_MAP_DRDY_TO_INT4 UINT8_C(0x80)
#define BMI088_GYRO_MAP_DRDY_TO_BOTH_INT3_INT4 UINT8_C(0x81)
/**\name Gyro Fifo Operating Mode selection values */
#define BMI088_GYRO_BYPASS_OP_MODE UINT8_C(0x00)
#define BMI088_GYRO_FIFO_OP_MODE UINT8_C(0x01)
#define BMI088_GYRO_STREAM_OP_MODE UINT8_C(0x02)
/**\name Gyro Fifo data select values */
#define BMI088_GYRO_ALL_INT_DATA UINT8_C(0x00)//(X,Y,Z plus INT_status 0 AND 1 )
#define BMI088_GYRO_X_DATA UINT8_C(0x01)
#define BMI088_GYRO_Y_DATA UINT8_C(0x02)
#define BMI088_GYRO_Z_DATA UINT8_C(0x03)
/**\name Gyro Soft reset delay */
#define BMI088_GYRO_SOFTRESET_DELAY UINT8_C(30)
/**\name Gyro Fifo watermark mark maximum value */
#define BMI088_GYRO_FIFO_WM_MAX UINT8_C(0x7F)
/**\name Mask definitions for BMI088_GYRO_FIFO_STAT_REG register */
#define BMI088_GYRO_FIFO_COUNTER_MASK UINT8_C(0x7F)
#define BMI088_GYRO_FIFO_OVERRUN_MASK UINT8_C(0x80)
/**\name Position definitions for BMI088_GYRO_FIFO_STAT_REG register */
#define BMI088_GYRO_FIFO_COUNTER_POS UINT8_C(0)
#define BMI088_GYRO_FIFO_OVERRUN_POS UINT8_C(7)
/**\name Mask definitions for BMI088_GYRO_INT_CTRL_REG register */
#define BMI088_GYRO_FIFO_EN_MASK UINT8_C(0x40)
#define BMI088_GYRO_DATA_EN_MASK UINT8_C(0x80)
/**\name Position definitions for BMI088_GYRO_INT_CTRL_REG register */
#define BMI088_GYRO_FIFO_EN_POS UINT8_C(6)
#define BMI088_GYRO_DATA_EN_POS UINT8_C(7)
/**\name Mask definitions for BMI088_GYRO_INT3_INT4_IO_CONF_REG register */
#define BMI088_GYRO_INT3_LVL_MASK UINT8_C(0x01)
#define BMI088_GYRO_INT3_OD_MASK UINT8_C(0x02)
#define BMI088_GYRO_INT4_LVL_MASK UINT8_C(0x04)
#define BMI088_GYRO_INT4_OD_MASK UINT8_C(0x08)
/**\name Position definitions for BMI088_GYRO_INT3_INT4_IO_CONF_REG register */
#define BMI088_GYRO_INT3_LVL_POS UINT8_C(0)
#define BMI088_GYRO_INT3_OD_POS UINT8_C(1)
#define BMI088_GYRO_INT4_LVL_POS UINT8_C(2)
#define BMI088_GYRO_INT4_OD_POS UINT8_C(3)
/**\name Mask definitions for BMI088_GYRO_INT3_INT4_IO_MAP_REG register */
#define BMI088_GYRO_INT1_FIFO_MASK UINT8_C(0x04)
#define BMI088_GYRO_INT2_FIFO_MASK UINT8_C(0x20)
/**\name Position definitions for BMI088_GYRO_INT3_INT4_IO_MAP_REG register */
#define BMI088_GYRO_INT1_FIFO_POS UINT8_C(2)
#define BMI088_GYRO_INT2_FIFO_POS UINT8_C(5)
/**\name Mask definitions for BMI088_GYRO_INT_CTRL_REG register */
#define BMI088_GYRO_INT_EN_MASK UINT8_C(0x80)
/**\name Position definitions for BMI088_GYRO_INT_CTRL_REG register */
#define BMI088_GYRO_INT_EN_POS UINT8_C(7)
/**\name Mask definitions for GYRO_SELF_TEST register */
#define BMI088_GYRO_SELF_TEST_EN_MASK UINT8_C(0x01)
#define BMI088_GYRO_SELF_TEST_RDY_MASK UINT8_C(0x02)
#define BMI088_GYRO_SELF_TEST_RESULT_MASK UINT8_C(0x04)
#define BMI088_GYRO_SELF_TEST_FUNCTION_MASK UINT8_C(0x08)
/**\name Position definitions for GYRO_SELF_TEST register */
#define BMI088_GYRO_SELF_TEST_EN_POS UINT8_C(0)
#define BMI088_GYRO_SELF_TEST_RDY_POS UINT8_C(1)
#define BMI088_GYRO_SELF_TEST_RESULT_POS UINT8_C(2)
#define BMI088_GYRO_SELF_TEST_FUNCTION_POS UINT8_C(3)
/**\name Mask definitions for BMI088_GYRO_FIFO_CONFIG_0_REG register */
#define BMI088_GYRO_FIFO_WM_MASK UINT8_C(0x7F)
#define BMI088_GYRO_FIFO_TAG_MASK UINT8_C(0x80)
/**\name Position definitions for BMI088_GYRO_FIFO_CONFIG_0_REG register */
#define BMI088_GYRO_FIFO_WM_POS UINT8_C(0)
#define BMI088_GYRO_FIFO_TAG_POS UINT8_C(7)
/**\name Mask definitions for BMI088_GYRO_FIFO_CONFIG_1_REG register */
#define BMI088_GYRO_FIFO_DATA_SELECT_MASK UINT8_C(0x03)
#define BMI088_GYRO_FIFO_MODE_MASK UINT8_C(0xC0)
/**\name Position definitions for BMI088_GYRO_FIFO_CONFIG_1_REG register */
#define BMI088_GYRO_FIFO_DATA_SELECT_POS UINT8_C(0)
#define BMI088_GYRO_FIFO_MODE_POS UINT8_C(6)
/*************************** Common Macros for both Accel and Gyro *****************************/
/**\name Interface settings */
#define BMI088_SPI_INTF UINT8_C(1)
#define BMI088_I2C_INTF UINT8_C(0)
/**\name SPI read/write mask to configure address */
#define BMI088_SPI_RD_MASK UINT8_C(0x80)
#define BMI088_SPI_WR_MASK UINT8_C(0x7F)
/**\name Error code definitions */
#define BMI088_OK UINT16_C(0)
#define BMI088_E_NULL_PTR UINT16_C(1)
#define BMI088_E_COM_FAIL UINT16_C(1 << 2)
#define BMI088_E_DEV_NOT_FOUND UINT16_C(1 << 3)
#define BMI088_E_OUT_OF_RANGE UINT16_C(1 << 4)
#define BMI088_E_INVALID_INPUT UINT16_C(1 << 5)
#define BMI088_E_SELF_TEST_FAIL UINT16_C(1 << 6)
#define BMI088_E_CONFIG_STREAM_ERROR UINT16_C(1 << 7)
/***\name Soft reset Value */
#define BMI088_SOFT_RESET_VAL UINT8_C(0xB6)
/**\name Enable/disable values */
#define BMI088_ENABLE UINT8_C(0x01)
#define BMI088_DISABLE UINT8_C(0x00)
/**\name Constant values macros */
#define BMI088_ONE UINT8_C(1)
#define BMI088_TWO UINT8_C(2)
#define BMI088_THREE UINT8_C(3)
#define BMI088_FOUR UINT8_C(4)
#define BMI088_FIVE UINT8_C(5)
#define BMI088_SIX UINT8_C(6)
#define BMI088_SEVEN UINT8_C(7)
#define BMI088_EIGHT UINT8_C(8)
#define BMI088_NINE UINT8_C(9)
#define BMI088_TEN UINT8_C(10)
#define BMI088_ELEVEN UINT8_C(11)
#define BMI088_TWELVE UINT8_C(12)
#define BMI088_SIXTEEN UINT8_C(16)
#define BMI088_FIFTY UINT8_C(50)
#define BMI088_HUNDRED UINT8_C(100)
#define BMI088_ONE_FIFTY UINT8_C(150)
#define BMI088_CONFIG_STREAM_SIZE UINT16_C(6144)
/**\name Sensor time array parameter definitions */
#define BMI088_SENSOR_TIME_MSB_BYTE UINT8_C(2)
#define BMI088_SENSOR_TIME_XLSB_BYTE UINT8_C(1)
#define BMI088_SENSOR_TIME_LSB_BYTE UINT8_C(0)
/**\name FIFO header data definitions */
#define FIFO_HEAD_A UINT8_C(0x84)
#define FIFO_HEAD_G UINT8_C(0x90)
#define FIFO_HEAD_G_A UINT8_C(0x94)
#define FIFO_HEAD_SENSOR_TIME UINT8_C(0x44)
#define FIFO_HEAD_INPUT_CONFIG UINT8_C(0x48)
#define FIFO_HEAD_SKIP_FRAME UINT8_C(0x40)
#define FIFO_HEAD_OVER_READ_MSB UINT8_C(0x80)
#define FIFO_HEAD_SAMPLE_DROP UINT8_C(0x50)
/**\name FIFO headerless mode data enable definitions */
#define BMI088_FIFO_A_ENABLE UINT8_C(0x40)
/**\name FIFO configuration selection */
#define BMI088_FIFO_STOP_ON_FULL UINT8_C(0x01)
#define BMI088_FIFO_TIME UINT8_C(0x02)
#define BMI088_FIFO_TAG_INTR2 UINT8_C(0x04)
#define BMI088_FIFO_TAG_INTR1 UINT8_C(0x08)
#define BMI088_FIFO_HEADER UINT8_C(0x10)
#define BMI088_FIFO_ACCEL UINT8_C(0x40)
#define BMI088_FIFO_ALL UINT8_C(0x7F)
#define BMI088_FIFO_CONFIG_0_MASK UINT8_C(0x03)
#define BMI088_FIFO_CONFIG_1_MASK UINT8_C(0xFC)
/**\name FIFO frame count definition */
#define FIFO_LSB_CONFIG_CHECK UINT8_C(0x00)
#define FIFO_MSB_CONFIG_CHECK UINT8_C(0x80)
#define BMI088_FIFO_TAG_INTR_MASK UINT8_C(0xFC)
/**\name FIFO dropped frame definition */
#define ACCEL_FIFO_DROP UINT8_C(0x01)
/**\name FIFO sensor time length definitions*/
#define BMI088_SENSOR_TIME_LENGTH UINT8_C(3)
/**\name FIFO length definitions */
#define BMI088_FIFO_A_LENGTH UINT8_C(6)
#define BMI088_FIFO_G_ALL_DATA_LENGTH UINT8_C(8)
#define BMI088_FIFO_G_X_LENGTH UINT8_C(2)
#define BMI088_FIFO_G_Y_LENGTH UINT8_C(2)
#define BMI088_FIFO_G_Z_LENGTH UINT8_C(2)
/**\name Self test result indicators */
#define BMI088_SELFTEST_PASS UINT8_C(0)
#define BMI088_SELFTEST_FAIL INT8_C(-1)
/**\name Sensor bit resolution */
#define BMI088_16_BIT_RESOLUTION UINT8_C(16)
/**\name Absolute value */
#ifndef ABS
#define ABS(a) ((a) > 0 ? (a) : -(a))
#endif
/**\name Utility Macros */
#define BMI088_SET_LOW_BYTE UINT16_C(0x00FF)
#define BMI088_SET_HIGH_BYTE UINT16_C(0xFF00)
#define BMI088_SET_LOW_NIBBLE UINT8_C(0x0F)
/**\name Macro definition for register bit slicing, read access */
#define BMI088_GET_BITSLICE(regvar, bitname)\
(regvar & bitname##_MASK) >> bitname##_POS
/**\name Macro definition for register bit slicing, write access */
#define BMI088_SET_BITSLICE(regvar, bitname, val)\
(regvar & ~bitname##_MASK) | ((val<<bitname##_POS)&bitname##_MASK)
/**\name Macro definition for difference between 2 values */
#define BMI088_GET_DIFF(x, y) ((x) - (y))
/**\name Macro definition to get LSB of 16 bit variable */
#define BMI088_GET_LSB(var) (uint8_t)(var & BMI088_SET_LOW_BYTE)
/**\name Macro definition to get MSB of 16 bit variable */
#define BMI088_GET_MSB(var) (uint8_t)((var & BMI088_SET_HIGH_BYTE) >> 8)
/*************************** Data structures *****************************/
/**\name Typedef definitions */
/*!
* @brief Bus communication function pointer which should be mapped to
* the platform specific read and write functions of the user
*
* @note : dev_addr is used for I2C read/write operations only.
* For SPI read/write operations this is dummy variable.
*/
typedef int8_t (*bmi088_com_fptr_t)(uint8_t dev_addr, uint8_t reg_addr, uint8_t *data, uint16_t len);
/**\name delay function pointer */
typedef void (*bmi088_delay_fptr_t)(uint32_t period);
/**\name Structure Definitions */
/*!
* @brief Sensor XYZ data structure
*/
struct bmi088_sensor_data
{
/*! X-axis sensor data */
int16_t x;
/*! Y-axis sensor data */
int16_t y;
/*! Z-axis sensor data */
int16_t z;
};
/*!
* @brief Sensor configuration structure
*/
struct bmi088_cfg
{
/*! power mode */
uint8_t power;
/*! range */
uint8_t range;
/*! bandwidth */
uint8_t bw;
/*! output data rate */
uint8_t odr;
};
/*!
* @brief Error Status structure
*/
struct bmi088_err_reg
{
/*! Indicates fatal error */
uint8_t fatal_err;
/*! Indicates command error */
uint8_t cmd_err;
/*! Indicates error code */
uint8_t err_code;
};
/*!
* @brief Enum to select accelerometer Interrupt pins
*/
enum bmi088_accel_int_channel
{
BMI088_INT_CHANNEL_1, /* interrupt Channel 1 for accel sensor*/
BMI088_INT_CHANNEL_2 /* interrupt Channel 2 */
};
/*!
* @brief Enum to select gyroscope Interrupt pins
*/
enum bmi088_gyro_int_channel
{
BMI088_INT_CHANNEL_3, /* interrupt Channel 3 for gyro sensor*/
BMI088_INT_CHANNEL_4, /* interrupt Channel 4 */
BMI088_INT_CHANNEL_BOTH /* Both interrupt Channel 3 and 4 */
};
/*!
* @brief Enum to select accelerometer interrupts
*/
enum bmi088_accel_int_types
{
BMI088_ACCEL_DATA_RDY_INT, /* Accel data ready interrupt */
};
/*!
* @brief Enum to select gyroscope interrupts
*/
enum bmi088_gyro_int_types
{
BMI088_GYRO_DATA_RDY_INT, /* Gyro data ready interrupt */
};
/*!
* @brief Interrupt pin configuration structure
*/
struct bmi088_int_pin_cfg
{
#ifdef LITTLE_ENDIAN
/*! Enable interrupt pin -> 0 - disable, 1 - enable */
uint8_t enable_int_pin :1;
/*! 0 - push-pull, 1 - open drain */
uint8_t output_mode :1;
/*! 0 - active low, 1 - active high level */
uint8_t lvl :1;
#else
/*! 0 - active low, 1 - active high level */
uint8_t lvl : 1;
/*! 0 - push-pull, 1 - open drain */
uint8_t output_mode : 1;
/*! Enable interrupt pin -> 0 - disable, 1 - enable */
uint8_t enable_int_pin : 1;
#endif
};
/*!
* @brief Interrupt Configuration structure
*/
struct bmi088_int_cfg
{
/*! Accel Interrupt channel */
enum bmi088_accel_int_channel accel_int_channel;
/*! Gyro Interrupt channel */
enum bmi088_gyro_int_channel gyro_int_channel;
/*! Select Accel Interrupt */
enum bmi088_accel_int_types accel_int_type;
/*! Select Gyro Interrupt */
enum bmi088_gyro_int_types gyro_int_type;
/*! Structure to configure accel interrupt pins */
struct bmi088_int_pin_cfg accel_int_pin_cfg;
/*! Structure to configure gyro interrupt pin 3 */
struct bmi088_int_pin_cfg gyro_int_pin_3_cfg;
/*! Structure to configure gyro interrupt pin 4 */
struct bmi088_int_pin_cfg gyro_int_pin_4_cfg;
};
/*!
* @brief This structure holds the information for usage of
* FIFO by the user.
*/
struct bmi088_fifo_frame
{
/*! Data buffer of user defined length is to be mapped here */
uint8_t *data;
/*! Number of bytes of FIFO to be read as specified by the user */
uint16_t length;
/*! Length of each frame stored in fifo */
uint16_t frame_length;
/*! Enabling the FIFO header to stream in header mode */
uint8_t fifo_header_enable;
/*! Sensor data enabled status */
uint8_t fifo_data_enable;
/*! Will be equal to length when no more frames are there to parse */
uint16_t byte_start_idx;
/*! Value of FIFO sensor time */
uint32_t sensor_time;
/*! Value of Skipped frame counts */
uint8_t skipped_frame_count;
/*! Value of dropped frame count */
uint8_t dropped_frame_count;
};
/*!
* @brief
* This structure holds all relevant information about BMI088
*/
struct bmi088_dev
{
/*! Accel chip Id */
uint8_t accel_chip_id;
/*! Gyro chip Id */
uint8_t gyro_chip_id;
/*! Accel device Id */
uint8_t accel_id;
/*! Gyro device Id */
uint8_t gyro_id;
/*! 0 - I2C , 1 - SPI Interface */
uint8_t interface;
/*! Decide SPI or I2C read mechanism */
uint8_t dummy_byte;
/*! Structure to configure accel sensor */
struct bmi088_cfg accel_cfg;
/*! Structure to configure gyro sensor */
struct bmi088_cfg gyro_cfg;
/*! Accel FIFO related configurations */
struct bmi088_fifo_frame *accel_fifo;
/*! Gyro FIFO related configurations */
struct bmi088_fifo_frame *gyro_fifo;
/*! Config stream data buffer address will be assigned*/
const uint8_t *config_file_ptr;
/*! Max read/write length (maximum supported length is 32).
To be set by the user */
uint8_t read_write_len;
/*! Read function pointer */
bmi088_com_fptr_t read;
/*! Write function pointer */
bmi088_com_fptr_t write;
/*! Delay function pointer */
bmi088_delay_fptr_t delay_ms;
};
/*************************** C++ guard macro *****************************/
#ifdef __cplusplus
}
#endif
#endif /* BMI088_DEFS_H_ */
/*
*
****************************************************************************
* Copyright (C) 2015 - 2016 Bosch Sensortec GmbH
*
* File : bmi088_fifo.h
*
* Date: 30 Oct 2017
*
* Revision:
*
* Usage: Sensor Driver for BMI088 family of sensors
*
****************************************************************************
*
* Disclaimer
*
* Common:
* Bosch Sensortec products are developed for the consumer goods industry.
* They may only be used within the parameters of the respective valid
* product data sheet. Bosch Sensortec products are provided with the
* express understanding that there is no warranty of fitness for a
* particular purpose.They are not fit for use in life-sustaining,
* safety or security sensitive systems or any system or device
* that may lead to bodily harm or property damage if the system
* or device malfunctions. In addition,Bosch Sensortec products are
* not fit for use in products which interact with motor vehicle systems.
* The resale and or use of products are at the purchasers own risk and
* his own responsibility. The examination of fitness for the intended use
* is the sole responsibility of the Purchaser.
*
* The purchaser shall indemnify Bosch Sensortec from all third party
* claims, including any claims for incidental, or consequential damages,
* arising from any product use not covered by the parameters of
* the respective valid product data sheet or not approved by
* Bosch Sensortec and reimburse Bosch Sensortec for all costs in
* connection with such claims.
*
* The purchaser must monitor the market for the purchased products,
* particularly with regard to product safety and inform Bosch Sensortec
* without delay of all security relevant incidents.
*
* Engineering Samples are marked with an asterisk (*) or (e).
* Samples may vary from the valid technical specifications of the product
* series. They are therefore not intended or fit for resale to third
* parties or for use in end products. Their sole purpose is internal
* client testing. The testing of an engineering sample may in no way
* replace the testing of a product series. Bosch Sensortec assumes
* no liability for the use of engineering samples.
* By accepting the engineering samples, the Purchaser agrees to indemnify
* Bosch Sensortec from all claims arising from the use of engineering
* samples.
*
* Special:
* This software module (hereinafter called "Software") and any information
* on application-sheets (hereinafter called "Information") is provided
* free of charge for the sole purpose to support your application work.
* The Software and Information is subject to the following
* terms and conditions:
*
* The Software is specifically designed for the exclusive use for
* Bosch Sensortec products by personnel who have special experience
* and training. Do not use this Software if you do not have the
* proper experience or training.
*
* This Software package is provided `` as is `` and without any expressed
* or implied warranties,including without limitation, the implied warranties
* of merchantability and fitness for a particular purpose.
*
* Bosch Sensortec and their representatives and agents deny any liability
* for the functional impairment
* of this Software in terms of fitness, performance and safety.
* Bosch Sensortec and their representatives and agents shall not be liable
* for any direct or indirect damages or injury, except as
* otherwise stipulated in mandatory applicable law.
*
* The Information provided is believed to be accurate and reliable.
* Bosch Sensortec 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 Bosch. Specifications mentioned in the Information are
* subject to change without notice.
**************************************************************************/
/*! \file bmi088_fifo.h
\brief Sensor Driver for BMI088 family of sensors */
#ifndef BMI088_FIFO_H_
#define BMI088_FIFO_H_
#ifdef __cplusplus
extern "C"
{
#endif
#ifdef USE_FIFO
/*********************************************************************/
/* header files */
#include "bmi088.h"
/*********************************************************************/
/* (extern) variable declarations */
/*********************************************************************/
/* function prototype declarations */
/*!
* @brief This API reads the FIFO data of Accel sensor.
*
* @param[in,out] dev : Structure instance of bmi088_dev
*
* @return Result of API execution status
* @retval 0 -> Success
* @retval Any non zero value -> Fail
*
*/
uint16_t bmi088_get_accel_fifo_data(struct bmi088_dev *dev);
/*!
* @brief This API parses and extracts the accelerometer frames from
* FIFO data read by the "bmi088_get_accel_fifo_data" API and stores
* it in the "accel_data" structure instance.
*
* @note The bmi088_extract_accel API should be called only after reading
* the FIFO data by calling the bmi088_get_accel_fifo_data() API
*
* @param[in,out] accel_data : Structure instance of bmi088_sensor_data
* where the accelerometer data in FIFO is stored.
* @param[in,out] accel_length : Number of accelerometer frames
* (x,y,z axes data)
* @param[in,out] dev : Structure instance of bmi088_dev.
*
* @note accel_length has the number of accelerometer frames
* (1 accel frame = 6 bytes) which the user needs to extract and store, is
* provided as input parameter by the user and the Number of valid
* accelerometer frames extracted and stored is updated in
* "accel_length" at the end of execution of this API.
*
* @return Result of API execution status
* @retval 0 -> Success
* @retval Any non zero value -> Fail
*
*/
uint16_t bmi088_extract_accel(struct bmi088_sensor_data *accel_data, uint16_t *accel_length, const struct bmi088_dev *dev);
/*!
* @brief This API reads the FIFO water mark level which is set
* in the accel sensor.
*
* @note The FIFO watermark is issued when the accel FIFO fill level
* is equal or above the watermark level.
*
* @param[out] fifo_wm : Pointer variable to store FIFO water mark level
* @param[in] dev : Structure instance of bmi088_dev
*
* @return Result of API execution status
* @retval 0 -> Success
* @retval Any non zero value -> Fail
*
*/
uint16_t bmi088_get_accel_fifo_wm(uint16_t *fifo_wm, struct bmi088_dev *dev);
/*!
* @brief This API sets the FIFO watermark level in the accel sensor.
*
* @note The FIFO watermark is issued when the accel FIFO fill level is
* equal or above the watermark level.
*
* @param[in] fifo_wm : Variable used to set the FIFO water mark level
* @param[out] dev : Structure instance of bmi088_dev
*
* @return Result of API execution status
* @retval 0 -> Success
* @retval Any non zero value -> Fail
*
*/
uint16_t bmi088_set_accel_fifo_wm(uint16_t fifo_wm, struct bmi088_dev *dev);
/*!
* @brief This API checks whether the Accel FIFO data is set for filtered
* or unfiltered mode.
*
* @param[out] accel_fifo_filter : Variable used to check whether the Accel
* data is filtered or unfiltered.
* Value | accel_fifo_filter
* ---------|-------------------------
* 0x00 | Unfiltered data
* 0x01 | Filtered data
*
* @param[in] dev : structure instance of bmi088_dev
*
* @return Result of API execution status
* @retval 0 -> Success
* @retval Any non zero value -> Fail
*
*/
uint16_t bmi088_get_accel_fifo_filt_data(uint8_t *accel_fifo_filter, struct bmi088_dev *dev);
/*!
* @brief This API sets the condition of Accel FIFO data either to
* filtered or unfiltered mode.
*
* @param[in] accel_fifo_filter : Variable used to set the filtered or
* unfiltered condition of Accel FIFO data.
* value | accel_fifo_filter_data
* -----------|-------------------------
* 0x00 | Unfiltered data
* 0x01 | Filtered data
*
* @param[out] dev : Structure instance of bmi088_dev
*
* @return Result of API execution status
* @retval 0 -> Success
* @retval Any non zero value -> Fail
*
*/
uint16_t bmi088_set_accel_fifo_filt_data(uint8_t accel_fifo_filter, struct bmi088_dev *dev);
/*!
* @brief This API reads the down sampling rates which is configured
* for Accel FIFO data.
*
* @param[out] fifo_down : Variable used to specify the Accel FIFO
* down-sampling rates
* @param[in] dev : Structure instance of bmi088_dev
*
* @return Result of API execution status
* @retval 0 -> Success
* @retval Any non zero value -> Fail
*
*/
uint16_t bmi088_get_fifo_down_accel(uint8_t *fifo_down, struct bmi088_dev *dev);
/*!
* @brief This API sets the down-sampling rates for Accel FIFO.
*
* @param[in] fifo_down : Variable used to specify the Accel FIFO
* down-sampling rates.
* @param[in] dev : Structure instance of bmi088_dev
*
* @return Result of API execution status
* @retval 0 -> Success
* @retval Any non zero value -> Fail
*
*/
uint16_t bmi088_set_fifo_down_accel(uint8_t fifo_down, struct bmi088_dev *dev);
/*!
* @brief This API reads the length of Accel FIFO data in the units of bytes.
*
* @note This byte counter is updated each time a complete frame is read
* or written
*
* @param[in] fifo_length : Pointer variable used to store the value of
* fifo byte counter
* @param[in] dev : Structure instance of bmi088_dev
*
* @return Result of API execution status
* @retval 0 -> Success
* @retval Any non zero value -> Fail
*
*/
uint16_t bmi088_get_accel_fifo_length(uint16_t *fifo_length, struct bmi088_dev *dev);
/*!
* @brief This API sets the FIFO full interrupt of the accel sensor.
*
* @param[in] int_config : Structure instance of bmi088_int_cfg.
* @param[in] dev : Structure instance of bmi088_dev.
*
* @return Result of API execution status
* @retval zero -> Success
* @retval Any non zero value -> Fail
*
*/
uint16_t bmi088_set_accel_fifo_full_int(struct bmi088_int_cfg *int_config, struct bmi088_dev *dev);
/*!
* @brief This API sets the FIFO watermark interrupt of the accel sensor.
*
* @param[in] int_config : Structure instance of bmi088_int_cfg.
* @param[in] dev : Structure instance of bmi088_dev.
*
* @return Result of API execution status
* @retval zero -> Success
* @retval Any non zero value -> Fail
*
*/
uint16_t bmi088_set_accel_fifo_wm_int(struct bmi088_int_cfg *int_config, struct bmi088_dev *dev);
/*!
* @brief This API reads the FIFO data of Gyro sensor
*
* @param[in,out] dev : Structure instance of bmi088_dev
*
* @return Result of API execution status
* @retval 0 -> Success
* @retval Any non zero value -> Fail
*
*/
uint16_t bmi088_get_gyro_fifo_data(struct bmi088_dev *dev);
/*!
* @brief This API parses and extracts the gyroscope frames from
* FIFO data read by the "bmi088_get_gyro_fifo_data" API and stores
* it in the "gyro_data" structure instance parameter of this API
*
* @note The bmi088_extract_gyro API should be called only after reading
* the FIFO data by calling the bmi088_get_gyro_fifo_data() API
*
* @param[in,out] gyro_data : Structure instance of bmi088_sensor_data
* where the gyroscope data in FIFO is stored.
* @param[in,out] gyro_length : Number of gyroscope frames (x,y,z,r data)
* @param[in,out] dev : Structure instance of bmi088_dev.
*
* @note gyro_length has the number of gyroscope frames(x,y,z,r data)
* which the user needs to extract and store. It is provided as input
* parameter by the user and the number of valid gyroscope frames
* extracted and stored is updated in "gyro_length" at the end of
* execution of this API.
*
* @return Result of API execution status
* @retval 0 -> Success
* @retval Any non zero value -> Fail
*
*/
uint16_t bmi088_extract_gyro(struct bmi088_sensor_data *gyro_data, uint16_t *gyro_length, const struct bmi088_dev *dev);
/*!
* @brief This API reads the FIFO water mark level which is set
* in the gyro sensor.
*
* @note The FIFO watermark is issued when the FIFO fill level is
* equal or above the watermark level.
*
* @param[out] fifo_wm : Pointer variable to store FIFO water mark level
* @param[in] dev : Structure instance of bmi088_dev
*
* @return Result of API execution status
* @retval 0 -> Success
* @retval Any non zero value -> Fail
*
*/
uint16_t bmi088_get_gyro_fifo_wm(uint8_t *fifo_wm, struct bmi088_dev *dev);
/*!
* @brief This API sets the FIFO watermark level in the gyro sensor.
*
* @note The FIFO watermark is issued when the FIFO fill level is
* equal or above the watermark level.
*
* @param[in] fifo_wm : Variable used to set the FIFO water mark level
* @param[in] dev : Structure instance of bmi088_dev
*
* @return Result of API execution status
* @retval 0 -> Success
* @retval Any non zero value -> Fail
*
*/
uint16_t bmi088_set_gyro_fifo_wm(uint8_t fifo_wm, struct bmi088_dev *dev);
/*!
* @brief This API reads the FIFO operating mode which is set
* in the gyro sensor.
*
* @param[out] fifo_mode : Pointer variable used to get the FIFO
* operating mode
* value | fifo_mode
* --------------------------------|-------------------------
* BMI088_GYRO_BYPASS_OP_MODE | Bypass Mode
* BMI088_GYRO_FIFO_OP_MODE | Fifo Mode
* BMI088_GYRO_STREAM_OP_MODE | Stream Mode
*
* @param[in] dev : Structure instance of bmi088_dev
*
* @return Result of API execution status
* @retval 0 -> Success
* @retval Any non zero value -> Fail
*
*/
uint16_t bmi088_get_gyro_fifo_mode(uint8_t *fifo_mode, struct bmi088_dev *dev);
/*!
* @brief This API sets the FIFO operating mode in the gyro sensor.
*
* @param[in] fifo_mode : Variable used to set the FIFO operating mode
* value | Fifo Mode
* --------------------------------|-------------------------
* BMI088_GYRO_BYPASS_OP_MODE | Bypass Mode
* BMI088_GYRO_FIFO_OP_MODE | Fifo Mode
* BMI088_GYRO_STREAM_OP_MODE | Stream Mode
*
* @param[in] dev : Structure instance of bmi088_dev
*
* @return Result of API execution status
* @retval 0 -> Success
* @retval Any non zero value -> Fail
*
*/
uint16_t bmi088_set_gyro_fifo_mode(uint8_t fifo_mode, struct bmi088_dev *dev);
/*!
* @brief This API reads the data of axes to be stored in the FIFO in the gyro sensor.
*
* @param[out] fifo_data_select : Pointer variable used to get the selected data
* axes for FIFO data storage.
* value | fifo_data_select
* --------------------------------|-------------------------
* BMI088_GYRO_ALL_INT_DATA | X,Y,Z plus INT_status 0 and 1
* BMI088_GYRO_X_DATA | X only
* BMI088_GYRO_Y_DATA | Y only
* BMI088_GYRO_Z_DATA | Z only
*
* @param[in] dev : Structure instance of bmi088_dev
*
* @return Result of API execution status
* @retval 0 -> Success
* @retval Any non zero value -> Fail
*
*/
uint16_t bmi088_get_gyro_fifo_data_sel(uint8_t *fifo_data_select, struct bmi088_dev *dev);
/*!
* @brief This API sets the data of axes to be stored in the FIFO in the gyro sensor.
*
* @param[in] fifo_data_select : Variable used to select data of axis to be stored
* in fifo
* value | Data of axis stored in FIFO
* --------------------------------|-------------------------
* BMI088_GYRO_ALL_INT_DATA | X,Y,Z plus INT_status 0 and 1
* BMI088_GYRO_X_DATA | X only
* BMI088_GYRO_Y_DATA | Y only
* BMI088_GYRO_Z_DATA | Z only
*
* @param[in] dev : Structure instance of bmi088_dev
*
* @return Result of API execution status
* @retval 0 -> Success
* @retval Any non zero value -> Fail
*
*/
uint16_t bmi088_set_gyro_fifo_data_sel(uint8_t fifo_data_select, struct bmi088_dev *dev);
/*!
* @brief This API gets the length of Gyro FIFO data in the units of bytes.
*
* @note This byte counter is updated each time a complete frame is read
* or written
*
* @param[out] fifo_length : Pointer variable used to store the value of
* fifo byte counter
* @param[in] dev : Structure instance of bmi088_dev
*
* @return Result of API execution status
* @retval 0 -> Success
* @retval Any non zero value -> Fail
*
*/
uint16_t bmi088_get_gyro_fifo_length(uint8_t *fifo_length, struct bmi088_dev *dev);
/*!
* @brief This API gets the gyro FIFO overrun status.
*
* @param[out] fifo_overrun_status : Pointer variable used to store the status
* of FIFO overrun.
* @param[in] dev : Structure instance of bmi088_dev
*
* @return Result of API execution status
* @retval 0 -> Success
* @retval Any non zero value -> Fail
*
*/
uint16_t bmi088_get_gyro_fifo_overrun(uint8_t *fifo_overrun_status, struct bmi088_dev *dev);
/*!
* @brief This API gets the fifo tag status which is set in
* gyro sensor.
*
* @param[out] fifo_tag_status : Pointer variable used to store the value of
* fifo tag status.
* @param[in] dev : Structure instance of bmi088_dev
*
* @return Result of API execution status
* @retval 0 -> Success
* @retval Any non zero value -> Fail
*
*/
uint16_t bmi088_get_gyro_fifo_tag(uint8_t *fifo_tag_status, struct bmi088_dev *dev);
/*!
* @brief This API enables or disables fifo tag in gyro sensor.
*
* @param[in] fifo_tag : Variable used to enable or disable fifo tag
* value | fifo_tag
* --------------------------|-----------------------------------
* BMI088_DISABLE | Do not collect Interrupts in FIFO
* BMI088_ENABLE | Collects Interrupts in FIFO
*
* @param[in] dev : Structure instance of bmi088_dev
*
* @return Result of API execution status
* @retval 0 -> Success
* @retval Any non zero value -> Fail
*
*/
uint16_t bmi088_set_gyro_fifo_tag(uint8_t fifo_tag, struct bmi088_dev *dev);
/*!
* @brief This API enables or disables the FIFO full interrupt of the gyro sensor.
*
* @param[in] int_config : Structure instance of bmi088_int_cfg.
* @param[in] dev : Structure instance of bmi088_dev.
* @param[in] fifo_full_enable : Variable used to enable or disable fifo
* full interrupt
* value | fifo_full_enable
* --------------------------|-----------------------------------
* BMI088_DISABLE | Disables fifo full interrupt
* BMI088_ENABLE | Enables fifo full interrupt
*
* @return Result of API execution status
* @retval zero -> Success
* @retval Any non zero value -> Fail
*
*/
uint16_t bmi088_set_gyro_fifo_full_int(struct bmi088_int_cfg *int_config, struct bmi088_dev *dev, uint8_t fifo_full_enable);
/*!
* @brief This API enables or disables the FIFO watermark interrupt of the gyro sensor.
*
* @param[in] int_config : Structure instance of bmi088_int_cfg.
* @param[in] dev : Structure instance of bmi088_dev.
* @param[in] fifo_wm_enable : Variable used to enable or disable fifo
* watermark interrupt
* value | fifo_full_enable
* --------------------------|-----------------------------------
* BMI088_DISABLE | Disables fifo watermark interrupt
* BMI088_ENABLE | Enables fifo watermark interrupt
*
* @return Result of API execution status
* @retval zero -> Success
* @retval Any non zero value -> Fail
*
*/
uint16_t bmi088_set_gyro_fifo_wm_int(struct bmi088_int_cfg *int_config, struct bmi088_dev *dev, uint8_t fifo_wm_enable);
#ifdef __cplusplus
}
#endif
#endif
#endif
/* End of BMI088_FIFO_H_ */
/**
* Copyright (C) 2015 - 2016 Bosch Sensortec GmbH
*
* 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.
*
* @file bmi160.h
* @date 6 Apr 2017
* @version 3.4.0
* @brief
*
*/
/*!
* @defgroup bmi160
* @brief
* @{*/
#ifndef BMI160_H_
#define BMI160_H_
#ifdef __cplusplus
extern "C"
{
#endif
#include "../interface/bmi160_defs.h"
#ifdef __KERNEL__
#include <bmi160_math.h>
#else
#include <math.h>
#include <string.h>
#include <stdlib.h>
#endif
/*********************** User function prototypes ************************/
/*!
* @brief This API is the entry point for sensor.It performs
* the selection of I2C/SPI read mechanism according to the
* selected interface and reads the chip-id of bmi160 sensor.
*
* @param[in,out] dev : Structure instance of bmi160_dev
* @note : Refer user guide for detailed info.
*
* @return Result of API execution status
* @retval zero -> Success / -ve value -> Error
*/
int8_t bmi160_init(struct bmi160_dev *dev);
/*!
* @brief This API reads the data from the given register address of sensor.
*
* @param[in] reg_addr : Register address from where the data to be read
* @param[out] data : Pointer to data buffer to store the read data.
* @param[in] len : No of bytes of data to be read.
* @param[in] dev : Structure instance of bmi160_dev.
*
* @return Result of API execution status
* @retval zero -> Success / -ve value -> Error
*/
int8_t bmi160_get_regs(uint8_t reg_addr, uint8_t *data, uint16_t len, const struct bmi160_dev *dev);
/*!
* @brief This API writes the given data to the register address
* of sensor.
*
* @param[in] reg_addr : Register address from where the data to be written.
* @param[in] data : Pointer to data buffer which is to be written
* in the sensor.
* @param[in] len : No of bytes of data to write..
* @param[in] dev : Structure instance of bmi160_dev.
*
* @return Result of API execution status
* @retval zero -> Success / -ve value -> Error
*/
int8_t bmi160_set_regs(uint8_t reg_addr, uint8_t *data, uint16_t len, const struct bmi160_dev *dev);
/*!
* @brief This API resets and restarts the device.
* All register values are overwritten with default parameters.
*
* @param[in] dev : Structure instance of bmi160_dev.
*
* @return Result of API execution status
* @retval zero -> Success / -ve value -> Error.
*/
int8_t bmi160_soft_reset(const struct bmi160_dev *dev);
/*!
* @brief This API configures the power mode, range and bandwidth
* of sensor.
*
* @param[in] dev : Structure instance of bmi160_dev.
* @note : Refer user guide for detailed info.
*
* @return Result of API execution status
* @retval zero -> Success / -ve value -> Error.
*/
int8_t bmi160_set_sens_conf(struct bmi160_dev *dev);
/*!
* @brief This API sets the power mode of the sensor.
*
* @param[in] dev : Structure instance of bmi160_dev.
*
* @return Result of API execution status
* @retval zero -> Success / -ve value -> Error.
*/
int8_t bmi160_set_power_mode(struct bmi160_dev *dev);
/*!
* @brief This API reads sensor data, stores it in
* the bmi160_sensor_data structure pointer passed by the user.
* The user can ask for accel data ,gyro data or both sensor
* data using bmi160_select_sensor enum
*
* @param[in] select_sensor : enum to choose accel,gyro or both sensor data
* @param[out] accel : Structure pointer to store accel data
* @param[out] gyro : Structure pointer to store gyro data
* @param[in] dev : Structure instance of bmi160_dev.
* @note : Refer user guide for detailed info.
*
* @return Result of API execution status
* @retval zero -> Success / -ve value -> Error
*/
int8_t bmi160_get_sensor_data(uint8_t select_sensor, struct bmi160_sensor_data *accel,
struct bmi160_sensor_data *gyro, const struct bmi160_dev *dev);
/*!
* @brief This API configures the necessary interrupt based on
* the user settings in the bmi160_int_settg structure instance.
*
* @param[in] int_config : Structure instance of bmi160_int_settg.
* @param[in] dev : Structure instance of bmi160_dev.
* @note : Refer user guide for detailed info.
*
* @return Result of API execution status
* @retval zero -> Success / -ve value -> Error
*/
int8_t bmi160_set_int_config(struct bmi160_int_settg *int_config, struct bmi160_dev *dev);
/*!
* @brief This API enables the step counter feature.
*
* @param[in] step_cnt_enable : value to enable or disable
* @param[in] dev : Structure instance of bmi160_dev.
* @note : Refer user guide for detailed info.
*
* @return Result of API execution status
* @retval zero -> Success / -ve value -> Error
*/
int8_t bmi160_set_step_counter(uint8_t step_cnt_enable, const struct bmi160_dev *dev);
/*!
* @brief This API reads the step counter value.
*
* @param[in] step_val : Pointer to store the step counter value.
* @param[in] dev : Structure instance of bmi160_dev.
* @note : Refer user guide for detailed info.
*
* @return Result of API execution status
* @retval zero -> Success / -ve value -> Error
*/
int8_t bmi160_read_step_counter(uint16_t *step_val, const struct bmi160_dev *dev);
/*!
* @brief This API reads the mention no of byte of data from the given
* register address of auxiliary sensor.
*
* @param[in] reg_addr : Address of register to read.
* @param[in] aux_data : Pointer to store the read data.
* @param[in] len : No of bytes to read.
* @param[in] dev : Structure instance of bmi160_dev.
* @note : Refer user guide for detailed info.
*
* @return Result of API execution status
* @retval zero -> Success / -ve value -> Error
*/
int8_t bmi160_aux_read(uint8_t reg_addr, uint8_t *aux_data, uint16_t len, const struct bmi160_dev *dev);
/*!
* @brief This API writes the mention no of byte of data to the given
* register address of auxiliary sensor.
*
* @param[in] reg_addr : Address of register to write.
* @param[in] aux_data : Pointer to write data.
* @param[in] len : No of bytes to write.
* @param[in] dev : Structure instance of bmi160_dev.
* @note : Refer user guide for detailed info.
*
* @return Result of API execution status
* @retval zero -> Success / -ve value -> Error
*/
int8_t bmi160_aux_write(uint8_t reg_addr, uint8_t *aux_data, uint16_t len, const struct bmi160_dev *dev);
/*!
* @brief This API initialize the auxiliary sensor
* in order to access it.
*
* @param[in] dev : Structure instance of bmi160_dev.
* @note : Refer user guide for detailed info.
*
* @return Result of API execution status
* @retval zero -> Success / -ve value -> Error
*/
int8_t bmi160_aux_init(const struct bmi160_dev *dev);
/*!
* @brief This API is used to setup the auxiliary sensor of bmi160 in auto mode
* Thus enabling the auto update of 8 bytes of data from auxiliary sensor
* to BMI160 register address 0x04 to 0x0B
*
* @param[in] data_addr : Starting address of aux. sensor's data register
* (BMI160 registers 0x04 to 0x0B will be updated
* with 8 bytes of data from auxiliary sensor
* starting from this register address.)
* @param[in] dev : Structure instance of bmi160_dev.
*
* @note : Set the value of auxiliary polling rate by setting
* dev->aux_cfg.aux_odr to the required value from the table
* before calling this API
*
* dev->aux_cfg.aux_odr | Auxiliary ODR (Hz)
* -----------------------|-----------------------
* BMI160_AUX_ODR_0_78HZ | 25/32
* BMI160_AUX_ODR_1_56HZ | 25/16
* BMI160_AUX_ODR_3_12HZ | 25/8
* BMI160_AUX_ODR_6_25HZ | 25/4
* BMI160_AUX_ODR_12_5HZ | 25/2
* BMI160_AUX_ODR_25HZ | 25
* BMI160_AUX_ODR_50HZ | 50
* BMI160_AUX_ODR_100HZ | 100
* BMI160_AUX_ODR_200HZ | 200
* BMI160_AUX_ODR_400HZ | 400
* BMI160_AUX_ODR_800HZ | 800
*
* @note : Other values of dev->aux_cfg.aux_odr are reserved and not for use
*
* @return Result of API execution status
* @retval zero -> Success / -ve value -> Error
*/
int8_t bmi160_set_aux_auto_mode(uint8_t* data_addr, struct bmi160_dev *dev);
/*!
* @brief This API configures the 0x4C register and settings like
* Auxiliary sensor manual enable/ disable and aux burst read length.
*
* @param[in] dev : Structure instance of bmi160_dev.
*
* @return Result of API execution status
* @retval zero -> Success / -ve value -> Error
*/
int8_t bmi160_config_aux_mode(const struct bmi160_dev *dev);
/*!
* @brief This API is used to read the raw uncompensated auxiliary sensor
* data of 8 bytes from BMI160 register address 0x04 to 0x0B
*
* @param[in] aux_data : Pointer to user array of length 8 bytes
* Ensure that the aux_data array is of
* length 8 bytes
* @param[in] dev : Structure instance of bmi160_dev
*
* @return Result of API execution status
* @retval zero -> Success / -ve value -> Error
*/
int8_t bmi160_read_aux_data_auto_mode(uint8_t *aux_data, const struct bmi160_dev *dev);
/*!
* @brief This API reads the data from fifo buffer.
*
* @note User has to allocate the FIFO buffer along with
* corresponding fifo length from his side before calling this API
* as mentioned in the readme.md
*
* @note User must specify the number of bytes to read from the FIFO in
* dev->fifo->length , It will be updated by the number of bytes actually
* read from FIFO after calling this API
*
* @param[in] dev : Structure instance of bmi160_dev.
*
* @return Result of API execution status
* @retval zero -> Success / -ve value -> Error
*
*/
int8_t bmi160_get_fifo_data(struct bmi160_dev const *dev);
/*!
* @brief This API writes fifo_flush command to command register.This
* action clears all data in the Fifo without changing fifo configuration
* settings.
*
* @param[in] dev : Structure instance of bmi160_dev
*
* @return Result of API execution status
* @retval 0 -> Success
* @retval Any non zero value -> Fail
*
*/
int8_t bmi160_set_fifo_flush(const struct bmi160_dev *dev);
/*! @brief This API sets the FIFO configuration in the sensor.
*
* @param[in] config : variable used to specify the FIFO
* configurations which are to be enabled or disabled in the sensor.
*
* @note : User can set either set one or more or all FIFO configurations
* by ORing the below mentioned macros.
* config | Value
* ------------------------|---------------------------
* BMI160_FIFO_TIME | 0x02
* BMI160_FIFO_TAG_INT2 | 0x04
* BMI160_FIFO_TAG_INT1 | 0x08
* BMI160_FIFO_HEADER | 0x10
* BMI160_FIFO_AUX | 0x20
* BMI160_FIFO_ACCEL | 0x40
* BMI160_FIFO_GYRO | 0x80
*
* @param[in] enable : Parameter used to enable or disable the above
* FIFO configuration
* @param[in] dev : Structure instance of bmi160_dev.
*
* @return status of bus communication result
* @retval 0 -> Success
* @retval Any non zero value -> Fail
*
*/
int8_t bmi160_set_fifo_config(uint8_t config, uint8_t enable, struct bmi160_dev const *dev);
/*! @brief This API is used to configure the down sampling ratios of
* the accel and gyro data for FIFO.Also, it configures filtered or
* pre-filtered data for the fifo for accel and gyro.
*
* @param[in] fifo_down : variable used to specify the FIFO down
* configurations which are to be enabled or disabled in the sensor.
*
* @note The user must select one among the following macros to
* select down-sampling ratio for accel
* config | Value
* -------------------------------------|---------------------------
* BMI160_ACCEL_FIFO_DOWN_ZERO | 0x00
* BMI160_ACCEL_FIFO_DOWN_ONE | 0x10
* BMI160_ACCEL_FIFO_DOWN_TWO | 0x20
* BMI160_ACCEL_FIFO_DOWN_THREE | 0x30
* BMI160_ACCEL_FIFO_DOWN_FOUR | 0x40
* BMI160_ACCEL_FIFO_DOWN_FIVE | 0x50
* BMI160_ACCEL_FIFO_DOWN_SIX | 0x60
* BMI160_ACCEL_FIFO_DOWN_SEVEN | 0x70
*
* @note The user must select one among the following macros to
* select down-sampling ratio for gyro
*
* config | Value
* -------------------------------------|---------------------------
* BMI160_GYRO_FIFO_DOWN_ZERO | 0x00
* BMI160_GYRO_FIFO_DOWN_ONE | 0x01
* BMI160_GYRO_FIFO_DOWN_TWO | 0x02
* BMI160_GYRO_FIFO_DOWN_THREE | 0x03
* BMI160_GYRO_FIFO_DOWN_FOUR | 0x04
* BMI160_GYRO_FIFO_DOWN_FIVE | 0x05
* BMI160_GYRO_FIFO_DOWN_SIX | 0x06
* BMI160_GYRO_FIFO_DOWN_SEVEN | 0x07
*
* @note The user can enable filtered accel data by the following macro
* config | Value
* -------------------------------------|---------------------------
* BMI160_ACCEL_FIFO_FILT_EN | 0x80
*
* @note The user can enable filtered gyro data by the following macro
* config | Value
* -------------------------------------|---------------------------
* BMI160_GYRO_FIFO_FILT_EN | 0x08
*
* @note : By ORing the above mentioned macros, the user can select
* the required FIFO down config settings
*
* @param[in] dev : Structure instance of bmi160_dev.
*
* @return status of bus communication result
* @retval 0 -> Success
* @retval Any non zero value -> Fail
*
*/
int8_t bmi160_set_fifo_down(uint8_t fifo_down, const struct bmi160_dev *dev);
/*!
* @brief This API sets the FIFO watermark level in the sensor.
*
* @note The FIFO watermark is issued when the FIFO fill level is
* equal or above the watermark level and units of watermark is 4 bytes.
*
* @param[in] fifo_wm : Variable used to set the FIFO water mark level
* @param[in] dev : Structure instance of bmi160_dev
*
* @return Result of API execution status
* @retval 0 -> Success
* @retval Any non zero value -> Fail
*
*/
int8_t bmi160_set_fifo_wm(uint8_t fifo_wm, const struct bmi160_dev *dev);
/*!
* @brief This API parses and extracts the accelerometer frames from
* FIFO data read by the "bmi160_get_fifo_data" API and stores it in
* the "accel_data" structure instance.
*
* @note The bmi160_extract_accel API should be called only after
* reading the FIFO data by calling the bmi160_get_fifo_data() API.
*
* @param[out] accel_data : Structure instance of bmi160_sensor_data
* where the accelerometer data in FIFO is stored.
* @param[in,out] accel_length : Number of valid accelerometer frames
* (x,y,z axes data) read out from fifo.
* @param[in] dev : Structure instance of bmi160_dev.
*
* @note accel_length is updated with the number of valid accelerometer
* frames extracted from fifo (1 accel frame = 6 bytes) at the end of
* execution of this API.
*
* @return Result of API execution status
* @retval 0 -> Success
* @retval Any non zero value -> Fail
*
*/
int8_t bmi160_extract_accel(struct bmi160_sensor_data *accel_data, uint8_t *accel_length, struct bmi160_dev const *dev);
/*!
* @brief This API parses and extracts the gyro frames from
* FIFO data read by the "bmi160_get_fifo_data" API and stores it in
* the "gyro_data" structure instance.
*
* @note The bmi160_extract_accel API should be called only after
* reading the FIFO data by calling the bmi160_get_fifo_data() API.
*
* @param[out] gyro_data : Structure instance of bmi160_sensor_data
* where the gyro data in FIFO is stored.
* @param[in,out] gyro_length : Number of valid gyro frames
* (x,y,z axes data) read out from fifo.
* @param[in] dev : Structure instance of bmi160_dev.
*
* @note gyro_length is updated with the number of valid gyro
* frames extracted from fifo (1 gyro frame = 6 bytes) at the end of
* execution of this API.
*
* @return Result of API execution status
* @retval 0 -> Success
* @retval Any non zero value -> Fail
*
*/
int8_t bmi160_extract_gyro(struct bmi160_sensor_data *gyro_data, uint8_t *gyro_length, struct bmi160_dev const *dev);
#ifdef __cplusplus
}
#endif
#endif /* BMI160_H_ */
/** @}*/
/**
* Copyright (C) 2015 - 2016 Bosch Sensortec GmbH
*
* 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.
*
* @file bmi160_defs.h
* @date 6 Apr 2017
* @version 3.4.0
* @brief
*
*/
/*!
* @defgroup bmi160_defs
* @brief
* @{*/
#ifndef BMI160_DEFS_H_
#define BMI160_DEFS_H_
/*************************** C types headers *****************************/
#ifdef __KERNEL__
#include <linux/types.h>
#else
#include <stdint.h>
#include <stddef.h>
#endif
/*************************** C++ guard macro *****************************/
#ifdef __cplusplus
extern "C"
{
#endif
/*************************** Common macros *****************************/
#if (LONG_MAX) > 0x7fffffff
#define __have_long64 1
#elif (LONG_MAX) == 0x7fffffff
#define __have_long32 1
#endif
#if !defined(UINT8_C)
#define INT8_C(x) x
#if (INT_MAX) > 0x7f
#define UINT8_C(x) x
#else
#define UINT8_C(x) x##U
#endif
#endif
#if !defined(UINT16_C)
#define INT16_C(x) x
#if (INT_MAX) > 0x7fff
#define UINT16_C(x) x
#else
#define UINT16_C(x) x##U
#endif
#endif
#if !defined(INT32_C) && !defined(UINT32_C)
#if __have_long32
#define INT32_C(x) x##L
#define UINT32_C(x) x##UL
#else
#define INT32_C(x) x
#define UINT32_C(x) x##U
#endif
#endif
#if !defined(INT64_C) && !defined(UINT64_C)
#if __have_long64
#define INT64_C(x) x##L
#define UINT64_C(x) x##UL
#else
#define INT64_C(x) x##LL
#define UINT64_C(x) x##ULL
#endif
#endif
/*************************** Sensor macros *****************************/
/* Test for an endian machine */
#if __BYTE_ORDER__ == __ORDER_LITTLE_ENDIAN__
#define LITTLE_ENDIAN 1
#elif __BYTE_ORDER__ == __ORDER_BIG_ENDIAN__
#define BIG_ENDIAN 1
#else
#error "Code does not support Endian format of the processor"
#endif
/** Mask definitions */
#define BMI160_ACCEL_BW_MASK UINT8_C(0x70)
#define BMI160_ACCEL_ODR_MASK UINT8_C(0x0F)
#define BMI160_ACCEL_UNDERSAMPLING_MASK UINT8_C(0x80)
#define BMI160_ACCEL_RANGE_MASK UINT8_C(0x0F)
#define BMI160_GYRO_BW_MASK UINT8_C(0x30)
#define BMI160_GYRO_ODR_MASK UINT8_C(0x0F)
#define BMI160_GYRO_RANGE_MSK UINT8_C(0x07)
/** Mask definitions for INT_EN registers */
#define BMI160_ANY_MOTION_X_INT_EN_MASK UINT8_C(0x01)
#define BMI160_HIGH_G_X_INT_EN_MASK UINT8_C(0x01)
#define BMI160_NO_MOTION_X_INT_EN_MASK UINT8_C(0x01)
#define BMI160_ANY_MOTION_Y_INT_EN_MASK UINT8_C(0x02)
#define BMI160_HIGH_G_Y_INT_EN_MASK UINT8_C(0x02)
#define BMI160_NO_MOTION_Y_INT_EN_MASK UINT8_C(0x02)
#define BMI160_ANY_MOTION_Z_INT_EN_MASK UINT8_C(0x04)
#define BMI160_HIGH_G_Z_INT_EN_MASK UINT8_C(0x04)
#define BMI160_NO_MOTION_Z_INT_EN_MASK UINT8_C(0x04)
#define BMI160_SIG_MOTION_INT_EN_MASK UINT8_C(0x07)
#define BMI160_ANY_MOTION_ALL_INT_EN_MASK UINT8_C(0x07)
#define BMI160_STEP_DETECT_INT_EN_MASK UINT8_C(0x08)
#define BMI160_DOUBLE_TAP_INT_EN_MASK UINT8_C(0x10)
#define BMI160_SINGLE_TAP_INT_EN_MASK UINT8_C(0x20)
#define BMI160_FIFO_FULL_INT_EN_MASK UINT8_C(0x20)
#define BMI160_ORIENT_INT_EN_MASK UINT8_C(0x40)
#define BMI160_FIFO_WATERMARK_INT_EN_MASK UINT8_C(0x40)
#define BMI160_LOW_G_INT_EN_MASK UINT8_C(0x08)
#define BMI160_STEP_DETECT_EN_MASK UINT8_C(0x08)
#define BMI160_FLAT_INT_EN_MASK UINT8_C(0x80)
#define BMI160_DATA_RDY_INT_EN_MASK UINT8_C(0x10)
/** Mask definitions for INT_OUT_CTRL register */
#define BMI160_INT1_EDGE_CTRL_MASK UINT8_C(0x01)
#define BMI160_INT1_OUTPUT_MODE_MASK UINT8_C(0x04)
#define BMI160_INT1_OUTPUT_TYPE_MASK UINT8_C(0x02)
#define BMI160_INT1_OUTPUT_EN_MASK UINT8_C(0x08)
#define BMI160_INT2_EDGE_CTRL_MASK UINT8_C(0x10)
#define BMI160_INT2_OUTPUT_MODE_MASK UINT8_C(0x40)
#define BMI160_INT2_OUTPUT_TYPE_MASK UINT8_C(0x20)
#define BMI160_INT2_OUTPUT_EN_MASK UINT8_C(0x80)
/** Mask definitions for INT_LATCH register */
#define BMI160_INT1_INPUT_EN_MASK UINT8_C(0x10)
#define BMI160_INT2_INPUT_EN_MASK UINT8_C(0x20)
#define BMI160_INT_LATCH_MASK UINT8_C(0x0F)
/** Mask definitions for INT_MAP register */
#define BMI160_INT1_LOW_G_MASK UINT8_C(0x01)
#define BMI160_INT1_HIGH_G_MASK UINT8_C(0x02)
#define BMI160_INT1_SLOPE_MASK UINT8_C(0x04)
#define BMI160_INT1_NO_MOTION_MASK UINT8_C(0x08)
#define BMI160_INT1_DOUBLE_TAP_MASK UINT8_C(0x10)
#define BMI160_INT1_SINGLE_TAP_MASK UINT8_C(0x20)
#define BMI160_INT1_FIFO_FULL_MASK UINT8_C(0x20)
#define BMI160_INT1_FIFO_WM_MASK UINT8_C(0x40)
#define BMI160_INT1_ORIENT_MASK UINT8_C(0x40)
#define BMI160_INT1_FLAT_MASK UINT8_C(0x80)
#define BMI160_INT1_DATA_READY_MASK UINT8_C(0x80)
#define BMI160_INT2_LOW_G_MASK UINT8_C(0x01)
#define BMI160_INT1_LOW_STEP_DETECT_MASK UINT8_C(0x01)
#define BMI160_INT2_LOW_STEP_DETECT_MASK UINT8_C(0x01)
#define BMI160_INT2_HIGH_G_MASK UINT8_C(0x02)
#define BMI160_INT2_FIFO_FULL_MASK UINT8_C(0x02)
#define BMI160_INT2_FIFO_WM_MASK UINT8_C(0x04)
#define BMI160_INT2_SLOPE_MASK UINT8_C(0x04)
#define BMI160_INT2_DATA_READY_MASK UINT8_C(0x08)
#define BMI160_INT2_NO_MOTION_MASK UINT8_C(0x08)
#define BMI160_INT2_DOUBLE_TAP_MASK UINT8_C(0x10)
#define BMI160_INT2_SINGLE_TAP_MASK UINT8_C(0x20)
#define BMI160_INT2_ORIENT_MASK UINT8_C(0x40)
#define BMI160_INT2_FLAT_MASK UINT8_C(0x80)
/** Mask definitions for INT_DATA register */
#define BMI160_TAP_SRC_INT_MASK UINT8_C(0x08)
#define BMI160_LOW_HIGH_SRC_INT_MASK UINT8_C(0x80)
#define BMI160_MOTION_SRC_INT_MASK UINT8_C(0x80)
/** Mask definitions for INT_MOTION register */
#define BMI160_SLOPE_INT_DUR_MASK UINT8_C(0x03)
#define BMI160_NO_MOTION_INT_DUR_MASK UINT8_C(0xFC)
#define BMI160_NO_MOTION_SEL_BIT_MASK UINT8_C(0x01)
/** Mask definitions for INT_TAP register */
#define BMI160_TAP_DUR_MASK UINT8_C(0x07)
#define BMI160_TAP_SHOCK_DUR_MASK UINT8_C(0x40)
#define BMI160_TAP_QUIET_DUR_MASK UINT8_C(0x80)
#define BMI160_TAP_THRES_MASK UINT8_C(0x1F)
/** Mask definitions for INT_FLAT register */
#define BMI160_FLAT_THRES_MASK UINT8_C(0x3F)
#define BMI160_FLAT_HOLD_TIME_MASK UINT8_C(0x30)
#define BMI160_FLAT_HYST_MASK UINT8_C(0x07)
/** Mask definitions for INT_LOWHIGH register */
#define BMI160_LOW_G_HYST_MASK UINT8_C(0x03)
#define BMI160_LOW_G_LOW_MODE_MASK UINT8_C(0x04)
#define BMI160_HIGH_G_HYST_MASK UINT8_C(0xC0)
/** Mask definitions for INT_SIG_MOTION register */
#define BMI160_SIG_MOTION_SEL_MASK UINT8_C(0x02)
#define BMI160_SIG_MOTION_SKIP_MASK UINT8_C(0x0C)
#define BMI160_SIG_MOTION_PROOF_MASK UINT8_C(0x30)
/** Mask definitions for INT_ORIENT register */
#define BMI160_ORIENT_MODE_MASK UINT8_C(0x03)
#define BMI160_ORIENT_BLOCK_MASK UINT8_C(0x0C)
#define BMI160_ORIENT_HYST_MASK UINT8_C(0xF0)
#define BMI160_ORIENT_THETA_MASK UINT8_C(0x3F)
#define BMI160_ORIENT_UD_ENABLE UINT8_C(0x40)
#define BMI160_AXES_EN_MASK UINT8_C(0x80)
/** Mask definitions for FIFO_CONFIG register */
#define BMI160_FIFO_GYRO UINT8_C(0x80)
#define BMI160_FIFO_ACCEL UINT8_C(0x40)
#define BMI160_FIFO_AUX UINT8_C(0x20)
#define BMI160_FIFO_TAG_INT1 UINT8_C(0x08)
#define BMI160_FIFO_TAG_INT2 UINT8_C(0x04)
#define BMI160_FIFO_TIME UINT8_C(0x02)
#define BMI160_FIFO_HEADER UINT8_C(0x10)
#define BMI160_FIFO_CONFIG_1_MASK UINT8_C(0xFE)
/** Mask definitions for STEP_CONF register */
#define BMI160_STEP_COUNT_EN_BIT_MASK UINT8_C(0x08)
#define BMI160_STEP_DETECT_MIN_THRES_MASK UINT8_C(0x18)
#define BMI160_STEP_DETECT_STEPTIME_MIN_MASK UINT8_C(0x07)
#define BMI160_STEP_MIN_BUF_MASK UINT8_C(0x07)
/** Mask definition for FIFO Header Data Tag */
#define BMI160_FIFO_TAG_INTR_MASK UINT8_C(0xFC)
/** Fifo byte counter mask definitions */
#define BMI160_FIFO_BYTE_COUNTER_MASK UINT8_C(0x07)
/** Enable/disable bit value */
#define BMI160_ENABLE UINT8_C(0x01)
#define BMI160_DISABLE UINT8_C(0x00)
/** Latch Duration */
#define BMI160_LATCH_DUR_NONE UINT8_C(0x00)
#define BMI160_LATCH_DUR_312_5_MICRO_SEC UINT8_C(0x01)
#define BMI160_LATCH_DUR_625_MICRO_SEC UINT8_C(0x02)
#define BMI160_LATCH_DUR_1_25_MILLI_SEC UINT8_C(0x03)
#define BMI160_LATCH_DUR_2_5_MILLI_SEC UINT8_C(0x04)
#define BMI160_LATCH_DUR_5_MILLI_SEC UINT8_C(0x05)
#define BMI160_LATCH_DUR_10_MILLI_SEC UINT8_C(0x06)
#define BMI160_LATCH_DUR_20_MILLI_SEC UINT8_C(0x07)
#define BMI160_LATCH_DUR_40_MILLI_SEC UINT8_C(0x08)
#define BMI160_LATCH_DUR_80_MILLI_SEC UINT8_C(0x09)
#define BMI160_LATCH_DUR_160_MILLI_SEC UINT8_C(0x0A)
#define BMI160_LATCH_DUR_320_MILLI_SEC UINT8_C(0x0B)
#define BMI160_LATCH_DUR_640_MILLI_SEC UINT8_C(0x0C)
#define BMI160_LATCH_DUR_1_28_SEC UINT8_C(0x0D)
#define BMI160_LATCH_DUR_2_56_SEC UINT8_C(0x0E)
#define BMI160_LATCHED UINT8_C(0x0F)
/** BMI160 Register map */
#define BMI160_CHIP_ID_ADDR UINT8_C(0x00)
#define BMI160_ERROR_REG_ADDR UINT8_C(0x02)
#define BMI160_AUX_DATA_ADDR UINT8_C(0x04)
#define BMI160_GYRO_DATA_ADDR UINT8_C(0x0C)
#define BMI160_ACCEL_DATA_ADDR UINT8_C(0x12)
#define BMI160_FIFO_LENGTH_ADDR UINT8_C(0x22)
#define BMI160_FIFO_DATA_ADDR UINT8_C(0x24)
#define BMI160_ACCEL_CONFIG_ADDR UINT8_C(0x40)
#define BMI160_ACCEL_RANGE_ADDR UINT8_C(0x41)
#define BMI160_GYRO_CONFIG_ADDR UINT8_C(0x42)
#define BMI160_GYRO_RANGE_ADDR UINT8_C(0x43)
#define BMI160_AUX_ODR_ADDR UINT8_C(0x44)
#define BMI160_FIFO_DOWN_ADDR UINT8_C(0x45)
#define BMI160_FIFO_CONFIG_0_ADDR UINT8_C(0x46)
#define BMI160_FIFO_CONFIG_1_ADDR UINT8_C(0x47)
#define BMI160_AUX_IF_0_ADDR UINT8_C(0x4B)
#define BMI160_AUX_IF_1_ADDR UINT8_C(0x4C)
#define BMI160_AUX_IF_2_ADDR UINT8_C(0x4D)
#define BMI160_AUX_IF_3_ADDR UINT8_C(0x4E)
#define BMI160_AUX_IF_4_ADDR UINT8_C(0x4F)
#define BMI160_INT_ENABLE_0_ADDR UINT8_C(0x50)
#define BMI160_INT_ENABLE_1_ADDR UINT8_C(0x51)
#define BMI160_INT_ENABLE_2_ADDR UINT8_C(0x52)
#define BMI160_INT_OUT_CTRL_ADDR UINT8_C(0x53)
#define BMI160_INT_LATCH_ADDR UINT8_C(0x54)
#define BMI160_INT_MAP_0_ADDR UINT8_C(0x55)
#define BMI160_INT_MAP_1_ADDR UINT8_C(0x56)
#define BMI160_INT_MAP_2_ADDR UINT8_C(0x57)
#define BMI160_INT_DATA_0_ADDR UINT8_C(0x58)
#define BMI160_INT_DATA_1_ADDR UINT8_C(0x59)
#define BMI160_INT_LOWHIGH_0_ADDR UINT8_C(0x5A)
#define BMI160_INT_LOWHIGH_1_ADDR UINT8_C(0x5B)
#define BMI160_INT_LOWHIGH_2_ADDR UINT8_C(0x5C)
#define BMI160_INT_LOWHIGH_3_ADDR UINT8_C(0x5D)
#define BMI160_INT_LOWHIGH_4_ADDR UINT8_C(0x5E)
#define BMI160_INT_MOTION_0_ADDR UINT8_C(0x5F)
#define BMI160_INT_MOTION_1_ADDR UINT8_C(0x60)
#define BMI160_INT_MOTION_2_ADDR UINT8_C(0x61)
#define BMI160_INT_MOTION_3_ADDR UINT8_C(0x62)
#define BMI160_INT_TAP_0_ADDR UINT8_C(0x63)
#define BMI160_INT_TAP_1_ADDR UINT8_C(0x64)
#define BMI160_INT_ORIENT_0_ADDR UINT8_C(0x65)
#define BMI160_INT_ORIENT_1_ADDR UINT8_C(0x66)
#define BMI160_INT_FLAT_0_ADDR UINT8_C(0x67)
#define BMI160_INT_FLAT_1_ADDR UINT8_C(0x68)
#define BMI160_IF_CONF_ADDR UINT8_C(0x6B)
#define BMI160_INT_STEP_CNT_0_ADDR UINT8_C(0x78)
#define BMI160_INT_STEP_CONFIG_0_ADDR UINT8_C(0x7A)
#define BMI160_INT_STEP_CONFIG_1_ADDR UINT8_C(0x7B)
#define BMI160_COMMAND_REG_ADDR UINT8_C(0x7E)
#define BMI160_SPI_COMM_TEST_ADDR UINT8_C(0x7F)
#define BMI160_INTL_PULLUP_CONF_ADDR UINT8_C(0x85)
/** Error code definitions */
#define BMI160_OK INT8_C(0)
#define BMI160_E_NULL_PTR INT8_C(-1)
#define BMI160_E_COM_FAIL INT8_C(-2)
#define BMI160_E_DEV_NOT_FOUND INT8_C(-3)
#define BMI160_E_OUT_OF_RANGE INT8_C(-4)
#define BMI160_E_INVALID_INPUT INT8_C(-5)
#define BMI160_E_ACCEL_ODR_BW_INVALID INT8_C(-6)
#define BMI160_E_GYRO_ODR_BW_INVALID INT8_C(-7)
#define BMI160_E_LWP_PRE_FLTR_INT_INVALID INT8_C(-8)
#define BMI160_E_LWP_PRE_FLTR_INVALID INT8_C(-9)
#define BMI160_E_AUX_NOT_FOUND INT8_C(-10)
/** BMI160 unique chip identifier */
#define BMI160_CHIP_ID UINT8_C(0xD1)
/** Soft reset command */
#define BMI160_SOFT_RESET_CMD UINT8_C(0xb6)
#define BMI160_SOFT_RESET_DELAY_MS UINT8_C(15)
/* Delay in ms settings */
#define BMI160_ACCEL_DELAY_MS UINT8_C(5)
#define BMI160_GYRO_DELAY_MS UINT8_C(81)
#define BMI160_ONE_MS_DELAY UINT8_C(1)
#define BMI160_AUX_COM_DELAY UINT8_C(10)
/** Power mode settings */
/* Accel power mode */
#define BMI160_ACCEL_NORMAL_MODE UINT8_C(0x11)
#define BMI160_ACCEL_LOWPOWER_MODE UINT8_C(0x12)
#define BMI160_ACCEL_SUSPEND_MODE UINT8_C(0x10)
/* Gyro power mode */
#define BMI160_GYRO_SUSPEND_MODE UINT8_C(0x14)
#define BMI160_GYRO_NORMAL_MODE UINT8_C(0x15)
#define BMI160_GYRO_FASTSTARTUP_MODE UINT8_C(0x17)
/* Aux power mode */
#define BMI160_AUX_SUSPEND_MODE UINT8_C(0x18)
#define BMI160_AUX_NORMAL_MODE UINT8_C(0x19)
#define BMI160_AUX_LOWPOWER_MODE UINT8_C(0x1A)
/** Range settings */
/* Accel Range */
#define BMI160_ACCEL_RANGE_2G UINT8_C(0x03)
#define BMI160_ACCEL_RANGE_4G UINT8_C(0x05)
#define BMI160_ACCEL_RANGE_8G UINT8_C(0x08)
#define BMI160_ACCEL_RANGE_16G UINT8_C(0x0C)
/* Gyro Range */
#define BMI160_GYRO_RANGE_2000_DPS UINT8_C(0x00)
#define BMI160_GYRO_RANGE_1000_DPS UINT8_C(0x01)
#define BMI160_GYRO_RANGE_500_DPS UINT8_C(0x02)
#define BMI160_GYRO_RANGE_250_DPS UINT8_C(0x03)
#define BMI160_GYRO_RANGE_125_DPS UINT8_C(0x04)
/** Bandwidth settings */
/* Accel Bandwidth */
#define BMI160_ACCEL_BW_OSR4_AVG1 UINT8_C(0x00)
#define BMI160_ACCEL_BW_OSR2_AVG2 UINT8_C(0x01)
#define BMI160_ACCEL_BW_NORMAL_AVG4 UINT8_C(0x02)
#define BMI160_ACCEL_BW_CIC_AVG8 UINT8_C(0x03)
#define BMI160_ACCEL_BW_RES_AVG16 UINT8_C(0x04)
#define BMI160_ACCEL_BW_RES_AVG32 UINT8_C(0x05)
#define BMI160_ACCEL_BW_RES_AVG64 UINT8_C(0x06)
#define BMI160_ACCEL_BW_RES_AVG128 UINT8_C(0x07)
#define BMI160_GYRO_BW_OSR4_MODE UINT8_C(0x00)
#define BMI160_GYRO_BW_OSR2_MODE UINT8_C(0x01)
#define BMI160_GYRO_BW_NORMAL_MODE UINT8_C(0x02)
#define BMI160_GYRO_BW_CIC_MODE UINT8_C(0x03)
/* Output Data Rate settings */
/* Accel Output data rate */
#define BMI160_ACCEL_ODR_RESERVED UINT8_C(0x00)
#define BMI160_ACCEL_ODR_0_78HZ UINT8_C(0x01)
#define BMI160_ACCEL_ODR_1_56HZ UINT8_C(0x02)
#define BMI160_ACCEL_ODR_3_12HZ UINT8_C(0x03)
#define BMI160_ACCEL_ODR_6_25HZ UINT8_C(0x04)
#define BMI160_ACCEL_ODR_12_5HZ UINT8_C(0x05)
#define BMI160_ACCEL_ODR_25HZ UINT8_C(0x06)
#define BMI160_ACCEL_ODR_50HZ UINT8_C(0x07)
#define BMI160_ACCEL_ODR_100HZ UINT8_C(0x08)
#define BMI160_ACCEL_ODR_200HZ UINT8_C(0x09)
#define BMI160_ACCEL_ODR_400HZ UINT8_C(0x0A)
#define BMI160_ACCEL_ODR_800HZ UINT8_C(0x0B)
#define BMI160_ACCEL_ODR_1600HZ UINT8_C(0x0C)
#define BMI160_ACCEL_ODR_RESERVED0 UINT8_C(0x0D)
#define BMI160_ACCEL_ODR_RESERVED1 UINT8_C(0x0E)
#define BMI160_ACCEL_ODR_RESERVED2 UINT8_C(0x0F)
/* Gyro Output data rate */
#define BMI160_GYRO_ODR_RESERVED UINT8_C(0x00)
#define BMI160_GYRO_ODR_25HZ UINT8_C(0x06)
#define BMI160_GYRO_ODR_50HZ UINT8_C(0x07)
#define BMI160_GYRO_ODR_100HZ UINT8_C(0x08)
#define BMI160_GYRO_ODR_200HZ UINT8_C(0x09)
#define BMI160_GYRO_ODR_400HZ UINT8_C(0x0A)
#define BMI160_GYRO_ODR_800HZ UINT8_C(0x0B)
#define BMI160_GYRO_ODR_1600HZ UINT8_C(0x0C)
#define BMI160_GYRO_ODR_3200HZ UINT8_C(0x0D)
/* Auxiliary sensor Output data rate */
#define BMI160_AUX_ODR_RESERVED UINT8_C(0x00)
#define BMI160_AUX_ODR_0_78HZ UINT8_C(0x01)
#define BMI160_AUX_ODR_1_56HZ UINT8_C(0x02)
#define BMI160_AUX_ODR_3_12HZ UINT8_C(0x03)
#define BMI160_AUX_ODR_6_25HZ UINT8_C(0x04)
#define BMI160_AUX_ODR_12_5HZ UINT8_C(0x05)
#define BMI160_AUX_ODR_25HZ UINT8_C(0x06)
#define BMI160_AUX_ODR_50HZ UINT8_C(0x07)
#define BMI160_AUX_ODR_100HZ UINT8_C(0x08)
#define BMI160_AUX_ODR_200HZ UINT8_C(0x09)
#define BMI160_AUX_ODR_400HZ UINT8_C(0x0A)
#define BMI160_AUX_ODR_800HZ UINT8_C(0x0B)
/* Maximum limits definition */
#define BMI160_ACCEL_ODR_MAX UINT8_C(15)
#define BMI160_ACCEL_BW_MAX UINT8_C(2)
#define BMI160_ACCEL_RANGE_MAX UINT8_C(12)
#define BMI160_GYRO_ODR_MAX UINT8_C(13)
#define BMI160_GYRO_BW_MAX UINT8_C(2)
#define BMI160_GYRO_RANGE_MAX UINT8_C(4)
/** FIFO_CONFIG Definitions */
#define BMI160_FIFO_TIME_ENABLE UINT8_C(0x02)
#define BMI160_FIFO_TAG_INT2_ENABLE UINT8_C(0x04)
#define BMI160_FIFO_TAG_INT1_ENABLE UINT8_C(0x08)
#define BMI160_FIFO_HEAD_ENABLE UINT8_C(0x10)
#define BMI160_FIFO_M_ENABLE UINT8_C(0x20)
#define BMI160_FIFO_A_ENABLE UINT8_C(0x40)
#define BMI160_FIFO_M_A_ENABLE UINT8_C(0x60)
#define BMI160_FIFO_G_ENABLE UINT8_C(0x80)
#define BMI160_FIFO_M_G_ENABLE UINT8_C(0xA0)
#define BMI160_FIFO_G_A_ENABLE UINT8_C(0xC0)
#define BMI160_FIFO_M_G_A_ENABLE UINT8_C(0xE0)
/* Accel, gyro and aux. sensor length and also their combined
* length definitions in FIFO */
#define BMI160_FIFO_G_LENGTH UINT8_C(6)
#define BMI160_FIFO_A_LENGTH UINT8_C(6)
#define BMI160_FIFO_M_LENGTH UINT8_C(8)
#define BMI160_FIFO_GA_LENGTH UINT8_C(12)
#define BMI160_FIFO_MA_LENGTH UINT8_C(14)
#define BMI160_FIFO_MG_LENGTH UINT8_C(14)
#define BMI160_FIFO_MGA_LENGTH UINT8_C(20)
/** FIFO Header Data definitions */
#define BMI160_FIFO_HEAD_SKIP_FRAME UINT8_C(0x40)
#define BMI160_FIFO_HEAD_SENSOR_TIME UINT8_C(0x44)
#define BMI160_FIFO_HEAD_INPUT_CONFIG UINT8_C(0x48)
#define BMI160_FIFO_HEAD_OVER_READ UINT8_C(0x80)
#define BMI160_FIFO_HEAD_A UINT8_C(0x84)
#define BMI160_FIFO_HEAD_G UINT8_C(0x88)
#define BMI160_FIFO_HEAD_G_A UINT8_C(0x8C)
#define BMI160_FIFO_HEAD_M UINT8_C(0x90)
#define BMI160_FIFO_HEAD_M_A UINT8_C(0x94)
#define BMI160_FIFO_HEAD_M_G UINT8_C(0x98)
#define BMI160_FIFO_HEAD_M_G_A UINT8_C(0x9C)
/** FIFO sensor time length definitions */
#define BMI160_SENSOR_TIME_LENGTH UINT8_C(3)
/** FIFO DOWN selection */
/* Accel fifo down-sampling values*/
#define BMI160_ACCEL_FIFO_DOWN_ZERO UINT8_C(0x00)
#define BMI160_ACCEL_FIFO_DOWN_ONE UINT8_C(0x10)
#define BMI160_ACCEL_FIFO_DOWN_TWO UINT8_C(0x20)
#define BMI160_ACCEL_FIFO_DOWN_THREE UINT8_C(0x30)
#define BMI160_ACCEL_FIFO_DOWN_FOUR UINT8_C(0x40)
#define BMI160_ACCEL_FIFO_DOWN_FIVE UINT8_C(0x50)
#define BMI160_ACCEL_FIFO_DOWN_SIX UINT8_C(0x60)
#define BMI160_ACCEL_FIFO_DOWN_SEVEN UINT8_C(0x70)
/* Gyro fifo down-smapling values*/
#define BMI160_GYRO_FIFO_DOWN_ZERO UINT8_C(0x00)
#define BMI160_GYRO_FIFO_DOWN_ONE UINT8_C(0x01)
#define BMI160_GYRO_FIFO_DOWN_TWO UINT8_C(0x02)
#define BMI160_GYRO_FIFO_DOWN_THREE UINT8_C(0x03)
#define BMI160_GYRO_FIFO_DOWN_FOUR UINT8_C(0x04)
#define BMI160_GYRO_FIFO_DOWN_FIVE UINT8_C(0x05)
#define BMI160_GYRO_FIFO_DOWN_SIX UINT8_C(0x06)
#define BMI160_GYRO_FIFO_DOWN_SEVEN UINT8_C(0x07)
/* Accel Fifo filter enable*/
#define BMI160_ACCEL_FIFO_FILT_EN UINT8_C(0x80)
/* Gyro Fifo filter enable*/
#define BMI160_GYRO_FIFO_FILT_EN UINT8_C(0x08)
/** Definitions to check validity of FIFO frames */
#define FIFO_CONFIG_MSB_CHECK UINT8_C(0x80)
#define FIFO_CONFIG_LSB_CHECK UINT8_C(0x00)
/** Array Parameter DefinItions */
#define BMI160_SENSOR_TIME_LSB_BYTE UINT8_C(0)
#define BMI160_SENSOR_TIME_XLSB_BYTE UINT8_C(1)
#define BMI160_SENSOR_TIME_MSB_BYTE UINT8_C(2)
/** Interface settings */
#define BMI160_SPI_INTF UINT8_C(1)
#define BMI160_I2C_INTF UINT8_C(0)
#define BMI160_SPI_RD_MASK UINT8_C(0x80)
#define BMI160_SPI_WR_MASK UINT8_C(0x7F)
/* Sensor & time select definition*/
#define BMI160_ACCEL_SEL UINT8_C(0x01)
#define BMI160_GYRO_SEL UINT8_C(0x02)
#define BMI160_TIME_SEL UINT8_C(0x04)
/* Sensor select mask*/
#define BMI160_SEN_SEL_MASK UINT8_C(0x07)
/* Error code mask */
#define BMI160_ERR_REG_MASK UINT8_C(0x0F)
/* BMI160 I2C address */
#define BMI160_I2C_ADDR UINT8_C(0x68)
/* BMI160 secondary IF address */
#define BMI160_AUX_BMM150_I2C_ADDR UINT8_C(0x10)
/** BMI160 Length definitions */
#define BMI160_ONE UINT8_C(1)
#define BMI160_TWO UINT8_C(2)
#define BMI160_THREE UINT8_C(3)
#define BMI160_FOUR UINT8_C(4)
#define BMI160_FIVE UINT8_C(5)
/** BMI160 fifo level Margin */
#define BMI160_FIFO_LEVEL_MARGIN UINT8_C(16)
/** BMI160 fifo flush Command */
#define BMI160_FIFO_FLUSH_VALUE UINT8_C(0xB0)
/** BMI160 fifo full interrupt position and mask */
#define BMI160_FIFO_FULL_INT_POS UINT8_C(5)
#define BMI160_FIFO_FULL_INT_MSK UINT8_C(0x20)
#define BMI160_FIFO_WTM_INT_POS UINT8_C(6)
#define BMI160_FIFO_WTM_INT_MSK UINT8_C(0x40)
#define BMI160_FIFO_FULL_INT_PIN1_POS UINT8_C(5)
#define BMI160_FIFO_FULL_INT_PIN1_MSK UINT8_C(0x20)
#define BMI160_FIFO_FULL_INT_PIN2_POS UINT8_C(1)
#define BMI160_FIFO_FULL_INT_PIN2_MSK UINT8_C(0x02)
#define BMI160_FIFO_WTM_INT_PIN1_POS UINT8_C(6)
#define BMI160_FIFO_WTM_INT_PIN1_MSK UINT8_C(0x40)
#define BMI160_FIFO_WTM_INT_PIN2_POS UINT8_C(2)
#define BMI160_FIFO_WTM_INT_PIN2_MSK UINT8_C(0x04)
#define BMI160_MANUAL_MODE_EN_POS UINT8_C(7)
#define BMI160_MANUAL_MODE_EN_MSK UINT8_C(0x80)
#define BMI160_AUX_READ_BURST_POS UINT8_C(0)
#define BMI160_AUX_READ_BURST_MSK UINT8_C(0x03)
/* BIT SLICE GET AND SET FUNCTIONS */
#define BMI160_GET_BITS(regvar, bitname)\
((regvar & bitname##_MSK) >> bitname##_POS)
#define BMI160_SET_BITS(regvar, bitname, val)\
((regvar & ~bitname##_MSK) | \
((val<<bitname##_POS)&bitname##_MSK))
#define BMI160_SET_BITS_POS_0(reg_data, bitname, data) \
((reg_data & ~(bitname##_MSK)) | \
(data & bitname##_MSK))
#define BMI160_GET_BITS_POS_0(reg_data, bitname) (reg_data & (bitname##_MSK))
/*****************************************************************************/
/* type definitions */
typedef int8_t (*bmi160_com_fptr_t)(uint8_t dev_addr, uint8_t reg_addr,
uint8_t *data, uint16_t len);
typedef void (*bmi160_delay_fptr_t)(uint32_t period);
/*************************** Data structures *********************************/
/*!
* @brief bmi160 sensor data structure which comprises of accel data
*/
struct bmi160_sensor_data {
/*! X-axis sensor data */
int16_t x;
/*! Y-axis sensor data */
int16_t y;
/*! Z-axis sensor data */
int16_t z;
/*! sensor time */
uint32_t sensortime;
};
/*!
* @brief FIFO aux. sensor data structure
*/
struct bmi160_aux_fifo_data {
/*! The value of aux. sensor x LSB data */
uint8_t aux_x_lsb;
/*! The value of aux. sensor x MSB data */
uint8_t aux_x_msb;
/*! The value of aux. sensor y LSB data */
uint8_t aux_y_lsb;
/*! The value of aux. sensor y MSB data */
uint8_t aux_y_msb;
/*! The value of aux. sensor z LSB data */
uint8_t aux_z_lsb;
/*! The value of aux. sensor z MSB data */
uint8_t aux_z_msb;
/*! The value of aux. sensor r for BMM150 LSB data */
uint8_t aux_r_y2_lsb;
/*! The value of aux. sensor r for BMM150 MSB data */
uint8_t aux_r_y2_msb;
};
/*!
* @brief bmi160 sensor select structure
*/
enum bmi160_select_sensor {
BMI160_ACCEL_ONLY = 1,
BMI160_GYRO_ONLY,
BMI160_BOTH_ACCEL_AND_GYRO
};
/*!
* @brief bmi160 sensor step detector mode structure
*/
enum bmi160_step_detect_mode {
BMI160_STEP_DETECT_NORMAL,
BMI160_STEP_DETECT_SENSITIVE,
BMI160_STEP_DETECT_ROBUST,
/*! Non recommended User defined setting */
BMI160_STEP_DETECT_USER_DEFINE
};
/*!
* @brief enum for auxiliary burst read selection
*/
enum bm160_aux_read_len {
BMI160_AUX_READ_LEN_0,
BMI160_AUX_READ_LEN_1,
BMI160_AUX_READ_LEN_2,
BMI160_AUX_READ_LEN_3
};
/*!
* @brief bmi160 sensor configuration structure
*/
struct bmi160_cfg {
/*! power mode */
uint8_t power;
/*! output data rate */
uint8_t odr;
/*! range */
uint8_t range;
/*! bandwidth */
uint8_t bw;
};
/*!
* @brief Aux sensor configuration structure
*/
struct bmi160_aux_cfg {
/*! Aux sensor, 1 - enable 0 - disable */
uint8_t aux_sensor_enable : 1;
/*! Aux manual/auto mode status */
uint8_t manual_enable : 1;
/*! Aux read burst length */
uint8_t aux_rd_burst_len : 2;
/*! output data rate */
uint8_t aux_odr :4;
/*! i2c addr of auxiliary sensor */
uint8_t aux_i2c_addr;
};
/*!
* @brief bmi160 interrupt channel selection structure
*/
enum bmi160_int_channel {
/*! interrupt Channel 1 */
BMI160_INT_CHANNEL_1,
/*! interrupt Channel 2 */
BMI160_INT_CHANNEL_2
};
enum bmi160_int_types {
/*! Slope/Any-motion interrupt */
BMI160_ACC_ANY_MOTION_INT,
/*! Significant motion interrupt */
BMI160_ACC_SIG_MOTION_INT,
/*! Step detector interrupt */
BMI160_STEP_DETECT_INT,
/*! double tap interrupt */
BMI160_ACC_DOUBLE_TAP_INT,
/*! single tap interrupt */
BMI160_ACC_SINGLE_TAP_INT,
/*! orientation interrupt */
BMI160_ACC_ORIENT_INT,
/*! flat interrupt */
BMI160_ACC_FLAT_INT,
/*! high-g interrupt */
BMI160_ACC_HIGH_G_INT,
/*! low-g interrupt */
BMI160_ACC_LOW_G_INT,
/*! slow/no-motion interrupt */
BMI160_ACC_SLOW_NO_MOTION_INT,
/*! data ready interrupt */
BMI160_ACC_GYRO_DATA_RDY_INT,
/*! fifo full interrupt */
BMI160_ACC_GYRO_FIFO_FULL_INT,
/*! fifo watermark interrupt */
BMI160_ACC_GYRO_FIFO_WATERMARK_INT
};
/*!
* @brief bmi160 active state of any & sig motion interrupt.
*/
enum bmi160_any_sig_motion_active_interrupt_state {
/*! Both any & sig motion are disabled */
BMI160_BOTH_ANY_SIG_MOTION_DISABLED = -1,
/*! Any-motion selected */
BMI160_ANY_MOTION_ENABLED,
/*! Sig-motion selected */
BMI160_SIG_MOTION_ENABLED
};
struct bmi160_acc_tap_int_cfg {
#if LITTLE_ENDIAN == 1
/*! tap threshold */
uint16_t tap_thr :5;
/*! tap shock */
uint16_t tap_shock :1;
/*! tap quiet */
uint16_t tap_quiet :1;
/*! tap duration */
uint16_t tap_dur :3;
/*! data source 0- filter & 1 pre-filter*/
uint16_t tap_data_src :1;
/*! tap enable, 1 - enable, 0 - disable */
uint16_t tap_en :1;
#elif BIG_ENDIAN == 1
/*! tap enable, 1 - enable, 0 - disable */
uint16_t tap_en :1;
/*! data source 0- filter & 1 pre-filter*/
uint16_t tap_data_src :1;
/*! tap duration */
uint16_t tap_dur : 3;
/*! tap quiet */
uint16_t tap_quiet : 1;
/*! tap shock */
uint16_t tap_shock : 1;
/*! tap threshold */
uint16_t tap_thr : 5;
#endif
};
struct bmi160_acc_any_mot_int_cfg {
#if LITTLE_ENDIAN == 1
/*! 1 any-motion enable, 0 - any-motion disable */
uint8_t anymotion_en :1;
/*! slope interrupt x, 1 - enable, 0 - disable */
uint8_t anymotion_x :1;
/*! slope interrupt y, 1 - enable, 0 - disable */
uint8_t anymotion_y :1;
/*! slope interrupt z, 1 - enable, 0 - disable */
uint8_t anymotion_z :1;
/*! slope duration */
uint8_t anymotion_dur :2;
/*! data source 0- filter & 1 pre-filter*/
uint8_t anymotion_data_src :1;
/*! slope threshold */
uint8_t anymotion_thr;
#elif BIG_ENDIAN == 1
/*! slope threshold */
uint8_t anymotion_thr;
/*! data source 0- filter & 1 pre-filter*/
uint8_t anymotion_data_src :1;
/*! slope duration */
uint8_t anymotion_dur : 2;
/*! slope interrupt z, 1 - enable, 0 - disable */
uint8_t anymotion_z : 1;
/*! slope interrupt y, 1 - enable, 0 - disable */
uint8_t anymotion_y : 1;
/*! slope interrupt x, 1 - enable, 0 - disable */
uint8_t anymotion_x : 1;
/*! 1 any-motion enable, 0 - any-motion disable */
uint8_t anymotion_en :1;
#endif
};
struct bmi160_acc_sig_mot_int_cfg {
#if LITTLE_ENDIAN == 1
/*! skip time of sig-motion interrupt */
uint8_t sig_mot_skip :2;
/*! proof time of sig-motion interrupt */
uint8_t sig_mot_proof :2;
/*! data source 0- filter & 1 pre-filter*/
uint8_t sig_data_src :1;
/*! 1 - enable sig, 0 - disable sig & enable anymotion */
uint8_t sig_en :1;
/*! sig-motion threshold */
uint8_t sig_mot_thres;
#elif BIG_ENDIAN == 1
/*! sig-motion threshold */
uint8_t sig_mot_thres;
/*! 1 - enable sig, 0 - disable sig & enable anymotion */
uint8_t sig_en :1;
/*! data source 0- filter & 1 pre-filter*/
uint8_t sig_data_src :1;
/*! proof time of sig-motion interrupt */
uint8_t sig_mot_proof : 2;
/*! skip time of sig-motion interrupt */
uint8_t sig_mot_skip : 2;
#endif
};
struct bmi160_acc_step_detect_int_cfg {
#if LITTLE_ENDIAN == 1
/*! 1- step detector enable, 0- step detector disable */
uint16_t step_detector_en :1;
/*! minimum threshold */
uint16_t min_threshold :2;
/*! minimal detectable step time */
uint16_t steptime_min :3;
/*! enable step counter mode setting */
uint16_t step_detector_mode :2;
/*! minimum step buffer size*/
uint16_t step_min_buf :3;
#elif BIG_ENDIAN == 1
/*! minimum step buffer size*/
uint16_t step_min_buf :3;
/*! enable step counter mode setting */
uint16_t step_detector_mode : 2;
/*! minimal detectable step time */
uint16_t steptime_min : 3;
/*! minimum threshold */
uint16_t min_threshold : 2;
/*! 1- step detector enable, 0- step detector disable */
uint16_t step_detector_en :1;
#endif
};
struct bmi160_acc_no_motion_int_cfg {
#if LITTLE_ENDIAN == 1
/*! no motion interrupt x */
uint16_t no_motion_x :1;
/*! no motion interrupt y */
uint16_t no_motion_y :1;
/*! no motion interrupt z */
uint16_t no_motion_z :1;
/*! no motion duration */
uint16_t no_motion_dur :6;
/*! no motion sel , 1 - enable no-motion ,0- enable slow-motion */
uint16_t no_motion_sel :1;
/*! data source 0- filter & 1 pre-filter*/
uint16_t no_motion_src :1;
/*! no motion threshold */
uint8_t no_motion_thres;
#elif BIG_ENDIAN == 1
/*! no motion threshold */
uint8_t no_motion_thres;
/*! data source 0- filter & 1 pre-filter*/
uint16_t no_motion_src :1;
/*! no motion sel , 1 - enable no-motion ,0- enable slow-motion */
uint16_t no_motion_sel : 1;
/*! no motion duration */
uint16_t no_motion_dur : 6;
/* no motion interrupt z */
uint16_t no_motion_z :1;
/*! no motion interrupt y */
uint16_t no_motion_y :1;
/*! no motion interrupt x */
uint16_t no_motion_x :1;
#endif
};
struct bmi160_acc_orient_int_cfg {
#if LITTLE_ENDIAN == 1
/*! thresholds for switching between the different orientations */
uint16_t orient_mode :2;
/*! blocking_mode */
uint16_t orient_blocking :2;
/*! Orientation interrupt hysteresis */
uint16_t orient_hyst :4;
/*! Orientation interrupt theta */
uint16_t orient_theta :6;
/*! Enable/disable Orientation interrupt */
uint16_t orient_ud_en :1;
/*! exchange x- and z-axis in algorithm ,0 - z, 1 - x */
uint16_t axes_ex :1;
/*! 1 - orient enable, 0 - orient disable */
uint8_t orient_en :1;
#elif BIG_ENDIAN == 1
/*! 1 - orient enable, 0 - orient disable */
uint8_t orient_en :1;
/*! exchange x- and z-axis in algorithm ,0 - z, 1 - x */
uint16_t axes_ex : 1;
/*! Enable/disable Orientation interrupt */
uint16_t orient_ud_en : 1;
/*! Orientation interrupt theta */
uint16_t orient_theta : 6;
/*! Orientation interrupt hysteresis */
uint16_t orient_hyst : 4;
/*! blocking_mode */
uint16_t orient_blocking : 2;
/*! thresholds for switching between the different orientations */
uint16_t orient_mode : 2;
#endif
};
struct bmi160_acc_flat_detect_int_cfg {
#if LITTLE_ENDIAN == 1
/*! flat threshold */
uint16_t flat_theta :6;
/*! flat interrupt hysteresis */
uint16_t flat_hy :3;
/*! delay time for which the flat value must remain stable for the
* flat interrupt to be generated */
uint16_t flat_hold_time :2;
/*! 1 - flat enable, 0 - flat disable */
uint16_t flat_en :1;
#elif BIG_ENDIAN == 1
/*! 1 - flat enable, 0 - flat disable */
uint16_t flat_en :1;
/*! delay time for which the flat value must remain stable for the
* flat interrupt to be generated */
uint16_t flat_hold_time : 2;
/*! flat interrupt hysteresis */
uint16_t flat_hy : 3;
/*! flat threshold */
uint16_t flat_theta : 6;
#endif
};
struct bmi160_acc_low_g_int_cfg {
#if LITTLE_ENDIAN == 1
/*! low-g interrupt trigger delay */
uint8_t low_dur;
/*! low-g interrupt trigger threshold */
uint8_t low_thres;
/*! hysteresis of low-g interrupt */
uint8_t low_hyst :2;
/*! 0 - single-axis mode ,1 - axis-summing mode */
uint8_t low_mode :1;
/*! data source 0- filter & 1 pre-filter */
uint8_t low_data_src :1;
/*! 1 - enable low-g, 0 - disable low-g */
uint8_t low_en :1;
#elif BIG_ENDIAN == 1
/*! 1 - enable low-g, 0 - disable low-g */
uint8_t low_en :1;
/*! data source 0- filter & 1 pre-filter */
uint8_t low_data_src :1;
/*! 0 - single-axis mode ,1 - axis-summing mode */
uint8_t low_mode : 1;
/*! hysteresis of low-g interrupt */
uint8_t low_hyst : 2;
/*! low-g interrupt trigger threshold */
uint8_t low_thres;
/*! low-g interrupt trigger delay */
uint8_t low_dur;
#endif
};
struct bmi160_acc_high_g_int_cfg {
#if LITTLE_ENDIAN == 1
/*! High-g interrupt x, 1 - enable, 0 - disable */
uint8_t high_g_x :1;
/*! High-g interrupt y, 1 - enable, 0 - disable */
uint8_t high_g_y :1;
/*! High-g interrupt z, 1 - enable, 0 - disable */
uint8_t high_g_z :1;
/*! High-g hysteresis */
uint8_t high_hy :2;
/*! data source 0- filter & 1 pre-filter */
uint8_t high_data_src :1;
/*! High-g threshold */
uint8_t high_thres;
/*! High-g duration */
uint8_t high_dur;
#elif BIG_ENDIAN == 1
/*! High-g duration */
uint8_t high_dur;
/*! High-g threshold */
uint8_t high_thres;
/*! data source 0- filter & 1 pre-filter */
uint8_t high_data_src :1;
/*! High-g hysteresis */
uint8_t high_hy : 2;
/*! High-g interrupt z, 1 - enable, 0 - disable */
uint8_t high_g_z : 1;
/*! High-g interrupt y, 1 - enable, 0 - disable */
uint8_t high_g_y : 1;
/*! High-g interrupt x, 1 - enable, 0 - disable */
uint8_t high_g_x : 1;
#endif
};
struct bmi160_int_pin_settg {
#if LITTLE_ENDIAN == 1
/*! To enable either INT1 or INT2 pin as output.
* 0- output disabled ,1- output enabled */
uint16_t output_en :1;
/*! 0 - push-pull 1- open drain,only valid if output_en is set 1 */
uint16_t output_mode :1;
/*! 0 - active low , 1 - active high level.
* if output_en is 1,this applies to interrupts,else PMU_trigger */
uint16_t output_type :1;
/*! 0 - level trigger , 1 - edge trigger */
uint16_t edge_ctrl :1;
/*! To enable either INT1 or INT2 pin as input.
* 0 - input disabled ,1 - input enabled */
uint16_t input_en :1;
/*! latch duration*/
uint16_t latch_dur :4;
#elif BIG_ENDIAN == 1
/*! latch duration*/
uint16_t latch_dur : 4;
/*! Latched,non-latched or temporary interrupt modes */
uint16_t input_en : 1;
/*! 1 - edge trigger, 0 - level trigger */
uint16_t edge_ctrl : 1;
/*! 0 - active low , 1 - active high level.
* if output_en is 1,this applies to interrupts,else PMU_trigger */
uint16_t output_type : 1;
/*! 0 - push-pull , 1 - open drain,only valid if output_en is set 1 */
uint16_t output_mode : 1;
/*! To enable either INT1 or INT2 pin as output.
* 0 - output disabled , 1 - output enabled */
uint16_t output_en : 1;
#endif
};
union bmi160_int_type_cfg {
/*! Tap interrupt structure */
struct bmi160_acc_tap_int_cfg acc_tap_int;
/*! Slope interrupt structure */
struct bmi160_acc_any_mot_int_cfg acc_any_motion_int;
/*! Significant motion interrupt structure */
struct bmi160_acc_sig_mot_int_cfg acc_sig_motion_int;
/*! Step detector interrupt structure */
struct bmi160_acc_step_detect_int_cfg acc_step_detect_int;
/*! No motion interrupt structure */
struct bmi160_acc_no_motion_int_cfg acc_no_motion_int;
/*! Orientation interrupt structure */
struct bmi160_acc_orient_int_cfg acc_orient_int;
/*! Flat interrupt structure */
struct bmi160_acc_flat_detect_int_cfg acc_flat_int;
/*! Low-g interrupt structure */
struct bmi160_acc_low_g_int_cfg acc_low_g_int;
/*! High-g interrupt structure */
struct bmi160_acc_high_g_int_cfg acc_high_g_int;
};
struct bmi160_int_settg {
/*! Interrupt channel */
enum bmi160_int_channel int_channel;
/*! Select Interrupt */
enum bmi160_int_types int_type;
/*! Structure configuring Interrupt pins */
struct bmi160_int_pin_settg int_pin_settg;
/*! Union configures required interrupt */
union bmi160_int_type_cfg int_type_cfg;
/*! FIFO FULL INT 1-enable, 0-disable */
uint8_t fifo_full_int_en :1;
/*! FIFO WTM INT 1-enable, 0-disable */
uint8_t fifo_WTM_int_en :1;
};
/*!
* @brief This structure holds the information for usage of
* FIFO by the user.
*/
struct bmi160_fifo_frame {
/*! Data buffer of user defined length is to be mapped here */
uint8_t *data;
/*! While calling the API "bmi160_get_fifo_data" , length stores
* number of bytes in FIFO to be read (specified by user as input)
* and after execution of the API ,number of FIFO data bytes
* available is provided as an output to user
*/
uint16_t length;
/*! FIFO time enable */
uint8_t fifo_time_enable;
/*! Enabling of the FIFO header to stream in header mode */
uint8_t fifo_header_enable;
/*! Streaming of the Accelerometer, Gyroscope
sensor data or both in FIFO */
uint8_t fifo_data_enable;
/*! Will be equal to length when no more frames are there to parse */
uint16_t accel_byte_start_idx;
/*! Will be equal to length when no more frames are there to parse */
uint16_t gyro_byte_start_idx;
/*! Will be equal to length when no more frames are there to parse */
uint16_t aux_byte_start_idx;
/*! Value of FIFO sensor time time */
uint32_t sensor_time;
/*! Value of Skipped frame counts */
uint8_t skipped_frame_count;
};
struct bmi160_dev {
/*! Chip Id */
uint8_t chip_id;
/*! Device Id */
uint8_t id;
/*! 0 - I2C , 1 - SPI Interface */
uint8_t interface;
/*! Hold active interrupts status for any and sig motion
* 0 - Any-motion enable, 1 - Sig-motion enable,
* -1 neither any-motion nor sig-motion selected */
enum bmi160_any_sig_motion_active_interrupt_state any_sig_sel;
/*! Structure to configure Accel sensor */
struct bmi160_cfg accel_cfg;
/*! Structure to hold previous/old accel config parameters.
* This is used at driver level to prevent overwriting of same
* data, hence user does not change it in the code */
struct bmi160_cfg prev_accel_cfg;
/*! Structure to configure Gyro sensor */
struct bmi160_cfg gyro_cfg;
/*! Structure to hold previous/old gyro config parameters.
* This is used at driver level to prevent overwriting of same
* data, hence user does not change it in the code */
struct bmi160_cfg prev_gyro_cfg;
/*! Structure to configure the auxiliary sensor */
struct bmi160_aux_cfg aux_cfg;
/*! Structure to hold previous/old aux config parameters.
* This is used at driver level to prevent overwriting of same
* data, hence user does not change it in the code */
struct bmi160_aux_cfg prev_aux_cfg;
/*! FIFO related configurations */
struct bmi160_fifo_frame *fifo;
/*! Read function pointer */
bmi160_com_fptr_t read;
/*! Write function pointer */
bmi160_com_fptr_t write;
/*! Delay function pointer */
bmi160_delay_fptr_t delay_ms;
};
/*************************** C++ guard macro *****************************/
#ifdef __cplusplus
}
#endif
#endif /* BMI160_DEFS_H_ */
/**
* Copyright (C) 2015 - 2016 Bosch Sensortec GmbH
*
* 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.
*
* @file bmm150.h
* @date 1 Mar 2017
* @version 0.8.0
* @brief
*
*/
/*! @file bmm150.h */
/*!
* @defgroup BMM150 SENSOR API
* @{*/
#ifndef BMM150_H__
#define BMM150_H__
/*! CPP guard */
#ifdef __cplusplus
extern "C"
{
#endif
/*********************************************************************/
/* header files */
#include "../interface/bmm150_defs.h"
/*********************************************************************/
/* (extern) variable declarations */
/*********************************************************************/
/* function prototype declarations */
/*!
* @brief This API is the entry point, Call this API before using other APIs.
* This API reads the chip-id of the sensor which is the first step to
* verify the sensor and also it configures the read mechanism of SPI and
* I2C interface.
*
* @param[in,out] dev : Structure instance of bmm150_dev
* @note : Refer user guide for detailed info.
*
* @return Result of API execution status
* @retval zero -> Success / +ve value -> Warning / -ve value -> Error
*/
int8_t bmm150_init(struct bmm150_dev *dev);
/*!
* @brief This API writes the given data to the register address
* of the sensor.
*
* @param[in] reg_addr : Register address from where the data to be written.
* @param[in] reg_data : Pointer to data buffer which is to be written
* in the reg_addr of sensor.
* @param[in] len : No of bytes of data to write..
* @param[in] dev : Structure instance of bmm150_dev.
*
* @return Result of API execution status
* @retval zero -> Success / +ve value -> Warning / -ve value -> Error
*/
int8_t bmm150_set_regs(uint8_t reg_addr, uint8_t *reg_data, uint8_t len, const struct bmm150_dev *dev);
/*!
* @brief This API reads the data from the given register address of sensor.
*
* @param[in] reg_addr : Register address from where the data to be read
* @param[out] reg_data : Pointer to data buffer to store the read data.
* @param[in] len : No of bytes of data to be read.
* @param[in] dev : Structure instance of bmm150_dev.
*
* @return Result of API execution status
* @retval zero -> Success / +ve value -> Warning / -ve value -> Error
*/
int8_t bmm150_get_regs(uint8_t reg_addr, uint8_t *reg_data, uint8_t len, const struct bmm150_dev *dev);
/*!
* @brief This API is used to perform soft-reset of the sensor
* where all the registers are reset to their default values except 0x4B.
*
* @param[in] dev : Structure instance of bmm150_dev.
*
* @return Result of API execution status
* @retval zero -> Success / +ve value -> Warning / -ve value -> Error
*/
int8_t bmm150_soft_reset(const struct bmm150_dev *dev);
/*!
* @brief This API is used to set the power mode of the sensor.
*
* @param[in] dev : Structure instance of bmm150_dev.
*
* dev->settings.pwr_mode | Power mode
* ------------------------|-----------------------
* 0x00 | BMM150_NORMAL_MODE
* 0x01 | BMM150_FORCED_MODE
* 0x03 | BMM150_SLEEP_MODE
* 0x04 | BMM150_SUSPEND_MODE
*
* @return Result of API execution status
* @retval zero -> Success / +ve value -> Warning / -ve value -> Error
*/
int8_t bmm150_set_op_mode(struct bmm150_dev *dev);
/*!
* @brief This API is used to get the power mode of the sensor.
*
* @param[out] op_mode : power mode of the sensor.
* @param[in] dev : Structure instance of bmm150_dev.
*
* op_mode | Power mode
* -------------|-----------------------
* 0x00 | BMM150_NORMAL_MODE
* 0x01 | BMM150_FORCED_MODE
* 0x03 | BMM150_SLEEP_MODE
* 0x04 | BMM150_SUSPEND_MODE
*
* @return Result of API execution status
* @retval zero -> Success / +ve value -> Warning / -ve value -> Error
*/
int8_t bmm150_get_op_mode(uint8_t *op_mode, const struct bmm150_dev *dev);
/*!
* @brief This API is used to set the preset mode of the sensor.
*
* @param[in] dev : Structure instance of bmm150_dev.
*
* dev->settings.preset_mode | Preset mode
* ---------------------------|----------------------------------
* 0x01 | BMM150_PRESETMODE_LOWPOWER
* 0x02 | BMM150_PRESETMODE_REGULAR
* 0x03 | BMM150_PRESETMODE_HIGHACCURACY
* 0x04 | BMM150_PRESETMODE_ENHANCED
*
* @return Result of API execution status
* @retval zero -> Success / +ve value -> Warning / -ve value -> Error
*/
int8_t bmm150_set_presetmode(struct bmm150_dev *dev);
/*!
* @brief This API sets the sensor settings based on the desired_settings
* and the dev structure configuration
*
* @param[in] desired_settings : Selection macro for selecting the setting.
* @param[in] dev : Structure instance of bmm150_dev.
*
* @note Assign the sensor setting macros (multiple macros can be
* set by doing a bitwise-OR operation) to the desired_settings parameter
* of this API to perform the corresponding setting.
*
* @note threshold interrupt for each axes are set by using bitwise AND
* operation of the following macros
* - BMM150_THRESHOLD_X
* - BMM150_THRESHOLD_Y
* - BMM150_THRESHOLD_Z
*
* desired_settings | Selected sensor setting macros
* -------------------|--------------------------------
* 0x0001 | BMM150_DATA_RATE_SEL
* 0x0002 | BMM150_CONTROL_MEASURE_SEL
* 0x0004 | BMM150_XY_REP_SEL
* 0x0008 | BMM150_Z_REP_SEL
* 0x0010 | BMM150_DRDY_PIN_EN_SEL
* 0x0020 | BMM150_INT_PIN_EN_SEL
* 0x0040 | BMM150_DRDY_POLARITY_SEL
* 0x0080 | BMM150_INT_LATCH_SEL
* 0x0100 | BMM150_INT_POLARITY_SEL
* 0x0200 | BMM150_DATA_OVERRUN_INT_SEL
* 0x0400 | BMM150_OVERFLOW_INT_SEL
* 0x0800 | BMM150_HIGH_THRESHOLD_INT_SEL
* 0x1000 | BMM150_LOW_THRESHOLD_INT_SEL
* 0x2000 | BMM150_LOW_THRESHOLD_SETTING_SEL
* 0x4000 | BMM150_HIGH_THRESHOLD_SETTING_SEL
*
* @return Result of API execution status
* @retval zero -> Success / +ve value -> Warning / -ve value -> Error
*/
int8_t bmm150_set_sensor_settings(uint16_t desired_settings, const struct bmm150_dev *dev);
/*!
* @brief This API gets all the sensor settings and updates the dev structure
*
* @param[in] dev : Structure instance of bmm150_dev.
*
* @return Result of API execution status
* @retval zero -> Success / +ve value -> Warning / -ve value -> Error
*/
int8_t bmm150_get_sensor_settings(struct bmm150_dev *dev);
/*!
* @brief This API reads the magnetometer data from registers 0x42 to 0x49
* and updates the dev structure with compensated mag data in micro-tesla
*
* @param[in,out] dev : Structure instance of bmm150_dev.
*
* @note The output mag data can be obtained either in int16_t or float format
* using this API.
* @note Enable the macro "BMM150_USE_FLOATING_POINT" in the bmm150_defs.h
* file and call this API to get the mag data in float,
* disable this macro to get the mag data in int16_t format
*
* Mag data output(micro-tesla) | Mag data in dev structure(int16_t/float)
* --------------------------------|------------------------------------------
* X-axis data | dev->data.x
* Y-axis data | dev->data.y
* Z-axis data | dev->data.z
*
* @return Result of API execution status
* @retval zero -> Success / +ve value -> Warning / -ve value -> Error
*/
int8_t bmm150_read_mag_data(struct bmm150_dev *dev);
/*!
* @brief This API is used to perform the complete self test
* (both normal and advanced) for the BMM150 sensor
*
* @param[in] self_test_mode : The type of self test to be performed
* @param[in] dev : Structure instance of bmm150_dev.
*
* self_test_mode | Self test enabled
* --------------------|--------------------------
* 0 | BMM150_NORMAL_SELF_TEST
* 1 | BMM150_ADVANCED_SELF_TEST
*
* @note The return value of this API gives us the result of self test.
*
* @note Performing advanced self test does soft reset of the sensor, User can
* set the desired settings after performing the advanced self test.
*
* @return Result of API execution status and self test result.
* @retval zero -> Success / +ve value -> Warning / -ve value -> Error
*
* Return value | Result of self test
* --------------------|---------------------------------
* 0 | BMM150_OK
* 1 | BMM150_W_NORMAL_SELF_TEST_YZ_FAIL
* 2 | BMM150_W_NORMAL_SELF_TEST_XZ_FAIL
* 3 | BMM150_W_NORMAL_SELF_TEST_Z_FAIL
* 4 | BMM150_W_NORMAL_SELF_TEST_XY_FAIL
* 5 | BMM150_W_NORMAL_SELF_TEST_Y_FAIL
* 6 | BMM150_W_NORMAL_SELF_TEST_X_FAIL
* 7 | BMM150_W_NORMAL_SELF_TEST_XYZ_FAIL
* 8 | BMM150_W_ADV_SELF_TEST_FAIL
*
*/
int8_t bmm150_perform_self_test(uint8_t self_test_mode, struct bmm150_dev *dev);
/*!
* @brief This API obtains the status flags of all interrupt
* which is used to check for the assertion of interrupts
*
* @param[in,out] dev : Structure instance of bmm150_dev.
*
* @note The status flags of all the interrupts are stored in the
* dev->int_status.
*
* @note The value of dev->int_status is performed a bitwise AND operation
* with predefined interrupt status macros to find the interrupt status
* which is either set or reset.
*
* Ex.
* if (dev->int_status & BMM150_DATA_READY_INT)
* {
* Occurrence of data ready interrupt
* } else {
* No interrupt occurred
* }
*
* @return Result of API execution status and self test result.
* @retval zero -> Success / +ve value -> Warning / -ve value -> Error
*/
int8_t bmm150_get_interrupt_status(struct bmm150_dev *dev);
#ifdef __cplusplus
}
#endif /* End of CPP guard */
#endif /* BMM150_H__ */
/** @}*/
/**
* Copyright (C) 2015 - 2016 Bosch Sensortec GmbH
*
* 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.
*
* @file bmm150_defs.h
* @date 1 Mar 2017
* @version 0.8.0
* @brief
*
*/
/*! \file bmm150_defs.h */
/*!
* @defgroup BMM150 SENSOR API
* @brief
* @{*/
#ifndef BMM150_DEFS_H_
#define BMM150_DEFS_H_
/*********************************************************************/
/**\ header files */
#ifdef __KERNEL__
#include <linux/types.h>
#else
#include <stdint.h>
#include <stddef.h>
#endif
/*********************************************************************/
/* macro definitions */
#ifdef __KERNEL__
#if (LONG_MAX) > 0x7fffffff
#define __have_long64 1
#elif (LONG_MAX) == 0x7fffffff
#define __have_long32 1
#endif
#endif
#if !defined(UINT8_C)
#define INT8_C(x) x
#if (INT_MAX) > 0x7f
#define UINT8_C(x) x
#else
#define UINT8_C(x) x##U
#endif
#endif
#if !defined(UINT16_C)
#define INT16_C(x) x
#if (INT_MAX) > 0x7fff
#define UINT16_C(x) x
#else
#define UINT16_C(x) x##U
#endif
#endif
#if !defined(INT32_C) && !defined(UINT32_C)
#if __have_long32
#define INT32_C(x) x##L
#define UINT32_C(x) x##UL
#else
#define INT32_C(x) x
#define UINT32_C(x) x##U
#endif
#endif
#if !defined(INT64_C) && !defined(UINT64_C)
#if __have_long64
#define INT64_C(x) x##L
#define UINT64_C(x) x##UL
#else
#define INT64_C(x) x##LL
#define UINT64_C(x) x##ULL
#endif
#endif
/**\name C standard macros */
#ifndef NULL
#ifdef __cplusplus
#define NULL 0
#else
#define NULL ((void *) 0)
#endif
#endif
#define TRUE UINT8_C(1)
#define FALSE UINT8_C(0)
/********************************************************/
/**\name Compiler switch macros */
/**\name Comment the below line to use fixed-point compensation and
un-comment it to obtain the output data in float */
#define BMM150_USE_FLOATING_POINT
/********************************************************/
/**\name Macro definitions */
/**\name API success code */
#define BMM150_OK INT8_C(0)
/**\name API error codes */
#define BMM150_E_NULL_PTR INT8_C(-1)
#define BMM150_E_DEV_NOT_FOUND INT8_C(-2)
#define BMM150_E_INVALID_CONFIG INT8_C(-3)
/**\name API warning codes */
#define BMM150_W_NORMAL_SELF_TEST_YZ_FAIL INT8_C(1)
#define BMM150_W_NORMAL_SELF_TEST_XZ_FAIL INT8_C(2)
#define BMM150_W_NORMAL_SELF_TEST_Z_FAIL INT8_C(3)
#define BMM150_W_NORMAL_SELF_TEST_XY_FAIL INT8_C(4)
#define BMM150_W_NORMAL_SELF_TEST_Y_FAIL INT8_C(5)
#define BMM150_W_NORMAL_SELF_TEST_X_FAIL INT8_C(6)
#define BMM150_W_NORMAL_SELF_TEST_XYZ_FAIL INT8_C(7)
#define BMM150_W_ADV_SELF_TEST_FAIL INT8_C(8)
/**\name CHIP ID & SOFT RESET VALUES */
#define BMM150_CHIP_ID UINT8_C(0x32)
#define BMM150_SET_SOFT_RESET UINT8_C(0x82)
/**\name POWER MODE DEFINTIONS */
#define BMM150_NORMAL_MODE UINT8_C(0x00)
#define BMM150_FORCED_MODE UINT8_C(0x01)
#define BMM150_SLEEP_MODE UINT8_C(0x03)
#define BMM150_SUSPEND_MODE UINT8_C(0x04)
/**\name I2C ADDRESS */
#define BMM150_DEFAULT_I2C_ADDRESS UINT8_C(0x10)
#define BMM150_I2C_ADDRESS_CSB_LOW_SDO_HIGH UINT8_C(0x11)
#define BMM150_I2C_ADDRESS_CSB_HIGH_SDO_LOW UINT8_C(0x12)
#define BMM150_I2C_ADDRESS_CSB_HIGH_SDO_HIGH UINT8_C(0x13)
/**\name Power mode settings */
#define BMM150_POWER_CNTRL_DISABLE UINT8_C(0x00)
#define BMM150_POWER_CNTRL_ENABLE UINT8_C(0x01)
/**\name Sensor delay time settings */
#define BMM150_SOFT_RESET_DELAY UINT8_C(1)
#define BMM150_NORMAL_SELF_TEST_DELAY UINT8_C(2)
#define BMM150_START_UP_TIME UINT8_C(3)
#define BMM150_ADV_SELF_TEST_DELAY UINT8_C(4)
/**\name ENABLE/DISABLE DEFINITIONS */
#define BMM150_XY_CHANNEL_ENABLE UINT8_C(0x00)
#define BMM150_XY_CHANNEL_DISABLE UINT8_C(0x03)
/**\name Register Address */
#define BMM150_CHIP_ID_ADDR UINT8_C(0x40)
#define BMM150_DATA_X_LSB UINT8_C(0x42)
#define BMM150_DATA_READY_STATUS UINT8_C(0x48)
#define BMM150_INTERRUPT_STATUS UINT8_C(0x4A)
#define BMM150_POWER_CONTROL_ADDR UINT8_C(0x4B)
#define BMM150_OP_MODE_ADDR UINT8_C(0x4C)
#define BMM150_INT_CONFIG_ADDR UINT8_C(0x4D)
#define BMM150_AXES_ENABLE_ADDR UINT8_C(0x4E)
#define BMM150_LOW_THRESHOLD_ADDR UINT8_C(0x4F)
#define BMM150_HIGH_THRESHOLD_ADDR UINT8_C(0x50)
#define BMM150_REP_XY_ADDR UINT8_C(0x51)
#define BMM150_REP_Z_ADDR UINT8_C(0x52)
/**\name Macros to select the sensor settings to be set by the user
These values are internal for API implementation. Don't relate this to
data sheet. */
#define BMM150_DATA_RATE_SEL UINT16_C(1)
#define BMM150_CONTROL_MEASURE_SEL UINT16_C(1 << 1)
#define BMM150_XY_REP_SEL UINT16_C(1 << 2)
#define BMM150_Z_REP_SEL UINT16_C(1 << 3)
#define BMM150_DRDY_PIN_EN_SEL UINT16_C(1 << 4)
#define BMM150_INT_PIN_EN_SEL UINT16_C(1 << 5)
#define BMM150_DRDY_POLARITY_SEL UINT16_C(1 << 6)
#define BMM150_INT_LATCH_SEL UINT16_C(1 << 7)
#define BMM150_INT_POLARITY_SEL UINT16_C(1 << 8)
#define BMM150_DATA_OVERRUN_INT_SEL UINT16_C(1 << 9)
#define BMM150_OVERFLOW_INT_SEL UINT16_C(1 << 10)
#define BMM150_HIGH_THRESHOLD_INT_SEL UINT16_C(1 << 11)
#define BMM150_LOW_THRESHOLD_INT_SEL UINT16_C(1 << 12)
#define BMM150_LOW_THRESHOLD_SETTING_SEL UINT16_C(1 << 13)
#define BMM150_HIGH_THRESHOLD_SETTING_SEL UINT16_C(1 << 14)
/**\name DATA RATE DEFINITIONS */
#define BMM150_DATA_RATE_10HZ UINT8_C(0x00)
#define BMM150_DATA_RATE_02HZ UINT8_C(0x01)
#define BMM150_DATA_RATE_06HZ UINT8_C(0x02)
#define BMM150_DATA_RATE_08HZ UINT8_C(0x03)
#define BMM150_DATA_RATE_15HZ UINT8_C(0x04)
#define BMM150_DATA_RATE_20HZ UINT8_C(0x05)
#define BMM150_DATA_RATE_25HZ UINT8_C(0x06)
#define BMM150_DATA_RATE_30HZ UINT8_C(0x07)
/**\name TRIM REGISTERS */
/* Trim Extended Registers */
#define BMM150_DIG_X1 UINT8_C(0x5D)
#define BMM150_DIG_Y1 UINT8_C(0x5E)
#define BMM150_DIG_Z4_LSB UINT8_C(0x62)
#define BMM150_DIG_Z4_MSB UINT8_C(0x63)
#define BMM150_DIG_X2 UINT8_C(0x64)
#define BMM150_DIG_Y2 UINT8_C(0x65)
#define BMM150_DIG_Z2_LSB UINT8_C(0x68)
#define BMM150_DIG_Z2_MSB UINT8_C(0x69)
#define BMM150_DIG_Z1_LSB UINT8_C(0x6A)
#define BMM150_DIG_Z1_MSB UINT8_C(0x6B)
#define BMM150_DIG_XYZ1_LSB UINT8_C(0x6C)
#define BMM150_DIG_XYZ1_MSB UINT8_C(0x6D)
#define BMM150_DIG_Z3_LSB UINT8_C(0x6E)
#define BMM150_DIG_Z3_MSB UINT8_C(0x6F)
#define BMM150_DIG_XY2 UINT8_C(0x70)
#define BMM150_DIG_XY1 UINT8_C(0x71)
/**\name Threshold interrupt setting macros for x,y,z axes selection */
#define BMM150_THRESHOLD_X UINT8_C(0x06)
#define BMM150_THRESHOLD_Y UINT8_C(0x05)
#define BMM150_THRESHOLD_Z UINT8_C(0x03)
/**\name User configurable interrupt setting macros */
#define BMM150_INT_ENABLE UINT8_C(0x01)
#define BMM150_INT_DISABLE UINT8_C(0x00)
#define BMM150_ACTIVE_HIGH_POLARITY UINT8_C(0x01)
#define BMM150_ACTIVE_LOW_POLARITY UINT8_C(0x00)
#define BMM150_LATCHED UINT8_C(0x01)
#define BMM150_NON_LATCHED UINT8_C(0x00)
/**\name Interrupt status */
#define BMM150_LOW_THRESHOLD_INT_X UINT16_C(0x0001)
#define BMM150_LOW_THRESHOLD_INT_Y UINT16_C(0x0002)
#define BMM150_LOW_THRESHOLD_INT_Z UINT16_C(0x0004)
#define BMM150_HIGH_THRESHOLD_INT_X UINT16_C(0x0008)
#define BMM150_HIGH_THRESHOLD_INT_Y UINT16_C(0x0010)
#define BMM150_HIGH_THRESHOLD_INT_Z UINT16_C(0x0020)
#define BMM150_DATA_OVERFLOW_INT UINT16_C(0x0040)
#define BMM150_DATA_OVERRUN_INT UINT16_C(0x0080)
#define BMM150_DATA_READY_INT UINT16_C(0x0100)
/**\name Macros for bit masking */
#define BMM150_PWR_CNTRL_MSK UINT8_C(0x01)
#define BMM150_PWR_CNTRL_POS UINT8_C(0x00)
#define BMM150_CONTROL_MEASURE_MSK UINT8_C(0x38)
#define BMM150_CONTROL_MEASURE_POS UINT8_C(0x03)
#define BMM150_POWER_CONTROL_BIT_MSK UINT8_C(0x01)
#define BMM150_POWER_CONTROL_BIT_POS UINT8_C(0x00)
#define BMM150_OP_MODE_MSK UINT8_C(0x06)
#define BMM150_OP_MODE_POS UINT8_C(0x01)
#define BMM150_ODR_MSK UINT8_C(0x38)
#define BMM150_ODR_POS UINT8_C(0x03)
#define BMM150_DATA_X_MSK UINT8_C(0xF8)
#define BMM150_DATA_X_POS UINT8_C(0x03)
#define BMM150_DATA_Y_MSK UINT8_C(0xF8)
#define BMM150_DATA_Y_POS UINT8_C(0x03)
#define BMM150_DATA_Z_MSK UINT8_C(0xFE)
#define BMM150_DATA_Z_POS UINT8_C(0x01)
#define BMM150_DATA_RHALL_MSK UINT8_C(0xFC)
#define BMM150_DATA_RHALL_POS UINT8_C(0x02)
#define BMM150_SELF_TEST_MSK UINT8_C(0x01)
#define BMM150_SELF_TEST_POS UINT8_C(0x00)
#define BMM150_ADV_SELF_TEST_MSK UINT8_C(0xC0)
#define BMM150_ADV_SELF_TEST_POS UINT8_C(0x06)
#define BMM150_DRDY_EN_MSK UINT8_C(0x80)
#define BMM150_DRDY_EN_POS UINT8_C(0x07)
#define BMM150_INT_PIN_EN_MSK UINT8_C(0x40)
#define BMM150_INT_PIN_EN_POS UINT8_C(0x06)
#define BMM150_DRDY_POLARITY_MSK UINT8_C(0x04)
#define BMM150_DRDY_POLARITY_POS UINT8_C(0x02)
#define BMM150_INT_LATCH_MSK UINT8_C(0x02)
#define BMM150_INT_LATCH_POS UINT8_C(0x01)
#define BMM150_INT_POLARITY_MSK UINT8_C(0x01)
#define BMM150_INT_POLARITY_POS UINT8_C(0x00)
#define BMM150_DATA_OVERRUN_INT_MSK UINT8_C(0x80)
#define BMM150_DATA_OVERRUN_INT_POS UINT8_C(0x07)
#define BMM150_OVERFLOW_INT_MSK UINT8_C(0x40)
#define BMM150_OVERFLOW_INT_POS UINT8_C(0x06)
#define BMM150_HIGH_THRESHOLD_INT_MSK UINT8_C(0x38)
#define BMM150_HIGH_THRESHOLD_INT_POS UINT8_C(0x03)
#define BMM150_LOW_THRESHOLD_INT_MSK UINT8_C(0x07)
#define BMM150_LOW_THRESHOLD_INT_POS UINT8_C(0x00)
#define BMM150_DRDY_STATUS_MSK UINT8_C(0x01)
#define BMM150_DRDY_STATUS_POS UINT8_C(0x00)
/**\name OVERFLOW DEFINITIONS */
#define BMM150_XYAXES_FLIP_OVERFLOW_ADCVAL INT16_C(-4096)
#define BMM150_ZAXIS_HALL_OVERFLOW_ADCVAL INT16_C(-16384)
#define BMM150_OVERFLOW_OUTPUT INT16_C(-32768)
#define BMM150_NEGATIVE_SATURATION_Z INT16_C(-32767)
#define BMM150_POSITIVE_SATURATION_Z UINT16_C(32767)
#ifdef BMM150_USE_FLOATING_POINT
#define BMM150_OVERFLOW_OUTPUT_FLOAT 0.0f
#endif
/**\name PRESET MODE DEFINITIONS */
#define BMM150_PRESETMODE_LOWPOWER UINT8_C(0x01)
#define BMM150_PRESETMODE_REGULAR UINT8_C(0x02)
#define BMM150_PRESETMODE_HIGHACCURACY UINT8_C(0x03)
#define BMM150_PRESETMODE_ENHANCED UINT8_C(0x04)
/**\name PRESET MODES - REPETITIONS-XY RATES */
#define BMM150_LOWPOWER_REPXY UINT8_C(1)
#define BMM150_REGULAR_REPXY UINT8_C(4)
#define BMM150_ENHANCED_REPXY UINT8_C(7)
#define BMM150_HIGHACCURACY_REPXY UINT8_C(23)
/**\name PRESET MODES - REPETITIONS-Z RATES */
#define BMM150_LOWPOWER_REPZ UINT8_C(2)
#define BMM150_REGULAR_REPZ UINT8_C(14)
#define BMM150_ENHANCED_REPZ UINT8_C(26)
#define BMM150_HIGHACCURACY_REPZ UINT8_C(82)
/**\name Register read lengths */
#define BMM150_SELF_TEST_LEN UINT8_C(5)
#define BMM150_SETTING_DATA_LEN UINT8_C(8)
#define BMM150_XYZR_DATA_LEN UINT8_C(8)
/**\name Self test selection macros */
#define BMM150_NORMAL_SELF_TEST UINT8_C(0)
#define BMM150_ADVANCED_SELF_TEST UINT8_C(1)
/**\name Self test settings */
#define BMM150_DISABLE_XY_AXIS UINT8_C(0x03)
#define BMM150_SELF_TEST_REP_Z UINT8_C(0x04)
/**\name Advanced self-test current settings */
#define BMM150_DISABLE_SELF_TEST_CURRENT UINT8_C(0x00)
#define BMM150_ENABLE_NEGATIVE_CURRENT UINT8_C(0x02)
#define BMM150_ENABLE_POSITIVE_CURRENT UINT8_C(0x03)
/**\name Normal self-test status */
#define BMM150_SELF_TEST_STATUS_XYZ_FAIL UINT8_C(0x00)
#define BMM150_SELF_TEST_STATUS_SUCCESS UINT8_C(0x07)
/**\name Macro to SET and GET BITS of a register*/
#define BMM150_SET_BITS(reg_data, bitname, data) \
((reg_data & ~(bitname##_MSK)) | \
((data << bitname##_POS) & bitname##_MSK))
#define BMM150_GET_BITS(reg_data, bitname) ((reg_data & (bitname##_MSK)) >> \
(bitname##_POS))
/********************************************************/
/*!
* @brief Interface selection Enums
*/
enum bmm150_intf {
/*! SPI interface */
BMM150_SPI_INTF,
/*! I2C interface */
BMM150_I2C_INTF
};
/********************************************************/
/**\name TYPE DEFINITIONS */
/*!
* @brief Bus communication function pointer which should be mapped to
* the platform specific read and write functions of the user
*/
typedef int8_t (*bmm150_com_fptr_t)(uint8_t id, uint8_t reg_addr, uint8_t *read_data, uint16_t len);
/*! delay function pointer */
typedef void (*bmm150_delay_fptr_t)(uint32_t);
/********************************************************/
/**\name STRUCTURE DEFINITIONS*/
/*!
* @brief bmm150 trim data structure
*/
struct bmm150_trim_registers {
/*! trim x1 data */
int8_t dig_x1;
/*! trim y1 data */
int8_t dig_y1;
/*! trim x2 data */
int8_t dig_x2;
/*! trim y2 data */
int8_t dig_y2;
/*! trim z1 data */
uint16_t dig_z1;
/*! trim z2 data */
int16_t dig_z2;
/*! trim z3 data */
int16_t dig_z3;
/*! trim z4 data */
int16_t dig_z4;
/*! trim xy1 data */
uint8_t dig_xy1;
/*! trim xy2 data */
int8_t dig_xy2;
/*! trim xyz1 data */
uint16_t dig_xyz1;
};
/*!
* @brief bmm150 interrupt pin settings
*/
struct bmm150_int_ctrl_settings {
/*! Data ready interrupt enable */
uint8_t drdy_pin_en;
/*! Threshold and overflow interrupts enable */
uint8_t int_pin_en;
/*! Data ready interrupt polarity Active high/low */
uint8_t drdy_polarity;
/*! Interrupt pin - Latched or Non-latched */
uint8_t int_latch;
/*! Interrupt polarity Active high/low */
uint8_t int_polarity;
/*! Data overrun interrupt enable */
uint8_t data_overrun_en;
/*! Overflow interrupt enable */
uint8_t overflow_int_en;
/*! high interrupt enable/disable axis selection */
uint8_t high_int_en;
/*! low interrupt enable/disable axis selection */
uint8_t low_int_en;
/*! low threshold limit */
uint8_t low_threshold;
/*! high threshold limit */
uint8_t high_threshold;
};
/*!
* @brief bmm150 sensor settings
*/
struct bmm150_settings {
/*! Control measurement of XYZ axes */
uint8_t xyz_axes_control;
/*! Power control bit value */
uint8_t pwr_cntrl_bit;
/*! Power control bit value */
uint8_t pwr_mode;
/*! Data rate value (ODR) */
uint8_t data_rate;
/*! XY Repetitions */
uint8_t xy_rep;
/*! Z Repetitions */
uint8_t z_rep;
/*! Preset mode of sensor */
uint8_t preset_mode;
/*! Interrupt configuration settings */
struct bmm150_int_ctrl_settings int_settings;
};
/*!
* @brief bmm150 un-compensated (raw) magnetometer data
*/
struct bmm150_raw_mag_data {
/*! Raw mag X data */
int16_t raw_datax;
/*! Raw mag Y data */
int16_t raw_datay;
/*! Raw mag Z data */
int16_t raw_dataz;
/*! Raw mag resistance value */
uint16_t raw_data_r;
};
#ifdef BMM150_USE_FLOATING_POINT
/*!
* @brief bmm150 compensated magnetometer data in float
*/
struct bmm150_mag_data {
/*! compensated mag X data */
float x;
/*! compensated mag Y data */
float y;
/*! compensated mag Z data */
float z;
};
#else
/*!
* @brief bmm150 compensated magnetometer data in int16_t format
*/
struct bmm150_mag_data {
/*! compensated mag X data */
int16_t x;
/*! compensated mag Y data */
int16_t y;
/*! compensated mag Z data */
int16_t z;
};
#endif
/*!
* @brief bmm150 device structure
*/
struct bmm150_dev {
/*! Chip Id */
uint8_t chip_id;
/*! Device Id */
uint8_t id;
/*! SPI/I2C Interface */
enum bmm150_intf interface;
/*! Bus read function pointer */
bmm150_com_fptr_t read;
/*! Bus write function pointer */
bmm150_com_fptr_t write;
/*! delay(in ms) function pointer */
bmm150_delay_fptr_t delay_ms;
/*! Trim registers */
struct bmm150_trim_registers trim_data;
/*! Sensor settings */
struct bmm150_settings settings;
/*! Interrupt status */
uint16_t int_status;
/*! Structure containing mag data */
struct bmm150_mag_data data;
};
#endif /* BMM150_DEFS_H_ */
/** @}*/
/** @}*/
/** \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.
**************************************************************************/
/*! \file bmp280.h
\brief BMP280 Sensor Driver Support Header File */
#ifndef __BMP280_H__
#define __BMP280_H__
#include "bstdr_comm_support.h"
#include "bstdr_types.h"
#define BMP280_ENABLE_FLOAT
/***************************************************************/
/**\name GET AND SET BITSLICE FUNCTIONS */
/***************************************************************/
/* never change this line */
#define BMP280_GET_BITSLICE(regvar, bitname)\
((regvar & bitname##__MSK) >> bitname##__POS)
#define BMP280_SET_BITSLICE(regvar, bitname, val)\
((regvar & ~bitname##__MSK) | ((val<<bitname##__POS)&bitname##__MSK))
/***************************************************************/
/**\name COMMON USED CONSTANTS */
/***************************************************************/
/* Constants */
#define BMP280_NULL (0)
#define BMP280_RETURN_FUNCTION_TYPE bstdr_ret_t
/* shift definitions*/
#define BMP280_SHIFT_BIT_POSITION_BY_01_BIT (1)
#define BMP280_SHIFT_BIT_POSITION_BY_02_BITS (2)
#define BMP280_SHIFT_BIT_POSITION_BY_03_BITS (3)
#define BMP280_SHIFT_BIT_POSITION_BY_04_BITS (4)
#define BMP280_SHIFT_BIT_POSITION_BY_05_BITS (5)
#define BMP280_SHIFT_BIT_POSITION_BY_08_BITS (8)
#define BMP280_SHIFT_BIT_POSITION_BY_10_BITS (10)
#define BMP280_SHIFT_BIT_POSITION_BY_11_BITS (11)
#define BMP280_SHIFT_BIT_POSITION_BY_12_BITS (12)
#define BMP280_SHIFT_BIT_POSITION_BY_13_BITS (13)
#define BMP280_SHIFT_BIT_POSITION_BY_14_BITS (14)
#define BMP280_SHIFT_BIT_POSITION_BY_15_BITS (15)
#define BMP280_SHIFT_BIT_POSITION_BY_16_BITS (16)
#define BMP280_SHIFT_BIT_POSITION_BY_17_BITS (17)
#define BMP280_SHIFT_BIT_POSITION_BY_18_BITS (18)
#define BMP280_SHIFT_BIT_POSITION_BY_19_BITS (19)
#define BMP280_SHIFT_BIT_POSITION_BY_25_BITS (25)
#define BMP280_SHIFT_BIT_POSITION_BY_29_BITS (29)
#define BMP280_SHIFT_BIT_POSITION_BY_30_BITS (30)
#define BMP280_SHIFT_BIT_POSITION_BY_31_BITS (31)
#define BMP280_SHIFT_BIT_POSITION_BY_33_BITS (33)
#define BMP280_SHIFT_BIT_POSITION_BY_35_BITS (35)
#define BMP280_SHIFT_BIT_POSITION_BY_47_BITS (47)
/* numeric definitions */
#define BMP280_PRESSURE_TEMPERATURE_CALIB_DATA_LENGTH (25)
#define BMP280_GEN_READ_WRITE_DATA_LENGTH (1)
#define BMP280_TEMPERATURE_DATA_LENGTH (3)
#define BMP280_PRESSURE_DATA_LENGTH (3)
#define BMP280_ALL_DATA_FRAME_LENGTH (6)
#define BMP280_INIT_VALUE (0)
#define BMP280_INVALID_DATA (0)
/************************************************/
/**\name ERROR CODES */
/************************************************/
#define SUCCESS ((uint8_t)0)
#define E_BMP280_NULL_PTR ((int8_t)-127)
#define E_BMP280_COMM_RES ((int8_t)-1)
#define E_BMP280_OUT_OF_RANGE ((int8_t)-2)
#define ERROR ((int8_t)-1)
/************************************************/
/**\name CHIP ID DEFINITION */
/***********************************************/
#define BMP280_CHIP_ID1 (0x56)
#define BMP280_CHIP_ID2 (0x57)
#define BMP280_CHIP_ID3 (0x58)
/************************************************/
/**\name I2C ADDRESS DEFINITION */
/***********************************************/
#define BMP280_I2C_ADDRESS1 (0x76)
#define BMP280_I2C_ADDRESS2 (0x77)
/************************************************/
/**\name 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)
/************************************************/
/**\name 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)
/************************************************/
/**\name 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)
/************************************************/
/**\name WORKING MODE DEFINITION */
/***********************************************/
#define BMP280_ULTRA_LOW_POWER_MODE (0x00)
#define BMP280_LOW_POWER_MODE (0x01)
#define BMP280_STANDARD_RESOLUTION_MODE (0x02)
#define BMP280_HIGH_RESOLUTION_MODE (0x03)
#define BMP280_ULTRA_HIGH_RESOLUTION_MODE (0x04)
#define BMP280_ULTRALOWPOWER_OVERSAMP_PRESSURE BMP280_OVERSAMP_1X
#define BMP280_ULTRALOWPOWER_OVERSAMP_TEMPERATURE BMP280_OVERSAMP_1X
#define BMP280_LOWPOWER_OVERSAMP_PRESSURE BMP280_OVERSAMP_2X
#define BMP280_LOWPOWER_OVERSAMP_TEMPERATURE BMP280_OVERSAMP_1X
#define BMP280_STANDARDRESOLUTION_OVERSAMP_PRESSURE BMP280_OVERSAMP_4X
#define BMP280_STANDARDRESOLUTION_OVERSAMP_TEMPERATURE BMP280_OVERSAMP_1X
#define BMP280_HIGHRESOLUTION_OVERSAMP_PRESSURE BMP280_OVERSAMP_8X
#define BMP280_HIGHRESOLUTION_OVERSAMP_TEMPERATURE BMP280_OVERSAMP_1X
#define BMP280_ULTRAHIGHRESOLUTION_OVERSAMP_PRESSURE BMP280_OVERSAMP_16X
#define BMP280_ULTRAHIGHRESOLUTION_OVERSAMP_TEMPERATURE BMP280_OVERSAMP_2X
/************************************************/
/**\name FILTER DEFINITION */
/***********************************************/
#define BMP280_FILTER_COEFF_OFF (0x00)
#define BMP280_FILTER_COEFF_2 (0x01)
#define BMP280_FILTER_COEFF_4 (0x02)
#define BMP280_FILTER_COEFF_8 (0x03)
#define BMP280_FILTER_COEFF_16 (0x04)
/************************************************/
/**\name DELAY TIME DEFINITION */
/***********************************************/
#define T_INIT_MAX (20)
/* 20/16 = 1.25 ms */
#define T_MEASURE_PER_OSRS_MAX (37)
/* 37/16 = 2.3125 ms*/
#define T_SETUP_PRESSURE_MAX (10)
/* 10/16 = 0.625 ms */
/************************************************/
/**\name CALIBRATION PARAMETERS DEFINITION */
/***********************************************/
/*calibration parameters */
#define BMP280_TEMPERATURE_CALIB_DIG_T1_LSB_REG (0x88)
#define BMP280_TEMPERATURE_CALIB_DIG_T1_MSB_REG (0x89)
#define BMP280_TEMPERATURE_CALIB_DIG_T2_LSB_REG (0x8A)
#define BMP280_TEMPERATURE_CALIB_DIG_T2_MSB_REG (0x8B)
#define BMP280_TEMPERATURE_CALIB_DIG_T3_LSB_REG (0x8C)
#define BMP280_TEMPERATURE_CALIB_DIG_T3_MSB_REG (0x8D)
#define BMP280_PRESSURE_CALIB_DIG_P1_LSB_REG (0x8E)
#define BMP280_PRESSURE_CALIB_DIG_P1_MSB_REG (0x8F)
#define BMP280_PRESSURE_CALIB_DIG_P2_LSB_REG (0x90)
#define BMP280_PRESSURE_CALIB_DIG_P2_MSB_REG (0x91)
#define BMP280_PRESSURE_CALIB_DIG_P3_LSB_REG (0x92)
#define BMP280_PRESSURE_CALIB_DIG_P3_MSB_REG (0x93)
#define BMP280_PRESSURE_CALIB_DIG_P4_LSB_REG (0x94)
#define BMP280_PRESSURE_CALIB_DIG_P4_MSB_REG (0x95)
#define BMP280_PRESSURE_CALIB_DIG_P5_LSB_REG (0x96)
#define BMP280_PRESSURE_CALIB_DIG_P5_MSB_REG (0x97)
#define BMP280_PRESSURE_CALIB_DIG_P6_LSB_REG (0x98)
#define BMP280_PRESSURE_CALIB_DIG_P6_MSB_REG (0x99)
#define BMP280_PRESSURE_CALIB_DIG_P7_LSB_REG (0x9A)
#define BMP280_PRESSURE_CALIB_DIG_P7_MSB_REG (0x9B)
#define BMP280_PRESSURE_CALIB_DIG_P8_LSB_REG (0x9C)
#define BMP280_PRESSURE_CALIB_DIG_P8_MSB_REG (0x9D)
#define BMP280_PRESSURE_CALIB_DIG_P9_LSB_REG (0x9E)
#define BMP280_PRESSURE_CALIB_DIG_P9_MSB_REG (0x9F)
/************************************************/
/**\name REGISTER ADDRESS DEFINITION */
/***********************************************/
#define BMP280_CHIP_ID_REG (0xD0) /*Chip ID Register */
#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 */
#define BMP280_TEMPERATURE_MSB_REG (0xFA) /*Temperature MSB Reg */
#define BMP280_TEMPERATURE_LSB_REG (0xFB) /*Temperature LSB Reg */
#define BMP280_TEMPERATURE_XLSB_REG (0xFC) /*Temperature XLSB Reg */
/************************************************/
/**\name BIT LENGTH,POSITION AND MASK DEFINITION */
/***********************************************/
/* Status Register */
#define BMP280_STATUS_REG_MEASURING__POS (3)
#define BMP280_STATUS_REG_MEASURING__MSK (0x08)
#define BMP280_STATUS_REG_MEASURING__LEN (1)
#define BMP280_STATUS_REG_MEASURING__REG (BMP280_STAT_REG)
#define BMP280_STATUS_REG_IM_UPDATE__POS (0)
#define BMP280_STATUS_REG_IM_UPDATE__MSK (0x01)
#define BMP280_STATUS_REG_IM_UPDATE__LEN (1)
#define BMP280_STATUS_REG_IM_UPDATE__REG (BMP280_STAT_REG)
/************************************************/
/**\name BIT LENGTH,POSITION AND MASK DEFINITION
FOR TEMPERATURE OVERSAMPLING */
/***********************************************/
/* Control Measurement Register */
#define BMP280_CTRL_MEAS_REG_OVERSAMP_TEMPERATURE__POS (5)
#define BMP280_CTRL_MEAS_REG_OVERSAMP_TEMPERATURE__MSK (0xE0)
#define BMP280_CTRL_MEAS_REG_OVERSAMP_TEMPERATURE__LEN (3)
#define BMP280_CTRL_MEAS_REG_OVERSAMP_TEMPERATURE__REG \
(BMP280_CTRL_MEAS_REG)
/************************************************/
/**\name BIT LENGTH,POSITION AND MASK DEFINITION
FOR PRESSURE OVERSAMPLING */
/***********************************************/
#define BMP280_CTRL_MEAS_REG_OVERSAMP_PRESSURE__POS (2)
#define BMP280_CTRL_MEAS_REG_OVERSAMP_PRESSURE__MSK (0x1C)
#define BMP280_CTRL_MEAS_REG_OVERSAMP_PRESSURE__LEN (3)
#define BMP280_CTRL_MEAS_REG_OVERSAMP_PRESSURE__REG \
(BMP280_CTRL_MEAS_REG)
/************************************************/
/**\name BIT LENGTH,POSITION AND MASK DEFINITION
FOR POWER MODE */
/***********************************************/
#define BMP280_CTRL_MEAS_REG_POWER_MODE__POS (0)
#define BMP280_CTRL_MEAS_REG_POWER_MODE__MSK (0x03)
#define BMP280_CTRL_MEAS_REG_POWER_MODE__LEN (2)
#define BMP280_CTRL_MEAS_REG_POWER_MODE__REG (BMP280_CTRL_MEAS_REG)
/************************************************/
/**\name BIT LENGTH,POSITION AND MASK DEFINITION
FOR STANDBY DURATION */
/***********************************************/
/* Configuration Register */
#define BMP280_CONFIG_REG_STANDBY_DURN__POS (5)
#define BMP280_CONFIG_REG_STANDBY_DURN__MSK (0xE0)
#define BMP280_CONFIG_REG_STANDBY_DURN__LEN (3)
#define BMP280_CONFIG_REG_STANDBY_DURN__REG (BMP280_CONFIG_REG)
/************************************************/
/**\name BIT LENGTH,POSITION AND MASK DEFINITION
FOR IIR FILTER */
/***********************************************/
#define BMP280_CONFIG_REG_FILTER__POS (2)
#define BMP280_CONFIG_REG_FILTER__MSK (0x1C)
#define BMP280_CONFIG_REG_FILTER__LEN (3)
#define BMP280_CONFIG_REG_FILTER__REG (BMP280_CONFIG_REG)
/************************************************/
/**\name BIT LENGTH,POSITION AND MASK DEFINITION
FOR SPI ENABLE*/
/***********************************************/
#define BMP280_CONFIG_REG_SPI3_ENABLE__POS (0)
#define BMP280_CONFIG_REG_SPI3_ENABLE__MSK (0x01)
#define BMP280_CONFIG_REG_SPI3_ENABLE__LEN (1)
#define BMP280_CONFIG_REG_SPI3_ENABLE__REG (BMP280_CONFIG_REG)
/************************************************/
/**\name BIT LENGTH,POSITION AND MASK DEFINITION
FOR PRESSURE AND TEMPERATURE DATA REGISTERS */
/***********************************************/
/* Data Register */
#define BMP280_PRESSURE_XLSB_REG_DATA__POS (4)
#define BMP280_PRESSURE_XLSB_REG_DATA__MSK (0xF0)
#define BMP280_PRESSURE_XLSB_REG_DATA__LEN (4)
#define BMP280_PRESSURE_XLSB_REG_DATA__REG (BMP280_PRESSURE_XLSB_REG)
#define BMP280_TEMPERATURE_XLSB_REG_DATA__POS (4)
#define BMP280_TEMPERATURE_XLSB_REG_DATA__MSK (0xF0)
#define BMP280_TEMPERATURE_XLSB_REG_DATA__LEN (4)
#define BMP280_TEMPERATURE_XLSB_REG_DATA__REG (BMP280_TEMPERATURE_XLSB_REG)
#define BMP280_MDELAY_DATA_TYPE uint32_t
/****************************************************/
/**\name DEFINITIONS FOR ARRAY SIZE OF DATA */
/***************************************************/
#define BMP280_TEMPERATURE_DATA_SIZE (3)
#define BMP280_PRESSURE_DATA_SIZE (3)
#define BMP280_DATA_FRAME_SIZE (6)
#define BMP280_CALIB_DATA_SIZE (25)
#define BMP280_TEMPERATURE_MSB_DATA (0)
#define BMP280_TEMPERATURE_LSB_DATA (1)
#define BMP280_TEMPERATURE_XLSB_DATA (2)
#define BMP280_PRESSURE_MSB_DATA (0)
#define BMP280_PRESSURE_LSB_DATA (1)
#define BMP280_PRESSURE_XLSB_DATA (2)
#define BMP280_DATA_FRAME_PRESSURE_MSB_BYTE (0)
#define BMP280_DATA_FRAME_PRESSURE_LSB_BYTE (1)
#define BMP280_DATA_FRAME_PRESSURE_XLSB_BYTE (2)
#define BMP280_DATA_FRAME_TEMPERATURE_MSB_BYTE (3)
#define BMP280_DATA_FRAME_TEMPERATURE_LSB_BYTE (4)
#define BMP280_DATA_FRAME_TEMPERATURE_XLSB_BYTE (5)
/****************************************************/
/**\name ARRAY PARAMETER FOR CALIBRATION */
/***************************************************/
#define BMP280_TEMPERATURE_CALIB_DIG_T1_LSB (0)
#define BMP280_TEMPERATURE_CALIB_DIG_T1_MSB (1)
#define BMP280_TEMPERATURE_CALIB_DIG_T2_LSB (2)
#define BMP280_TEMPERATURE_CALIB_DIG_T2_MSB (3)
#define BMP280_TEMPERATURE_CALIB_DIG_T3_LSB (4)
#define BMP280_TEMPERATURE_CALIB_DIG_T3_MSB (5)
#define BMP280_PRESSURE_CALIB_DIG_P1_LSB (6)
#define BMP280_PRESSURE_CALIB_DIG_P1_MSB (7)
#define BMP280_PRESSURE_CALIB_DIG_P2_LSB (8)
#define BMP280_PRESSURE_CALIB_DIG_P2_MSB (9)
#define BMP280_PRESSURE_CALIB_DIG_P3_LSB (10)
#define BMP280_PRESSURE_CALIB_DIG_P3_MSB (11)
#define BMP280_PRESSURE_CALIB_DIG_P4_LSB (12)
#define BMP280_PRESSURE_CALIB_DIG_P4_MSB (13)
#define BMP280_PRESSURE_CALIB_DIG_P5_LSB (14)
#define BMP280_PRESSURE_CALIB_DIG_P5_MSB (15)
#define BMP280_PRESSURE_CALIB_DIG_P6_LSB (16)
#define BMP280_PRESSURE_CALIB_DIG_P6_MSB (17)
#define BMP280_PRESSURE_CALIB_DIG_P7_LSB (18)
#define BMP280_PRESSURE_CALIB_DIG_P7_MSB (19)
#define BMP280_PRESSURE_CALIB_DIG_P8_LSB (20)
#define BMP280_PRESSURE_CALIB_DIG_P8_MSB (21)
#define BMP280_PRESSURE_CALIB_DIG_P9_LSB (22)
#define BMP280_PRESSURE_CALIB_DIG_P9_MSB (23)
#define BMP280_PRESSURE_CALIB_DIG_P10 (24)
/**************************************************************/
/**\name STRUCTURE DEFINITIONS */
/**************************************************************/
/*!
* @brief This structure holds all device specific calibration parameters
*/
struct bmp280_calib_param_t {
uint16_t dig_T1;/**<calibration T1 data*/
int16_t dig_T2;/**<calibration T2 data*/
int16_t dig_T3;/**<calibration T3 data*/
uint16_t dig_P1;/**<calibration P1 data*/
int16_t dig_P2;/**<calibration P2 data*/
int16_t dig_P3;/**<calibration P3 data*/
int16_t dig_P4;/**<calibration P4 data*/
int16_t dig_P5;/**<calibration P5 data*/
int16_t dig_P6;/**<calibration P6 data*/
int16_t dig_P7;/**<calibration P7 data*/
int16_t dig_P8;/**<calibration P8 data*/
int16_t dig_P9;/**<calibration P9 data*/
int8_t dig_P10;/**<calibration P10 data*/
int32_t t_fine;/**<calibration t_fine data*/
};
/*!
* @brief This structure holds BMP280 initialization parameters
*/
struct bmp280_t{
struct bmp280_calib_param_t calib_param;/**<calibration data*/
uint8_t chip_id;/**< chip id of the sensor*/
uint8_t dev_addr;/**< device address of the sensor*/
uint8_t oversamp_temperature;/**< temperature over sampling*/
uint8_t oversamp_pressure;/**< pressure over sampling*/
sensor_read bus_read;/**< bus write function pointer*/
sensor_write bus_write;/**< bus read function pointer*/
delay_msec delay_ms;/**< delay function pointer*/
};
/**************************************************************/
/**\name FUNCTION DECLARATIONS */
/**************************************************************/
/**************************************************************/
/**\name FUNCTION FOR INTIALIZATION */
/**************************************************************/
/*!
* @brief This function is used for initialize
* the bus read and bus write functions
* and assign the chip id and I2C address of the BMP280 sensor
* chip id is read in the register 0xD0 bit from 0 to 7
*
* @param *bmp280 structure pointer.
*
* @note While changing the parameter of the p_bmp280
* @note consider the following point:
* Changing the reference value of the parameter
* will changes the local copy or local reference
* make sure your changes will not
* affect the reference value of the parameter
* (Better case don't change the reference value of the parameter)
*
*
*
*
* @return results of bus communication function
* @retval 0 -> Success
* @retval -1 -> Error
*
*
*/
BMP280_RETURN_FUNCTION_TYPE bmp280_init(struct bmp280_t *bmp280);
/**************************************************************/
/**\name FUNCTION FOR READ UNCOMPENSATED TEMPERATURE */
/**************************************************************/
/*!
* @brief This API is used to read uncompensated temperature
* in the registers 0xFA, 0xFB and 0xFC
* @note 0xFA -> MSB -> bit from 0 to 7
* @note 0xFB -> LSB -> bit from 0 to 7
* @note 0xFC -> LSB -> bit from 4 to 7
*
* @param v_uncomp_temperature_s32 : The uncompensated temperature.
*
*
*
* @return results of bus communication function
* @retval 0 -> Success
* @retval -1 -> Error
*
*
*/
BMP280_RETURN_FUNCTION_TYPE bmp280_read_uncomp_temperature(int32_t *v_uncomp_temperature_s32);
/**************************************************************/
/**\name FUNCTION FOR READ TRUE TEMPERATURE S32 OUTPUT */
/**************************************************************/
/*!
* @brief Reads actual temperature
* from uncompensated temperature
* @note Returns the value in 0.01 degree Centigrade
* @note Output value of "5123" equals 51.23 DegC.
*
*
*
* @param v_uncomp_temperature_s32 : value of uncompensated temperature
*
*
*
* @return Actual temperature output as int32_t
*
*/
int32_t bmp280_compensate_temperature_int32(int32_t v_uncomp_temperature_s32);
/**************************************************************/
/**\name FUNCTION FOR READ UNCOMPENSATED PRESSURE */
/**************************************************************/
/*!
* @brief This API is used to read uncompensated pressure.
* in the registers 0xF7, 0xF8 and 0xF9
* @note 0xF7 -> MSB -> bit from 0 to 7
* @note 0xF8 -> LSB -> bit from 0 to 7
* @note 0xF9 -> LSB -> bit from 4 to 7
*
*
*
* @param v_uncomp_pressure_s32 : The value of uncompensated pressure
*
*
*
* @return results of bus communication function
* @retval 0 -> Success
* @retval -1 -> Error
*
*
*/
BMP280_RETURN_FUNCTION_TYPE bmp280_read_uncomp_pressure(int32_t *v_uncomp_pressure_s32);
/**************************************************************/
/**\name FUNCTION FOR READ TRUE PRESSURE S32 OUTPUT */
/**************************************************************/
/*!
* @brief 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
*
* @param v_uncomp_pressure_s32: value of uncompensated pressure
*
* @return Returns the Actual pressure out put as int32_t
*
*/
uint32_t bmp280_compensate_pressure_int32(int32_t v_uncomp_pressure_s32);
/**************************************************************/
/**\name FUNCTION FOR READ UNCOMPENSATED TEMPERATURE AND PRESSURE */
/**************************************************************/
/*!
* @brief reads uncompensated pressure and temperature
*
*
* @param v_uncomp_pressure_s32: The value of uncompensated pressure.
* @param v_uncomp_temperature_s32: The value of uncompensated temperature.
*
* @return results of bus communication function
* @retval 0 -> Success
* @retval -1 -> Error
*
*/
BMP280_RETURN_FUNCTION_TYPE bmp280_read_uncomp_pressure_temperature(
int32_t *v_uncomp_pressure_s32, int32_t *v_uncomp_temperature_s32);
/**************************************************************/
/**\name FUNCTION FOR READ TRUE TEMPERATURE AND PRESSURE */
/**************************************************************/
/*!
* @brief This API reads the true pressure and temperature
*
*
* @param v_pressure_u32 : The value of compensated pressure.
* @param v_temperature_s32 : The value of compensated temperature.
*
*
* @return results of bus communication function
* @retval 0 -> Success
* @retval -1 -> Error
*
*
*/
BMP280_RETURN_FUNCTION_TYPE bmp280_read_pressure_temperature(
uint32_t *v_pressure_u32, int32_t *v_pressure_s32);
/**************************************************************/
/**\name FUNCTION FOR READ CALIBRATION DATA */
/**************************************************************/
/*!
* @brief This API is used to
* 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
* @retval -1 -> Error
*
*
*/
BMP280_RETURN_FUNCTION_TYPE bmp280_get_calib_param(void);
/**************************************************************/
/**\name FUNCTION FOR OVERSAMPLING TEMPERATURE AND PRESSURE */
/**************************************************************/
/*!
* @brief This API is used to get
* the temperature oversampling setting in the register 0xF4
* bits from 5 to 7
*
* value | Temperature oversampling
* ------------------------|------------------------------
* 0x00 | BMP280_OVERSAMP_SKIPPED
* 0x01 | BMP280_OVERSAMP_1X
* 0x02 | BMP280_OVERSAMP_2X
* 0x03 | BMP280_OVERSAMP_4X
* 0x04 | BMP280_OVERSAMP_8X
* 0x05,0x06 and 0x07 | BMP280_OVERSAMP_16X
*
*
* @param v_value_u8 :The value of temperature over sampling
*
*
*
* @return results of bus communication function
* @retval 0 -> Success
* @retval -1 -> Error
*
*
*/
BMP280_RETURN_FUNCTION_TYPE bmp280_get_oversamp_temperature(uint8_t *v_value_u8);
/*!
* @brief This API is used to set
* the temperature oversampling setting in the register 0xF4
* bits from 5 to 7
*
* value | Temperature oversampling
* ------------------------|------------------------------
* 0x00 | BMP280_OVERSAMP_SKIPPED
* 0x01 | BMP280_OVERSAMP_1X
* 0x02 | BMP280_OVERSAMP_2X
* 0x03 | BMP280_OVERSAMP_4X
* 0x04 | BMP280_OVERSAMP_8X
* 0x05,0x06 and 0x07 | BMP280_OVERSAMP_16X
*
*
* @param v_value_u8 :The value of temperature over sampling
*
*
*
* @return results of bus communication function
* @retval 0 -> Success
* @retval -1 -> Error
*
*
*/
BMP280_RETURN_FUNCTION_TYPE bmp280_set_oversamp_temperature(uint8_t v_value_u8);
/*!
* @brief This API is used to get
* the pressure oversampling setting in the register 0xF4
* bits from 2 to 4
*
* value | Pressure oversampling
* ------------------------|------------------------------
* 0x00 | BMP280_OVERSAMP_SKIPPED
* 0x01 | BMP280_OVERSAMP_1X
* 0x02 | BMP280_OVERSAMP_2X
* 0x03 | BMP280_OVERSAMP_4X
* 0x04 | BMP280_OVERSAMP_8X
* 0x05,0x06 and 0x07 | BMP280_OVERSAMP_16X
*
*
* @param v_value_u8 : The value of pressure over sampling
*
*
*
* @return results of bus communication function
* @retval 0 -> Success
* @retval -1 -> Error
*
*
*/
BMP280_RETURN_FUNCTION_TYPE bmp280_get_oversamp_pressure(uint8_t *v_value_u8);
/*!
* @brief This API is used to set
* the pressure oversampling setting in the register 0xF4
* bits from 2 to 4
*
* value | Pressure oversampling
* ------------------------|------------------------------
* 0x00 | BMP280_OVERSAMP_SKIPPED
* 0x01 | BMP280_OVERSAMP_1X
* 0x02 | BMP280_OVERSAMP_2X
* 0x03 | BMP280_OVERSAMP_4X
* 0x04 | BMP280_OVERSAMP_8X
* 0x05,0x06 and 0x07 | BMP280_OVERSAMP_16X
*
*
* @param v_value_u8 : The value of pressure over sampling
*
*
*
* @return results of bus communication function
* @retval 0 -> Success
* @retval -1 -> Error
*
*
*/
BMP280_RETURN_FUNCTION_TYPE bmp280_set_oversamp_pressure(uint8_t v_value_u8);
/**************************************************************/
/**\name FUNCTION FOR POWER MODE */
/**************************************************************/
/*!
* @brief This API used to get the
* Operational Mode from the sensor in the register 0xF4 bit 0 and 1
*
*
*
* @param v_power_mode_u8 : The value of power mode value
* value | Power mode
* ------------------|------------------
* 0x00 | BMP280_SLEEP_MODE
* 0x01 and 0x02 | BMP280_FORCED_MODE
* 0x03 | BMP280_NORMAL_MODE
*
* @return results of bus communication function
* @retval 0 -> Success
* @retval -1 -> Error
*
*
*/
BMP280_RETURN_FUNCTION_TYPE bmp280_get_power_mode(uint8_t *v_power_mode_u8);
/*!
* @brief This API used to set the
* Operational Mode from the sensor in the register 0xF4 bit 0 and 1
*
*
*
* @param v_power_mode_u8 : The value of power mode value
* value | Power mode
* ------------------|------------------
* 0x00 | BMP280_SLEEP_MODE
* 0x01 and 0x02 | BMP280_FORCED_MODE
* 0x03 | BMP280_NORMAL_MODE
*
* @return results of bus communication function
* @retval 0 -> Success
* @retval -1 -> Error
*
*
*/
BMP280_RETURN_FUNCTION_TYPE bmp280_set_power_mode(uint8_t v_power_mode_u8);
/**************************************************************/
/**\name FUNCTION FOR SOFT RESET */
/**************************************************************/
/*!
* @brief Used to reset the sensor
* The value 0xB6 is written to the
* 0xE0 register the device is reset using the
* complete power-on-reset procedure.
* Softreset can be easily set using bmp280_set_softreset().
*
* @note Usage Hint : bmp280_set_softreset()
*
*
* @return results of bus communication function
* @retval 0 -> Success
* @retval -1 -> Error
*
*
*/
BMP280_RETURN_FUNCTION_TYPE bmp280_set_soft_rst(void);
/**************************************************************/
/**\name FUNCTION FOR SPI ENABLE */
/**************************************************************/
/*!
* @brief This API used to get the sensor
* SPI mode(communication type) in the register 0xF5 bit 0
*
*
*
* @param v_enable_disable_u8 : The spi3 enable or disable state
* value | Description
* -----------|---------------
* 0 | Disable
* 1 | Enable
*
*
*
* @return results of bus communication function
* @retval 0 -> Success
* @retval -1 -> Error
*
*
*/
BMP280_RETURN_FUNCTION_TYPE bmp280_get_spi3(uint8_t *v_enable_disable_u8);
/*!
* @brief This API used to set the sensor
* SPI mode(communication type) in the register 0xF5 bit 0
*
*
*
* @param v_enable_disable_u8 : The spi3 enable or disable state
* value | Description
* -----------|---------------
* 0 | Disable
* 1 | Enable
*
*
*
* @return results of bus communication function
* @retval 0 -> Success
* @retval -1 -> Error
*
*
*/
BMP280_RETURN_FUNCTION_TYPE bmp280_set_spi3(uint8_t v_enable_disable_u8);
/**************************************************************/
/**\name FUNCTION FOR IIR FILTER SETTING */
/**************************************************************/
/*!
* @brief This API is used to reads filter setting
* in the register 0xF5 bit 3 and 4
*
*
*
* @param v_value_u8 : The value of filter coefficient
* value | Filter coefficient
* -------------|-------------------------
* 0x00 | BMP280_FILTER_COEFF_OFF
* 0x01 | BMP280_FILTER_COEFF_2
* 0x02 | BMP280_FILTER_COEFF_4
* 0x03 | BMP280_FILTER_COEFF_8
* 0x04 | BMP280_FILTER_COEFF_16
*
* @return results of bus communication function
* @retval 0 -> Success
* @retval -1 -> Error
*
*
*/
BMP280_RETURN_FUNCTION_TYPE bmp280_get_filter(uint8_t *v_value_u8);
/*!
* @brief This API is used to write filter setting
* in the register 0xF5 bit 3 and 4
*
*
*
* @param v_value_u8 : The value of filter coefficient
* value | Filter coefficient
* -------------|-------------------------
* 0x00 | BMP280_FILTER_COEFF_OFF
* 0x01 | BMP280_FILTER_COEFF_2
* 0x02 | BMP280_FILTER_COEFF_4
* 0x03 | BMP280_FILTER_COEFF_8
* 0x04 | BMP280_FILTER_COEFF_16
*
* @return results of bus communication function
* @retval 0 -> Success
* @retval -1 -> Error
*
*
*/
BMP280_RETURN_FUNCTION_TYPE bmp280_set_filter(uint8_t v_value_u8);
/**************************************************************/
/**\name FUNCTION FOR STANDBY DURATION */
/**************************************************************/
/*!
* @brief This API used to Read the
* standby duration time from the sensor in the register 0xF5 bit 5 to 7
*
* @param v_standby_durn_u8 : The standby duration time value.
* value | standby duration
* -----------|--------------------
* 0x00 | BMP280_STANDBYTIME_1_MS
* 0x01 | BMP280_STANDBYTIME_63_MS
* 0x02 | BMP280_STANDBYTIME_125_MS
* 0x03 | BMP280_STANDBYTIME_250_MS
* 0x04 | BMP280_STANDBYTIME_500_MS
* 0x05 | BMP280_STANDBYTIME_1000_MS
* 0x06 | BMP280_STANDBYTIME_2000_MS
* 0x07 | BMP280_STANDBYTIME_4000_MS
*
*
*
* @return results of bus communication function
* @retval 0 -> Success
* @retval -1 -> Error
*
*
*/
BMP280_RETURN_FUNCTION_TYPE bmp280_get_standby_durn(uint8_t *v_standby_durn_u8);
/*!
* @brief This API used to Read the
* standby duration time from the sensor in the register 0xF5 bit 5 to 7
* @note Normal mode comprises an automated perpetual cycling between an (active)
* Measurement period and an (inactive) standby period.
* @note The standby time is determined by the contents of the register t_sb.
* Standby time can be set using BMP280_STANDBYTIME_125_MS.
*
* @note bmp280_set_standby_durn(BMP280_STANDBYTIME_125_MS)
*
*
*
* @param v_standby_durn_u8 : The standby duration time value.
* value | standby duration
* -----------|--------------------
* 0x00 | BMP280_STANDBYTIME_1_MS
* 0x01 | BMP280_STANDBYTIME_63_MS
* 0x02 | BMP280_STANDBYTIME_125_MS
* 0x03 | BMP280_STANDBYTIME_250_MS
* 0x04 | BMP280_STANDBYTIME_500_MS
* 0x05 | BMP280_STANDBYTIME_1000_MS
* 0x06 | BMP280_STANDBYTIME_2000_MS
* 0x07 | BMP280_STANDBYTIME_4000_MS
*
*
*
* @return results of bus communication function
* @retval 0 -> Success
* @retval -1 -> Error
*
*
*/
BMP280_RETURN_FUNCTION_TYPE bmp280_set_standby_durn(uint8_t v_standby_durn_u8);
/**************************************************************/
/**\name FUNCTION FOR WORK MODE */
/**************************************************************/
/*!
* @brief This API is used to write
* the working mode of the sensor
*
*
* @param v_work_mode_u8 : The value of work mode
* value | mode
* -------------|-------------
* 0 | BMP280_ULTRA_LOW_POWER_MODE
* 1 | BMP280_LOW_POWER_MODE
* 2 | BMP280_STANDARD_RESOLUTION_MODE
* 3 | BMP280_HIGH_RESOLUTION_MODE
* 4 | BMP280_ULTRA_HIGH_RESOLUTION_MODE
*
* @return results of bus communication function
* @retval 0 -> Success
* @retval -1 -> Error
*
*
*/
BMP280_RETURN_FUNCTION_TYPE bmp280_set_work_mode(uint8_t v_work_mode_u8);
/**************************************************************/
/**\name FUNCTION FOR FORCE MODE READING */
/**************************************************************/
/*!
* @brief This API used to read both
* uncompensated pressure and temperature in forced mode
*
*
* @param v_uncomp_pressure_s32: The value of uncompensated pressure.
* @param v_uncomp_temperature_s32: The value of uncompensated temperature
*
*
* @return results of bus communication function
* @retval 0 -> Success
* @retval -1 -> Error
*
*
*/
BMP280_RETURN_FUNCTION_TYPE bmp280_get_forced_uncomp_pressure_temperature(
int32_t *v_uncomp_pressure_s32, int32_t *v_uncomp_temperature_s32);
/**************************************************************/
/**\name FUNCTION FOR COMMON READ AND WRITE */
/**************************************************************/
/*!
* @brief
* This API write the data to
* the given register
*
*
* @param v_addr_u8 -> Address of the register
* @param v_data_u8 -> The data from the register
* @param v_len_u8 -> no of bytes to read
*
*
* @return results of bus communication function
* @retval 0 -> Success
* @retval -1 -> Error
*
*
*/
BMP280_RETURN_FUNCTION_TYPE bmp280_write_register(uint8_t v_addr_u8,
uint8_t *v_data_u8, uint8_t v_len_u8);
/*!
* @brief
* This API reads the data from
* the given register
*
*
* @param v_addr_u8 -> Address of the register
* @param v_data_u8 -> The data from the register
* @param v_len_u8 -> no of bytes to read
*
*
* @return results of bus communication function
* @retval 0 -> Success
* @retval -1 -> Error
*
*
*/
BMP280_RETURN_FUNCTION_TYPE bmp280_read_register(uint8_t v_addr_u8,
uint8_t *v_data_u8, uint8_t v_len_u8);
/**************************************************************/
/**\name FUNCTION FOR TRUE TEMPERATURE CALCULATION */
/**************************************************************/
#ifdef BMP280_ENABLE_FLOAT
/*!
* @brief This API used to read
* actual temperature from uncompensated temperature
* @note Returns the value in Degree centigrade
* @note Output value of "51.23" equals 51.23 DegC.
*
*
*
* @param v_uncomp_temperature_s32 : value of uncompensated temperature
*
*
*
* @return
* Actual temperature in floating point
*
*/
float bmp280_compensate_temperature_float(int32_t v_uncomp_temperature_s32);
/**************************************************************/
/**\name FUNCTION FOR TRUE PRESSURE CALCULATION */
/**************************************************************/
/*!
* @brief Reads actual pressure from uncompensated pressure
* and returns pressure in Pa as float.
* @note Output value of "96386.2"
* equals 96386.2 Pa = 963.862 hPa.
*
*
*
* @param v_uncomp_pressure_s32 : value of uncompensated pressure
*
*
*
* @return
* Actual pressure in floating point
*
*/
float bmp280_compensate_pressure_float(int32_t v_uncomp_pressure_s32);
#endif
#if defined(BMP280_ENABLE_INT64) && defined(BMP280_64BITSUPPORT_PRESENT)
/*!
* @brief This API used to read actual pressure from uncompensated pressure
* @note returns the value in Pa as unsigned 32 bit
* integer in Q24.8 format (24 integer bits and
* 8 fractional bits). Output value of "24674867"
* represents 24674867 / 256 = 96386.2 Pa = 963.862 hPa
*
*
*
* @param v_uncomp_pressure_s32 : value of uncompensated pressure
*
*
*
* @return actual pressure as 64bit output
*
*/
uint32_t bmp280_compensate_pressure_int64(int32_t v_uncomp_pressure_s32);
#endif
/**************************************************************/
/**\name FUNCTION FOR DELAY CALCULATION DURING FORCEMODE */
/**************************************************************/
/*!
* @brief Computing waiting time for sensor data read
*
*
*
*
* @param v_delaytime_u8r: The value of delay time
*
*
* @return 0
*
*
*/
BMP280_RETURN_FUNCTION_TYPE bmp280_compute_wait_time(uint8_t
*v_delaytime_u8r);
#endif
/**
* Copyright (C) 2016 - 2017 Bosch Sensortec GmbH
*
* 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.
*
* @file bmp3.h
* @date 04 Dec 2017
* @version 1.0.0
* @brief
*
*/
/*! @file bmp3.h
@brief Sensor driver for BMP3 sensor */
/*!
* @defgroup BMP3 SENSOR API
* @{*/
#ifndef BMP3_H_
#define BMP3_H_
/* Header includes */
#include "bmp3_defs.h"
/*!
* @brief This API is the entry point.
* It performs the selection of I2C/SPI read mechanism according to the
* selected interface and reads the chip-id and calibration data of the sensor.
*
* @param[in,out] dev : Structure instance of bmp3_dev
*
* @return Result of API execution status
* @retval zero -> Success / +ve value -> Warning / -ve value -> Error
*/
int8_t bmp3_init(struct bmp3_dev *dev);
/*!
* @brief This API performs the soft reset of the sensor.
*
* @param[in] dev : Structure instance of bmp3_dev.
*
* @return Result of API execution status
* @retval zero -> Success / +ve value -> Warning / -ve value -> Error.
*/
int8_t bmp3_soft_reset(const struct bmp3_dev *dev);
/*!
* @brief This API sets the power control(pressure enable and
* temperature enable), over sampling, odr and filter
* settings in the sensor.
*
* @param[in] dev : Structure instance of bmp3_dev.
* @param[in] desired_settings : Variable used to select the settings which
* are to be set in the sensor.
*
* @note : Below are the macros to be used by the user for selecting the
* desired settings. User can do OR operation of these macros for configuring
* multiple settings.
*
* Macros | Functionality
* -----------------------|----------------------------------------------
* BMP3_PRESS_EN_SEL | Enable/Disable pressure.
* BMP3_TEMP_EN_SEL | Enable/Disable temperature.
* BMP3_PRESS_OS_SEL | Set pressure oversampling.
* BMP3_TEMP_OS_SEL | Set temperature oversampling.
* BMP3_IIR_FILTER_SEL | Set IIR filter.
* BMP3_ODR_SEL | Set ODR.
* BMP3_OUTPUT_MODE_SEL | Set either open drain or push pull
* BMP3_LEVEL_SEL | Set interrupt pad to be active high or low
* BMP3_LATCH_SEL | Set interrupt pad to be latched or nonlatched.
* BMP3_DRDY_EN_SEL | Map/Unmap the drdy interrupt to interrupt pad.
* BMP3_I2C_WDT_EN_SEL | Enable/Disable I2C internal watch dog.
* BMP3_I2C_WDT_SEL_SEL | Set I2C watch dog timeout delay.
*
* @return Result of API execution status
* @retval zero -> Success / +ve value -> Warning / -ve value -> Error.
*/
int8_t bmp3_set_sensor_settings(uint32_t desired_settings, struct bmp3_dev *dev);
/*!
* @brief This API gets the power control(power mode, pressure enable and
* temperature enable), over sampling, odr, filter, interrupt control and
* advance settings from the sensor.
*
* @param[in,out] dev : Structure instance of bmp3_dev.
*
* @return Result of API execution status
* @retval zero -> Success / +ve value -> Warning / -ve value -> Error.
*/
int8_t bmp3_get_sensor_settings(struct bmp3_dev *dev);
/*!
* @brief This API sets the power mode of the sensor.
*
* @param[in] dev : Structure instance of bmp3_dev.
*
* dev->settings.op_mode | Macros
* ----------------------|-------------------
* 0 | BMP3_SLEEP_MODE
* 1 | BMP3_FORCED_MODE
* 3 | BMP3_NORMAL_MODE
*
*
* @note : Before setting normal mode, valid odr and osr settings should be set
* in the sensor by using 'bmp3_set_sensor_settings' function.
*
* @return Result of API execution status
* @retval zero -> Success / +ve value -> Warning / -ve value -> Error
*/
int8_t bmp3_set_op_mode(struct bmp3_dev *dev);
/*!
* @brief This API gets the power mode of the sensor.
*
* @param[in] dev : Structure instance of bmp3_dev.
* @param[out] op_mode : Pointer variable to store the op-mode.
*
* op_mode | Macros
* ----------------------|-------------------
* 0 | BMP3_SLEEP_MODE
* 1 | BMP3_FORCED_MODE
* 3 | BMP3_NORMAL_MODE
*
* @return Result of API execution status
* @retval zero -> Success / +ve value -> Warning / -ve value -> Error
*/
int8_t bmp3_get_op_mode(uint8_t *op_mode, const struct bmp3_dev *dev);
/*!
* @brief This API reads the pressure, temperature or both data from the
* sensor, compensates the data and store it in the bmp3_data structure
* instance passed by the user.
*
* @param[in] sensor_comp : Variable which selects which data to be read from
* the sensor.
*
* sensor_comp | Macros
* ------------|-------------------
* 1 | BMP3_PRESS
* 2 | BMP3_TEMP
* 3 | BMP3_ALL
*
* @param[out] data : Structure instance of bmp3_data.
* @param[in] dev : Structure instance of bmp3_dev.
*
* @return Result of API execution status
* @retval zero -> Success / +ve value -> Warning / -ve value -> Error
*/
int8_t bmp3_get_sensor_data(uint8_t sensor_comp, struct bmp3_data *data, struct bmp3_dev *dev);
/*!
* @brief This API writes the given data to the register address
* of the sensor.
*
* @param[in] reg_addr : Register address from where the data to be written.
* @param[in] reg_data : Pointer to data buffer which is to be written
* in the sensor.
* @param[in] len : No of bytes of data to write..
* @param[in] dev : Structure instance of bmp3_dev.
*
* @return Result of API execution status
* @retval zero -> Success / +ve value -> Warning / -ve value -> Error
*/
int8_t bmp3_set_regs(uint8_t *reg_addr, const uint8_t *reg_data, uint8_t len, const struct bmp3_dev *dev);
/*!
* @brief This API reads the data from the given register address of the sensor.
*
* @param[in] reg_addr : Register address from where the data to be read
* @param[out] reg_data : Pointer to data buffer to store the read data.
* @param[in] length : No of bytes of data to be read.
* @param[in] dev : Structure instance of bmp3_dev.
*
* @return Result of API execution status
* @retval zero -> Success / +ve value -> Warning / -ve value -> Error
*/
int8_t bmp3_get_regs(uint8_t reg_addr, uint8_t *reg_data, uint16_t length, const struct bmp3_dev *dev);
/*!
* @brief This API sets the fifo_config_1(fifo_mode,
* fifo_stop_on_full, fifo_time_en, fifo_press_en, fifo_temp_en),
* fifo_config_2(fifo_subsampling, data_select) and int_ctrl(fwtm_en, ffull_en)
* settings in the sensor.
*
* @param[in] dev : Structure instance of bmp3_dev.
* @param[in] desired_settings : Variable used to select the FIFO settings which
* are to be set in the sensor.
*
* @note : Below are the macros to be used by the user for selecting the
* desired settings. User can do OR operation of these macros for configuring
* multiple settings.
*
* Macros | Functionality
* --------------------------------|----------------------------
* BMP3_FIFO_MODE_SEL | Enable/Disable FIFO
* BMP3_FIFO_STOP_ON_FULL_EN_SEL | Set FIFO stop on full interrupt
* BMP3_FIFO_TIME_EN_SEL | Enable/Disable FIFO time
* BMP3_FIFO_PRESS_EN_SEL | Enable/Disable pressure
* BMP3_FIFO_TEMP_EN_SEL | Enable/Disable temperature
* BMP3_FIFO_DOWN_SAMPLING_SEL | Set FIFO downsampling
* BMP3_FIFO_FILTER_EN_SEL | Enable/Disable FIFO filter
* BMP3_FIFO_FWTM_EN_SEL | Enable/Disable FIFO watermark interrupt
* BMP3_FIFO_FFULL_EN_SEL | Enable/Disable FIFO full interrupt
*
* @return Result of API execution status
* @retval zero -> Success / +ve value -> Warning / -ve value -> Error.
*/
int8_t bmp3_set_fifo_settings(uint16_t desired_settings, const struct bmp3_dev *dev);
/*!
* @brief This API gets the fifo_config_1(fifo_mode,
* fifo_stop_on_full, fifo_time_en, fifo_press_en, fifo_temp_en),
* fifo_config_2(fifo_subsampling, data_select) and int_ctrl(fwtm_en, ffull_en)
* settings from the sensor.
*
* @param[in,out] dev : Structure instance of bmp3_dev.
*
* @return Result of API execution status
* @retval zero -> Success / +ve value -> Warning / -ve value -> Error.
*/
int8_t bmp3_get_fifo_settings(const struct bmp3_dev *dev);
/*!
* @brief This API gets the fifo data from the sensor.
*
* @param[in,out] dev : Structure instance of bmp3 device, where the fifo
* data will be stored in fifo buffer.
*
* @return Result of API execution status.
* @retval zero -> Success / +ve value -> Warning / -ve value -> Error.
*/
int8_t bmp3_get_fifo_data(const struct bmp3_dev *dev);
/*!
* @brief This API gets the fifo length from the sensor.
*
* @param[out] fifo_length : Variable used to store the fifo length.
* @param[in] dev : Structure instance of bmp3_dev.
*
* @return Result of API execution status.
* @retval zero -> Success / +ve value -> Warning / -ve value -> Error.
*/
int8_t bmp3_get_fifo_length(uint16_t *fifo_length, const struct bmp3_dev *dev);
/*!
* @brief This API extracts the temperature and/or pressure data from the FIFO
* data which is already read from the fifo.
*
* @param[out] data : Array of bmp3_data structures where the temperature
* and pressure frames will be stored.
* @param[in,out] dev : Structure instance of bmp3_dev which contains the
* fifo buffer to parse the temperature and pressure frames.
*
* @return Result of API execution status.
* @retval zero -> Success / -ve value -> Error.
*/
int8_t bmp3_extract_fifo_data(struct bmp3_data *data, struct bmp3_dev *dev);
/*!
* @brief This API gets the command ready, data ready for pressure and
* temperature and interrupt (fifo watermark, fifo full, data ready) and
* error status from the sensor.
*
* @param[in,out] dev : Structure instance of bmp3_dev
*
* @return Result of API execution status.
* @retval zero -> Success / -ve value -> Error.
*/
int8_t bmp3_get_status(struct bmp3_dev *dev);
/*!
* @brief This API sets the fifo watermark length according to the frames count
* set by the user in the device structure. Refer below for usage.
*
* @note: dev->fifo->data.req_frames = 50;
*
* @param[in] dev : Structure instance of bmp3_dev
*
* @return Result of API execution status.
* @retval zero -> Success / -ve value -> Error.
*/
int8_t bmp3_set_fifo_watermark(const struct bmp3_dev *dev);
#endif /* BMP3_H_ */
/** @}*/
/**
* Copyright (C) 2016 - 2017 Bosch Sensortec GmbH
*
* 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.
*
* @file bmp3_defs.h
* @date 04 Dec 2017
* @version 1.0.0
* @brief
*
*/
/*! @file bmp3_defs.h
@brief Sensor driver for BMP3 sensor */
/*!
* @defgroup BMP3 SENSOR API
* @brief
* @{*/
#ifndef BMP3_DEFS_H_
#define BMP3_DEFS_H_
/********************************************************/
/* header includes */
#ifdef __KERNEL__
#include <linux/types.h>
#include <linux/kernel.h>
#else
#include <stdint.h>
#include <stddef.h>
#endif
/*************************** Common macros *****************************/
#if !defined(UINT8_C) && !defined(INT8_C)
#define INT8_C(x) S8_C(x)
#define UINT8_C(x) U8_C(x)
#endif
#if !defined(UINT16_C) && !defined(INT16_C)
#define INT16_C(x) S16_C(x)
#define UINT16_C(x) U16_C(x)
#endif
#if !defined(INT32_C) && !defined(UINT32_C)
#define INT32_C(x) S32_C(x)
#define UINT32_C(x) U32_C(x)
#endif
#if !defined(INT64_C) && !defined(UINT64_C)
#define INT64_C(x) S64_C(x)
#define UINT64_C(x) U64_C(x)
#endif
/**@}*/
/**\name C standard macros */
#ifndef NULL
#ifdef __cplusplus
#define NULL 0
#else
#define NULL ((void *) 0)
#endif
#endif
#define TRUE UINT8_C(1)
#define FALSE UINT8_C(0)
/********************************************************/
/**\name Compiler switch macros */
/**\name Comment the below line to use fixed-point compensation */
#define FLOATING_POINT_COMPENSATION
/********************************************************/
/**\name Macro definitions */
/**\name I2C addresses */
#define BMP3_I2C_ADDR_PRIM UINT8_C(0x76)
#define BMP3_I2C_ADDR_SEC UINT8_C(0x77)
/**\name BMP3 chip identifier */
#define BMP3_CHIP_ID UINT8_C(0x50)
/**\name BMP3 pressure settling time (micro secs)*/
#define BMP3_PRESS_SETTLE_TIME UINT16_C(392)
/**\name BMP3 temperature settling time (micro secs) */
#define BMP3_TEMP_SETTLE_TIME UINT16_C(313)
/**\name BMP3 adc conversion time (micro secs) */
#define BMP3_ADC_CONV_TIME UINT16_C(2000)
/**\name Register Address */
#define BMP3_CHIP_ID_ADDR UINT8_C(0x00)
#define BMP3_ERR_REG_ADDR UINT8_C(0x02)
#define BMP3_SENS_STATUS_REG_ADDR UINT8_C(0x03)
#define BMP3_DATA_ADDR UINT8_C(0x04)
#define BMP3_EVENT_ADDR UINT8_C(0x10)
#define BMP3_INT_STATUS_REG_ADDR UINT8_C(0x11)
#define BMP3_FIFO_LENGTH_ADDR UINT8_C(0x12)
#define BMP3_FIFO_DATA_ADDR UINT8_C(0x14)
#define BMP3_FIFO_WM_ADDR UINT8_C(0x15)
#define BMP3_FIFO_CONFIG_1_ADDR UINT8_C(0x17)
#define BMP3_FIFO_CONFIG_2_ADDR UINT8_C(0x18)
#define BMP3_INT_CTRL_ADDR UINT8_C(0x19)
#define BMP3_IF_CONF_ADDR UINT8_C(0x1A)
#define BMP3_PWR_CTRL_ADDR UINT8_C(0x1B)
#define BMP3_OSR_ADDR UINT8_C(0X1C)
#define BMP3_CALIB_DATA_ADDR UINT8_C(0x31)
#define BMP3_CMD_ADDR UINT8_C(0x7E)
/**\name Error status macros */
#define BMP3_FATAL_ERR UINT8_C(0x01)
#define BMP3_CMD_ERR UINT8_C(0x02)
#define BMP3_CONF_ERR UINT8_C(0x04)
/**\name Status macros */
#define BMP3_CMD_RDY UINT8_C(0x10)
#define BMP3_DRDY_PRESS UINT8_C(0x20)
#define BMP3_DRDY_TEMP UINT8_C(0x40)
/**\name Power mode macros */
#define BMP3_SLEEP_MODE UINT8_C(0x00)
#define BMP3_FORCED_MODE UINT8_C(0x01)
#define BMP3_NORMAL_MODE UINT8_C(0x03)
/**\name FIFO related macros */
/**\name FIFO enable */
#define BMP3_ENABLE UINT8_C(0x01)
#define BMP3_DISABLE UINT8_C(0x00)
/**\name Interrupt pin configuration macros */
/**\name Open drain */
#define BMP3_INT_PIN_OPEN_DRAIN UINT8_C(0x01)
#define BMP3_INT_PIN_PUSH_PULL UINT8_C(0x00)
/**\name Level */
#define BMP3_INT_PIN_ACTIVE_HIGH UINT8_C(0x01)
#define BMP3_INT_PIN_ACTIVE_LOW UINT8_C(0x00)
/**\name Latch */
#define BMP3_INT_PIN_LATCH UINT8_C(0x01)
#define BMP3_INT_PIN_NON_LATCH UINT8_C(0x00)
/**\name Advance settings */
/**\name I2c watch dog timer period selection */
#define BMP3_I2C_WDT_SHORT_1_25_MS UINT8_C(0x00)
#define BMP3_I2C_WDT_LONG_40_MS UINT8_C(0x01)
/**\name FIFO Sub-sampling macros */
#define BMP3_FIFO_NO_SUBSAMPLING UINT8_C(0x00)
#define BMP3_FIFO_SUBSAMPLING_2X UINT8_C(0x01)
#define BMP3_FIFO_SUBSAMPLING_4X UINT8_C(0x02)
#define BMP3_FIFO_SUBSAMPLING_8X UINT8_C(0x03)
#define BMP3_FIFO_SUBSAMPLING_16X UINT8_C(0x04)
#define BMP3_FIFO_SUBSAMPLING_32X UINT8_C(0x05)
#define BMP3_FIFO_SUBSAMPLING_64X UINT8_C(0x06)
#define BMP3_FIFO_SUBSAMPLING_128X UINT8_C(0x07)
/**\name Over sampling macros */
#define BMP3_NO_OVERSAMPLING UINT8_C(0x00)
#define BMP3_OVERSAMPLING_2X UINT8_C(0x01)
#define BMP3_OVERSAMPLING_4X UINT8_C(0x02)
#define BMP3_OVERSAMPLING_8X UINT8_C(0x03)
#define BMP3_OVERSAMPLING_16X UINT8_C(0x04)
#define BMP3_OVERSAMPLING_32X UINT8_C(0x05)
/**\name Filter setting macros */
#define BMP3_IIR_FILTER_DISABLE UINT8_C(0x00)
#define BMP3_IIR_FILTER_COEFF_1 UINT8_C(0x01)
#define BMP3_IIR_FILTER_COEFF_3 UINT8_C(0x02)
#define BMP3_IIR_FILTER_COEFF_7 UINT8_C(0x03)
#define BMP3_IIR_FILTER_COEFF_15 UINT8_C(0x04)
#define BMP3_IIR_FILTER_COEFF_31 UINT8_C(0x05)
#define BMP3_IIR_FILTER_COEFF_63 UINT8_C(0x06)
#define BMP3_IIR_FILTER_COEFF_127 UINT8_C(0x07)
/**\name Odr setting macros */
#define BMP3_ODR_200_HZ UINT8_C(0x00)
#define BMP3_ODR_100_HZ UINT8_C(0x01)
#define BMP3_ODR_50_HZ UINT8_C(0x02)
#define BMP3_ODR_25_HZ UINT8_C(0x03)
#define BMP3_ODR_12_5_HZ UINT8_C(0x04)
#define BMP3_ODR_6_25_HZ UINT8_C(0x05)
#define BMP3_ODR_3_1_HZ UINT8_C(0x06)
#define BMP3_ODR_1_5_HZ UINT8_C(0x07)
#define BMP3_ODR_0_78_HZ UINT8_C(0x08)
#define BMP3_ODR_0_39_HZ UINT8_C(0x09)
#define BMP3_ODR_0_2_HZ UINT8_C(0x0A)
#define BMP3_ODR_0_1_HZ UINT8_C(0x0B)
#define BMP3_ODR_0_05_HZ UINT8_C(0x0C)
#define BMP3_ODR_0_02_HZ UINT8_C(0x0D)
#define BMP3_ODR_0_01_HZ UINT8_C(0x0E)
#define BMP3_ODR_0_006_HZ UINT8_C(0x0F)
#define BMP3_ODR_0_003_HZ UINT8_C(0x10)
#define BMP3_ODR_0_001_HZ UINT8_C(0x11)
/**\name API success code */
#define BMP3_OK INT8_C(0)
/**\name API error codes */
#define BMP3_E_NULL_PTR INT8_C(-1)
#define BMP3_E_DEV_NOT_FOUND INT8_C(-2)
#define BMP3_E_INVALID_ODR_OSR_SETTINGS INT8_C(-3)
#define BMP3_E_CMD_EXEC_FAILED INT8_C(-4)
#define BMP3_E_CONFIGURATION_ERR INT8_C(-5)
#define BMP3_E_INVALID_LEN INT8_C(-6)
#define BMP3_E_COMM_FAIL INT8_C(-7)
#define BMP3_E_FIFO_WATERMARK_NOT_REACHED INT8_C(-8)
/**\name API warning codes */
#define BMP3_W_SENSOR_NOT_ENABLED UINT8_C(1)
#define BMP3_W_INVALID_FIFO_REQ_FRAME_CNT UINT8_C(2)
/**\name Macros to select the which sensor settings are to be set by the user.
These values are internal for API implementation. Don't relate this to
data sheet. */
#define BMP3_PRESS_EN_SEL UINT16_C(1 << 1)
#define BMP3_TEMP_EN_SEL UINT16_C(1 << 2)
#define BMP3_DRDY_EN_SEL UINT16_C(1 << 3)
#define BMP3_PRESS_OS_SEL UINT16_C(1 << 4)
#define BMP3_TEMP_OS_SEL UINT16_C(1 << 5)
#define BMP3_IIR_FILTER_SEL UINT16_C(1 << 6)
#define BMP3_ODR_SEL UINT16_C(1 << 7)
#define BMP3_OUTPUT_MODE_SEL UINT16_C(1 << 8)
#define BMP3_LEVEL_SEL UINT16_C(1 << 9)
#define BMP3_LATCH_SEL UINT16_C(1 << 10)
#define BMP3_I2C_WDT_EN_SEL UINT16_C(1 << 11)
#define BMP3_I2C_WDT_SEL_SEL UINT16_C(1 << 12)
#define BMP3_ALL_SETTINGS UINT16_C(0x7FF)
/**\name Macros to select the which FIFO settings are to be set by the user
These values are internal for API implementation. Don't relate this to
data sheet.*/
#define BMP3_FIFO_MODE_SEL UINT16_C(1 << 1)
#define BMP3_FIFO_STOP_ON_FULL_EN_SEL UINT16_C(1 << 2)
#define BMP3_FIFO_TIME_EN_SEL UINT16_C(1 << 3)
#define BMP3_FIFO_PRESS_EN_SEL UINT16_C(1 << 4)
#define BMP3_FIFO_TEMP_EN_SEL UINT16_C(1 << 5)
#define BMP3_FIFO_DOWN_SAMPLING_SEL UINT16_C(1 << 6)
#define BMP3_FIFO_FILTER_EN_SEL UINT16_C(1 << 7)
#define BMP3_FIFO_FWTM_EN_SEL UINT16_C(1 << 8)
#define BMP3_FIFO_FULL_EN_SEL UINT16_C(1 << 9)
#define BMP3_FIFO_ALL_SETTINGS UINT16_C(0x3FF)
/**\name Sensor component selection macros
These values are internal for API implementation. Don't relate this to
data sheet.*/
#define BMP3_PRESS UINT8_C(1)
#define BMP3_TEMP UINT8_C(1 << 1)
#define BMP3_ALL UINT8_C(0x03)
/**\name Macros for bit masking */
#define BMP3_ERR_FATAL_MSK UINT8_C(0x01)
#define BMP3_ERR_CMD_MSK UINT8_C(0x02)
#define BMP3_ERR_CMD_POS UINT8_C(0x01)
#define BMP3_ERR_CONF_MSK UINT8_C(0x04)
#define BMP3_ERR_CONF_POS UINT8_C(0x02)
#define BMP3_STATUS_CMD_RDY_MSK UINT8_C(0x10)
#define BMP3_STATUS_CMD_RDY_POS UINT8_C(0x04)
#define BMP3_STATUS_DRDY_PRESS_MSK UINT8_C(0x20)
#define BMP3_STATUS_DRDY_PRESS_POS UINT8_C(0x05)
#define BMP3_STATUS_DRDY_TEMP_MSK UINT8_C(0x40)
#define BMP3_STATUS_DRDY_TEMP_POS UINT8_C(0x06)
#define BMP3_OP_MODE_MSK UINT8_C(0x30)
#define BMP3_OP_MODE_POS UINT8_C(0x04)
#define BMP3_PRESS_EN_MSK UINT8_C(0x01)
#define BMP3_TEMP_EN_MSK UINT8_C(0x02)
#define BMP3_TEMP_EN_POS UINT8_C(0x01)
#define BMP3_IIR_FILTER_MSK UINT8_C(0x0E)
#define BMP3_IIR_FILTER_POS UINT8_C(0x01)
#define BMP3_ODR_MSK UINT8_C(0x1F)
#define BMP3_PRESS_OS_MSK UINT8_C(0x07)
#define BMP3_TEMP_OS_MSK UINT8_C(0x38)
#define BMP3_TEMP_OS_POS UINT8_C(0x03)
#define BMP3_FIFO_MODE_MSK UINT8_C(0x01)
#define BMP3_FIFO_STOP_ON_FULL_MSK UINT8_C(0x02)
#define BMP3_FIFO_STOP_ON_FULL_POS UINT8_C(0x01)
#define BMP3_FIFO_TIME_EN_MSK UINT8_C(0x04)
#define BMP3_FIFO_TIME_EN_POS UINT8_C(0x02)
#define BMP3_FIFO_PRESS_EN_MSK UINT8_C(0x08)
#define BMP3_FIFO_PRESS_EN_POS UINT8_C(0x03)
#define BMP3_FIFO_TEMP_EN_MSK UINT8_C(0x10)
#define BMP3_FIFO_TEMP_EN_POS UINT8_C(0x04)
#define BMP3_FIFO_FILTER_EN_MSK UINT8_C(0x18)
#define BMP3_FIFO_FILTER_EN_POS UINT8_C(0x03)
#define BMP3_FIFO_DOWN_SAMPLING_MSK UINT8_C(0x07)
#define BMP3_FIFO_FWTM_EN_MSK UINT8_C(0x08)
#define BMP3_FIFO_FWTM_EN_POS UINT8_C(0x03)
#define BMP3_FIFO_FULL_EN_MSK UINT8_C(0x10)
#define BMP3_FIFO_FULL_EN_POS UINT8_C(0x04)
#define BMP3_INT_OUTPUT_MODE_MSK UINT8_C(0x01)
#define BMP3_INT_LEVEL_MSK UINT8_C(0x02)
#define BMP3_INT_LEVEL_POS UINT8_C(0x01)
#define BMP3_INT_LATCH_MSK UINT8_C(0x04)
#define BMP3_INT_LATCH_POS UINT8_C(0x02)
#define BMP3_INT_DRDY_EN_MSK UINT8_C(0x40)
#define BMP3_INT_DRDY_EN_POS UINT8_C(0x06)
#define BMP3_I2C_WDT_EN_MSK UINT8_C(0x02)
#define BMP3_I2C_WDT_EN_POS UINT8_C(0x01)
#define BMP3_I2C_WDT_SEL_MSK UINT8_C(0x04)
#define BMP3_I2C_WDT_SEL_POS UINT8_C(0x02)
#define BMP3_INT_STATUS_FWTM_MSK UINT8_C(0x01)
#define BMP3_INT_STATUS_FFULL_MSK UINT8_C(0x02)
#define BMP3_INT_STATUS_FFULL_POS UINT8_C(0x01)
#define BMP3_INT_STATUS_DRDY_MSK UINT8_C(0x08)
#define BMP3_INT_STATUS_DRDY_POS UINT8_C(0x03)
/**\name UTILITY MACROS */
#define BMP3_SET_LOW_BYTE UINT16_C(0x00FF)
#define BMP3_SET_HIGH_BYTE UINT16_C(0xFF00)
/**\name Macro to combine two 8 bit data's to form a 16 bit data */
#define BMP3_CONCAT_BYTES(msb, lsb) (((uint16_t)msb << 8) | (uint16_t)lsb)
#define BMP3_SET_BITS(reg_data, bitname, data) \
((reg_data & ~(bitname##_MSK)) | \
((data << bitname##_POS) & bitname##_MSK))
/* Macro variant to handle the bitname position if it is zero */
#define BMP3_SET_BITS_POS_0(reg_data, bitname, data) \
((reg_data & ~(bitname##_MSK)) | \
(data & bitname##_MSK))
#define BMP3_GET_BITS(reg_data, bitname) ((reg_data & (bitname##_MSK)) >> \
(bitname##_POS))
/* Macro variant to handle the bitname position if it is zero */
#define BMP3_GET_BITS_POS_0(reg_data, bitname) (reg_data & (bitname##_MSK))
#define BMP3_GET_LSB(var) (uint8_t)(var & BMP3_SET_LOW_BYTE)
#define BMP3_GET_MSB(var) (uint8_t)((var & BMP3_SET_HIGH_BYTE) >> 8)
/**\name Macros related to size */
#define BMP3_CALIB_DATA_LEN UINT8_C(21)
#define BMP3_P_AND_T_HEADER_DATA_LEN UINT8_C(7)
#define BMP3_P_OR_T_HEADER_DATA_LEN UINT8_C(4)
#define BMP3_P_T_DATA_LEN UINT8_C(6)
#define BMP3_GEN_SETT_LEN UINT8_C(7)
#define BMP3_P_DATA_LEN UINT8_C(3)
#define BMP3_T_DATA_LEN UINT8_C(3)
#define BMP3_SENSOR_TIME_LEN UINT8_C(3)
#define BMP3_FIFO_MAX_FRAMES UINT8_C(73)
/********************************************************/
/*!
* @brief Interface selection Enums
*/
enum bmp3_intf {
/*! SPI interface */
BMP3_SPI_INTF,
/*! I2C interface */
BMP3_I2C_INTF
};
/********************************************************/
/*!
* @brief Type definitions
*/
typedef int8_t (*bmp3_com_fptr_t)(uint8_t dev_id, uint8_t reg_addr,
uint8_t *data, uint16_t len);
typedef void (*bmp3_delay_fptr_t)(uint32_t period);
/********************************************************/
/*!
* @brief Register Trim Variables
*/
struct bmp3_reg_calib_data {
/**
* @ Trim Variables
*/
/**@{*/
uint16_t par_t1;
uint16_t par_t2;
int8_t par_t3;
int16_t par_p1;
int16_t par_p2;
int8_t par_p3;
int8_t par_p4;
uint16_t par_p5;
uint16_t par_p6;
int8_t par_p7;
int8_t par_p8;
int16_t par_p9;
int8_t par_p10;
int8_t par_p11;
int64_t t_lin;
/**@}*/
};
/*!
* @brief bmp3 advance settings
*/
struct bmp3_adv_settings {
/*! i2c watch dog enable */
uint8_t i2c_wdt_en;
/*! i2c watch dog select */
uint8_t i2c_wdt_sel;
};
/*!
* @brief bmp3 odr and filter settings
*/
struct bmp3_odr_filter_settings {
/*! Pressure oversampling */
uint8_t press_os;
/*! Temperature oversampling */
uint8_t temp_os;
/*! IIR filter */
uint8_t iir_filter;
/*! Output data rate */
uint8_t odr;
};
/*!
* @brief bmp3 sensor status flags
*/
struct bmp3_sens_status {
/*! Command ready status */
uint8_t cmd_rdy;
/*! Data ready for pressure */
uint8_t drdy_press;
/*! Data ready for temperature */
uint8_t drdy_temp;
};
/*!
* @brief bmp3 interrupt status flags
*/
struct bmp3_int_status {
/*! fifo watermark interrupt */
uint8_t fifo_wm;
/*! fifo full interrupt */
uint8_t fifo_full;
/*! data ready interrupt */
uint8_t drdy;
};
/*!
* @brief bmp3 error status flags
*/
struct bmp3_err_status {
/*! fatal error */
uint8_t fatal;
/*! command error */
uint8_t cmd;
/*! configuration error */
uint8_t conf;
};
/*!
* @brief bmp3 status flags
*/
struct bmp3_status {
/*! Interrupt status */
struct bmp3_int_status intr;
/*! Sensor status */
struct bmp3_sens_status sensor;
/*! Error status */
struct bmp3_err_status err;
/*! power on reset status */
uint8_t pwr_on_rst;
};
/*!
* @brief bmp3 interrupt pin settings
*/
struct bmp3_int_ctrl_settings {
/*! Output mode */
uint8_t output_mode;
/*! Active high/low */
uint8_t level;
/*! Latched or Non-latched */
uint8_t latch;
/*! Data ready interrupt */
uint8_t drdy_en;
};
/*!
* @brief bmp3 device settings
*/
struct bmp3_settings {
/*! Power mode which user wants to set */
uint8_t op_mode;
/*! Enable/Disable pressure sensor */
uint8_t press_en;
/*! Enable/Disable temperature sensor */
uint8_t temp_en;
/*! ODR and filter configuration */
struct bmp3_odr_filter_settings odr_filter;
/*! Interrupt configuration */
struct bmp3_int_ctrl_settings int_settings;
/*! Advance settings */
struct bmp3_adv_settings adv_settings;
};
/*!
* @brief bmp3 fifo frame
*/
struct bmp3_fifo_data {
/*! Data buffer of user defined length is to be mapped here
512 + 4 */
uint8_t buffer[516];
/*! Number of bytes of data read from the fifo */
uint16_t byte_count;
/*! Number of frames to be read as specified by the user */
uint8_t req_frames;
/*! Will be equal to length when no more frames are there to parse */
uint16_t start_idx;
/*! Will contain the no of parsed data frames from fifo */
uint8_t parsed_frames;
/*! Configuration error */
uint8_t config_err;
/*! Sensor time */
uint32_t sensor_time;
/*! FIFO input configuration change */
uint8_t config_change;
/*! All available frames are parsed */
uint8_t frame_not_available;
};
/*!
* @brief bmp3 fifo configuration
*/
struct bmp3_fifo_settings {
/*! enable/disable */
uint8_t mode;
/*! stop on full enable/disable */
uint8_t stop_on_full_en;
/*! time enable/disable */
uint8_t time_en;
/*! pressure enable/disable */
uint8_t press_en;
/*! temperature enable/disable */
uint8_t temp_en;
/*! down sampling rate */
uint8_t down_sampling;
/*! filter enable/disable */
uint8_t filter_en;
/*! FIFO watermark enable/disable */
uint8_t fwtm_en;
/*! FIFO full enable/disable */
uint8_t ffull_en;
};
/*!
* @brief bmp3 bmp3 FIFO
*/
struct bmp3_fifo {
/*! FIFO frame structure */
struct bmp3_fifo_data data;
/*! FIFO config structure */
struct bmp3_fifo_settings settings;
};
#ifdef FLOATING_POINT_COMPENSATION
/*!
* @brief Quantized Trim Variables
*/
struct bmp3_quantized_calib_data {
/**
* @ Quantized Trim Variables
*/
/**@{*/
float par_t1;
float par_t2;
float par_t3;
float par_p1;
float par_p2;
float par_p3;
float par_p4;
float par_p5;
float par_p6;
float par_p7;
float par_p8;
float par_p9;
float par_p10;
float par_p11;
float t_lin;
/**@}*/
};
/*!
* @brief Calibration data
*/
struct bmp3_calib_data {
/*! Quantized data */
struct bmp3_quantized_calib_data quantized_calib_data;
/*! Register data */
struct bmp3_reg_calib_data reg_calib_data;
};
/*!
* @brief bmp3 sensor structure which comprises of temperature and pressure
* data.
*/
struct bmp3_data {
/*! Compensated temperature */
float temperature;
/*! Compensated pressure */
float pressure;
};
#else
/*!
* @brief bmp3 sensor structure which comprises of temperature and pressure
* data.
*/
struct bmp3_data {
/*! Compensated temperature */
int64_t temperature;
/*! Compensated pressure */
uint64_t pressure;
};
/*!
* @brief Calibration data
*/
struct bmp3_calib_data {
/*! Register data */
struct bmp3_reg_calib_data reg_calib_data;
};
#endif /* BMP3_USE_FLOATING_POINT */
/*!
* @brief bmp3 sensor structure which comprises of uncompensated temperature
* and pressure data.
*/
struct bmp3_uncomp_data {
/*! un-compensated pressure */
uint32_t pressure;
/*! un-compensated temperature */
uint32_t temperature;
};
/*!
* @brief bmp3 device structure
*/
struct bmp3_dev {
/*! Chip Id */
uint8_t chip_id;
/*! Device Id */
uint8_t dev_id;
/*! SPI/I2C interface */
enum bmp3_intf intf;
/*! Decide SPI or I2C read mechanism */
uint8_t dummy_byte;
/*! Read function pointer */
bmp3_com_fptr_t read;
/*! Write function pointer */
bmp3_com_fptr_t write;
/*! Delay function pointer */
bmp3_delay_fptr_t delay_ms;
/*! Trim data */
struct bmp3_calib_data calib_data;
/*! Sensor Settings */
struct bmp3_settings settings;
/*! Sensor and interrupt status flags */
struct bmp3_status status;
/*! FIFO data and settings structure */
struct bmp3_fifo *fifo;
};
#endif /* BMP3_DEFS_H_ */
/** @}*/
/** @}*/
/*
* Copyright (C) 2014 Bosch Sensortec GmbH
*
* \section Disclaimer
*
* Common:
* Bosch Sensortec products are developed for the consumer goods industry.
* They may only be used within the parameters of the respective valid
* product data sheet. Bosch Sensortec products are provided with the
* express understanding that there is no warranty of fitness for a
* particular purpose.They are not fit for use in life-sustaining,
* safety or security sensitive systems or any system or device
* that may lead to bodily harm or property damage if the system
* or device malfunctions. In addition,Bosch Sensortec products are
* not fit for use in products which interact with motor vehicle systems.
* The resale and or use of products are at the purchasers own risk and
* his own responsibility. The examination of fitness for the intended use
* is the sole responsibility of the Purchaser.
*
* The purchaser shall indemnify Bosch Sensortec from all third party
* claims, including any claims for incidental, or consequential damages,
* arising from any product use not covered by the parameters of
* the respective valid product data sheet or not approved by
* Bosch Sensortec and reimburse Bosch Sensortec for all costs in
* connection with such claims.
*
* The purchaser must monitor the market for the purchased products,
* particularly with regard to product safety and inform Bosch Sensortec
* without delay of all security relevant incidents.
*
* Engineering Samples are marked with an asterisk (*) or (e).
* Samples may vary from the valid technical specifications of the product
* series. They are therefore not intended or fit for resale to third
* parties or for use in end products. Their sole purpose is internal
* client testing. The testing of an engineering sample may in no way
* replace the testing of a product series. Bosch Sensortec assumes
* no liability for the use of engineering samples.
* By accepting the engineering samples, the Purchaser agrees to indemnify
* Bosch Sensortec from all claims arising from the use of engineering
* samples.
*
* Special:
* This software module (hereinafter called "Software") and any information
* on application-sheets (hereinafter called "Information") is provided
* free of charge for the sole purpose to support your application work.
* The Software and Information is subject to the following
* terms and conditions:
*
* The Software is specifically designed for the exclusive use for
* Bosch Sensortec products by personnel who have special experience
* and training. Do not use this Software if you do not have the
* proper experience or training.
*
* This Software package is provided `` as is `` and without any expressed
* or implied warranties,including without limitation, the implied warranties
* of merchantability and fitness for a particular purpose.
*
* Bosch Sensortec and their representatives and agents deny any liability
* for the functional impairment
* of this Software in terms of fitness, performance and safety.
* Bosch Sensortec and their representatives and agents shall not be liable
* for any direct or indirect damages or injury, except as
* otherwise stipulated in mandatory applicable law.
*
* The Information provided is believed to be accurate and reliable.
* Bosch Sensortec 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 Bosch. Specifications mentioned in the Information are
* subject to change without notice.
*/
/*!
* @file bstdr_comm_support.h
*
* @brief
* Contains communication API wrappers
*
*/
#ifndef __BSTDR_COMM_SUPPORT_H__
#define __BSTDR_COMM_SUPPORT_H__
#include "bstdr_types.h"
/*!
* @brief Communication initialization
*
* This is optional. Depends on the system you are using
*
* @return Zero if successful, otherwise an error code
*/
bstdr_ret_t bstdr_comm_init(void);
/*!
* @brief Generic burst read
*
* @param [out] dev_id I2C address, SPI chip select or user desired identifier
*
* @return Zero if successful, otherwise an error code
*/
bstdr_ret_t bstdr_burst_read(uint8_t dev_id, uint8_t reg_addr, uint8_t *reg_data, uint32_t len);
/*!
* @brief Generic burst write
*
* @param [out] dev_id I2C address, SPI chip select or user desired identifier
*
* @return Zero if successful, otherwise an error code
*/
bstdr_ret_t bstdr_burst_write(uint8_t dev_id, uint8_t reg_addr, uint8_t *reg_data, uint32_t len);
/*!
* @brief Generic burst read
*
* @param [in] period Delay period in milliseconds
*
* @return None
*/
void bstdr_ms_delay(uint32_t period);
#endif /* __BSTDR_COMM_SUPPORT_H__ */
/*
* Copyright (C) 2014 Bosch Sensortec GmbH
*
* \section Disclaimer
*
* Common:
* Bosch Sensortec products are developed for the consumer goods industry.
* They may only be used within the parameters of the respective valid
* product data sheet. Bosch Sensortec products are provided with the
* express understanding that there is no warranty of fitness for a
* particular purpose.They are not fit for use in life-sustaining,
* safety or security sensitive systems or any system or device
* that may lead to bodily harm or property damage if the system
* or device malfunctions. In addition,Bosch Sensortec products are
* not fit for use in products which interact with motor vehicle systems.
* The resale and or use of products are at the purchasers own risk and
* his own responsibility. The examination of fitness for the intended use
* is the sole responsibility of the Purchaser.
*
* The purchaser shall indemnify Bosch Sensortec from all third party
* claims, including any claims for incidental, or consequential damages,
* arising from any product use not covered by the parameters of
* the respective valid product data sheet or not approved by
* Bosch Sensortec and reimburse Bosch Sensortec for all costs in
* connection with such claims.
*
* The purchaser must monitor the market for the purchased products,
* particularly with regard to product safety and inform Bosch Sensortec
* without delay of all security relevant incidents.
*
* Engineering Samples are marked with an asterisk (*) or (e).
* Samples may vary from the valid technical specifications of the product
* series. They are therefore not intended or fit for resale to third
* parties or for use in end products. Their sole purpose is internal
* client testing. The testing of an engineering sample may in no way
* replace the testing of a product series. Bosch Sensortec assumes
* no liability for the use of engineering samples.
* By accepting the engineering samples, the Purchaser agrees to indemnify
* Bosch Sensortec from all claims arising from the use of engineering
* samples.
*
* Special:
* This software module (hereinafter called "Software") and any information
* on application-sheets (hereinafter called "Information") is provided
* free of charge for the sole purpose to support your application work.
* The Software and Information is subject to the following
* terms and conditions:
*
* The Software is specifically designed for the exclusive use for
* Bosch Sensortec products by personnel who have special experience
* and training. Do not use this Software if you do not have the
* proper experience or training.
*
* This Software package is provided `` as is `` and without any expressed
* or implied warranties,including without limitation, the implied warranties
* of merchantability and fitness for a particular purpose.
*
* Bosch Sensortec and their representatives and agents deny any liability
* for the functional impairment
* of this Software in terms of fitness, performance and safety.
* Bosch Sensortec and their representatives and agents shall not be liable
* for any direct or indirect damages or injury, except as
* otherwise stipulated in mandatory applicable law.
*
* The Information provided is believed to be accurate and reliable.
* Bosch Sensortec 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 Bosch. Specifications mentioned in the Information are
* subject to change without notice.
*/
/*!
* @file bstdr_types.h
*
* @brief
* Contains the datatypes common to the sensor APIs
*
*/
#ifndef __BSTDR_TYPES_H__
#define __BSTDR_TYPES_H__
#include <stdint.h>
#include <stdbool.h>
/*!
* @brief Enumeration for function return codes
*
*/
typedef enum
{
BSTDR_OK = 0,
BSTDR_E_GEN_ERROR = -1,
BSTDR_E_OUT_OF_RANGE = -2,
BSTDR_E_BMI160_BUSY = -3,
BSTDR_E_CON_ERROR= -4,
BSTDR_E_CHIPID_ERROR= -5,
BSTDR_E_NULL_PTR = -127
}bstdr_ret_t;
/*!
* @brief Enumeration for sensor interfaces
*
*/
typedef enum
{
BSTDR_NO_INTERFACE = 0,
BSTDR_I2C_INTERFACE = 1,
BSTDR_SPI3_INTERFACE = 3,
BSTDR_SPI4_INTERFACE = 4
}bstdr_interface_t;
#define BSTDR_BITS_MSK(bitspos,bitslen) \
(((0xff>>(8-bitslen))<<bitspos))
#define BSTDR_GET_BITSLICE(regvar, bitspos, bitslen) \
((regvar & BSTDR_BITS_MSK(bitspos,bitslen)) >> bitspos)
#define BSTDR_SET_BITSLICE(regvar, bitspos,bitslen, val)\
((regvar & ~BSTDR_BITS_MSK(bitspos,bitslen)) | ((val<<bitspos)&BSTDR_BITS_MSK(bitspos,bitslen)))
/**< Function pointers */
/**< function pointer for the burst write operation in either I2C or SPI*/
typedef bstdr_ret_t(*sensor_write)(uint8_t dev_id, uint8_t reg_addr, uint8_t *reg_data, uint32_t len);
/**< function pointer for the burst read operation in either I2C or SPI*/
typedef bstdr_ret_t(*sensor_read)(uint8_t dev_id, uint8_t reg_addr, uint8_t *reg_data, uint32_t len);
/**< delay function pointer */
typedef void (*delay_msec)(uint32_t);
#endif /* __BSTDR_TYPES_H__ */
/**
* Copyright (C) 2015 - 2016 Bosch Sensortec GmbH
*
* 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.
*
* @file bmi055_accel.c
* @date 19 Apr, 2017
* @version 1.1.0
* @brief Sensor driver for BMI055 sensor
*
*/
/***************************************************************************/
/**\name Header files
****************************************************************************/
#include "bmi055.h"
/***************************************************************************/
/**\name Local Function Prototypes
****************************************************************************/
/*!
* @brief This internal API sets the range of accelerometer sensor.
*
* @param[in] dev : Structure instance of bmi055_dev.
*
* @note : Refer user guide for detailed info.
*
* @return Result of API execution status
* @retval zero -> Success / -ve value -> Error.
*/
static int8_t bmi055_set_accel_range(const struct bmi055_dev *dev);
/*!
* @brief This internal API sets the bandwidth of accelerometer sensor.
*
* @param[in] dev : Structure instance of bmi055_dev.
*
* @note : Refer user guide for detailed info.
*
* @return Result of API execution status
* @retval zero -> Success / -ve value -> Error.
*/
static int8_t bmi055_set_accel_bandwidth(const struct bmi055_dev *dev);
/*!
* @brief This internal API is used to validate the device pointer for
* null conditions.
*
* @param[in] dev : Structure instance of bmi055_dev.
*
* @return Result of API execution status
* @retval zero -> Success / +ve value -> Warning / -ve value -> Error
*/
static int8_t bmi055_accel_null_ptr_check(const struct bmi055_dev *dev);
/*!
* @brief This internal API enables/disables all accelerometer interrupts.
*
* @param[in] set_en_bit : Enable or disable bit
* @param[in] dev : Structure instance of bmi055_dev.
*
* @note set_en_bit = 0 -> disable
* set_en_bit = 1 -> enable
*
* @return Result of API execution status
* @retval zero -> Success / +ve value -> Warning / -ve value -> Error
*/
static int8_t enable_disable_all_accel_int(uint8_t set_en_bit, const struct bmi055_dev *dev);
/*!
* @brief This internal API configures the pins to fire the
* interrupt signal when it occurs.
*
* @param[in] acc_int_config : Structure instance of bmi055_accel_int_sett.
* @param[in] dev : Structure instance of bmi055_dev.
*
* @return Result of API execution status
* @retval zero -> Success / -ve value -> Error.
*/
static int8_t set_int_pin_config(struct bmi055_accel_int_sett *acc_int_config, const struct bmi055_dev *dev);
/*!
* @brief This internal API configures the input output configuration of the
* interrupt pins
*
* @param[in] int_pin_cfg : Structure instance of bmi055_int_pin_sett.
* @param[in] acc_int_config : Structure instance of bmi055_accel_int_sett.
* @param[in] temp_data : Input data given
* @param[out]temp_out_data : Output data from the register
*
* @return Result of API execution status
* @retval zero -> Success / -ve value -> Error.
*/
static int8_t config_in_out_int(const struct bmi055_int_pin_sett *int_pin_cfg,
const struct bmi055_accel_int_sett *acc_int_config,
uint8_t temp_data, uint8_t *temp_out_data);
/*!
* @brief This internal API configures the reset latch configuration of the
* interrupt pins
*
* @param[in] int_pin_cfg : Structure instance of bmi055_int_pin_sett.
* @param[in] temp_data : Input data given
* @param[out]temp_out_data : Output data from the register
*
* @return Result of API execution status
* @retval zero -> Success / -ve value -> Error.
*/
static void config_reset_latch_int(const struct bmi055_int_pin_sett *int_pin_cfg,
uint8_t temp_data, uint8_t *temp_out_data);
/*!
* @brief This internal API sets the orientation interrupt of the sensor.This
* interrupt occurs when there is orientation change in the sensor
* with respect to gravitational field vector g.
*
* @param[in] acc_int_config : Structure instance of bmi055_accel_int_sett.
* @param[in] dev : Structure instance of bmi055_dev.
*
* @return Result of API execution status
* @retval zero -> Success / -ve value -> Error.
*
*/
static int8_t set_accel_orientation_int(struct bmi055_accel_int_sett *acc_int_config, const struct bmi055_dev *dev);
/*!
* @brief This internal API enables the orient interrupt
*
* @param[in] acc_int_config : Structure instance of bmi055_accel_int_sett.
* @param[in] dev : Structure instance of bmi055_dev.
*
* @return Result of API execution status
* @retval zero -> Success / -ve value -> Error.
*/
static int8_t enable_accel_orient_int(struct bmi055_accel_int_sett *acc_int_config, const struct bmi055_dev *dev);
/*!
* @brief This internal API maps the orient interrupt to either
* INT pin 1 or 2
*
* @param[in] acc_int_config : Structure instance of bmi055_accel_int_sett.
* @param[in] dev : Structure instance of bmi055_dev.
*
* @return Result of API execution status
* @retval zero -> Success / -ve value -> Error.
*/
static int8_t map_accel_orient_int(const struct bmi055_accel_int_sett *acc_int_config, const struct bmi055_dev *dev);
/*!
* @brief This internal API configures registers for orient interrupt
*
* @param[in] acc_int_config : Structure instance of bmi055_accel_int_sett.
* @param[in] dev : Structure instance of bmi055_dev.
*
* @return Result of API execution status
* @retval zero -> Success / -ve value -> Error.
*/
static int8_t config_orient_reg(struct bmi055_accel_int_sett *acc_int_config, const struct bmi055_dev *dev);
/*!
* @brief This internal API sets the slope interrupt of the sensor.This
* interrupt occurs when slope(absolute value of acceleration difference)
* exceeds a preset threshold.
*
* @param[in] acc_int_config : Structure instance of bmi055_accel_int_sett.
* @param[in] dev : Structure instance of bmi055_dev.
*
* @return Result of API execution status
* @retval zero -> Success / -ve value -> Error.
*/
static int8_t set_accel_slope_int(struct bmi055_accel_int_sett *acc_int_config, const struct bmi055_dev *dev);
/*!
* @brief This internal API enables the slope interrupt
*
* @param[in] acc_int_config : Structure instance of bmi055_accel_int_sett.
* @param[in] dev : Structure instance of bmi055_dev.
*
* @return Result of API execution status
* @retval zero -> Success / -ve value -> Error.
*/
static int8_t enable_accel_slope_int(struct bmi055_accel_int_sett *acc_int_config, const struct bmi055_dev *dev);
/*!
* @brief This internal API maps the slope interrupt to either
* INT pin 1 or 2
*
* @param[in] acc_int_config : Structure instance of bmi055_accel_int_sett.
* @param[in] dev : Structure instance of bmi055_dev.
*
* @return Result of API execution status
* @retval zero -> Success / -ve value -> Error.
*/
static int8_t map_accel_slope_int(const struct bmi055_accel_int_sett *acc_int_config, const struct bmi055_dev *dev);
/*!
* @brief This internal API writes the data source definition for
* slope interrupt - filtered or unfiltered.
*
* @param[in] acc_int_config : Structure instance of bmi055_accel_int_sett.
* @param[in] dev : Structure instance of bmi055_dev.
*
* @note Value = 0 for filtered data , 1 for unfiltered data
*
* @return Result of API execution status
* @retval zero -> Success / -ve value -> Error.
*/
static int8_t config_int_slope_src(const struct bmi055_accel_int_sett *acc_int_config, const struct bmi055_dev *dev);
/*!
* @brief This internal API configures registers for slope interrupt
*
* @param[in] acc_int_config : Structure instance of bmi055_accel_int_sett.
* @param[in] dev : Structure instance of bmi055_dev.
*
* @return Result of API execution status
* @retval zero -> Success / -ve value -> Error.
*/
static int8_t config_slope_reg(struct bmi055_accel_int_sett *acc_int_config, const struct bmi055_dev *dev);
/*!
* @brief This internal API sets the slow/no-motion interrupt of the sensor.
* Slow motion interrupt occurs when slope of atleast one enabled axis exceeds
* preset threshold for programmable number of samples. No motion interrupt
* occurs when when slope of all enabled axes is less than the preset threshold
* for a programmable time.
*
* @param[in] acc_int_config : Structure instance of bmi055_accel_int_sett.
* @param[in] dev : Structure instance of bmi055_dev.
*
* @return Result of API execution status
* @retval zero -> Success / -ve value -> Error.
*/
static int8_t set_accel_slow_no_motion_int(struct bmi055_accel_int_sett *acc_int_config, const struct bmi055_dev *dev);
/*!
* @brief This internal API enables the slow/no-motion interrupt
*
* @param[in] acc_int_config : Structure instance of bmi055_accel_int_sett.
* @param[in] dev : Structure instance of bmi055_dev.
*
* @return Result of API execution status
* @retval zero -> Success / -ve value -> Error.
*/
static int8_t enable_accel_slow_no_motion_int(struct bmi055_accel_int_sett *acc_int_config,
const struct bmi055_dev *dev);
/*!
* @brief This internal API maps the slow/no-motion interrupt to either
* INT pin 1 or 2
*
* @param[in] acc_int_config : Structure instance of bmi055_accel_int_sett.
* @param[in] dev : Structure instance of bmi055_dev.
*
* @return Result of API execution status
* @retval zero -> Success / -ve value -> Error.
*/
static int8_t map_accel_slow_no_motion_int(const struct bmi055_accel_int_sett *acc_int_config,
const struct bmi055_dev *dev);
/*!
* @brief This internal API writes the data source definition for
* slow/no-motion interrupt - filtered or unfiltered.
*
* @param[in] acc_int_config : Structure instance of bmi055_accel_int_sett.
* @param[in] dev : Structure instance of bmi055_dev.
*
* @note Value = 0 for filtered data , 1 for unfiltered data
*
* @return Result of API execution status
* @retval zero -> Success / -ve value -> Error.
*/
static int8_t config_int_slow_no_motion_src(const struct bmi055_accel_int_sett *acc_int_config,
const struct bmi055_dev *dev);
/*!
* @brief This internal API configures registers for slow/no-motion interrupt
*
* @param[in] acc_int_config : Structure instance of bmi055_accel_int_sett.
* @param[in] dev : Structure instance of bmi055_dev.
*
* @return Result of API execution status
* @retval zero -> Success / -ve value -> Error.
*/
static int8_t config_slow_no_motion_reg(struct bmi055_accel_int_sett *acc_int_config, const struct bmi055_dev *dev);
/*!
* @brief This internal API configures duration for slow/no-motion interrupt
*
* @param[in] acc_int_config : Structure instance of bmi055_accel_int_sett.
* @param[in] dev : Structure instance of bmi055_dev.
*
* @return Result of API execution status
* @retval zero -> Success / -ve value -> Error.
*/
static int8_t config_slow_no_motion_dur(struct bmi055_accel_int_sett *acc_int_config, const struct bmi055_dev *dev);
/*!
* @brief This internal API configures threshold for slow/no-motion interrupt
*
* @param[in] acc_int_config : Structure instance of bmi055_accel_int_sett.
* @param[in] dev : Structure instance of bmi055_dev.
*
* @return Result of API execution status
* @retval zero -> Success / -ve value -> Error.
*/
static int8_t config_slow_no_motion_thres(struct bmi055_accel_int_sett *acc_int_config, const struct bmi055_dev *dev);
/*!
* @brief This internal API sets the low-g interrupt of the sensor.This
* interrupt occurs when the absolute value of sum of all accelerations or
* acceleration of each axis are lower than the preset threshold.
*
* @param[in] acc_int_config : Structure instance of bmi055_accel_int_sett.
* @param[in] dev : Structure instance of bmi055_dev.
*
* @return Result of API execution status
* @retval zero -> Success / -ve value -> Error.
*/
static int8_t set_accel_low_g_int(struct bmi055_accel_int_sett *acc_int_config, const struct bmi055_dev *dev);
/*!
* @brief This internal API enables the low g interrupt
*
* @param[in] acc_int_config : Structure instance of bmi055_accel_int_sett.
* @param[in] dev : Structure instance of bmi055_dev.
*
* @return Result of API execution status
* @retval zero -> Success / -ve value -> Error.
*/
static int8_t enable_accel_low_g_int(struct bmi055_accel_int_sett *acc_int_config, const struct bmi055_dev *dev);
/*!
* @brief This internal API maps the low-g interrupt to either
* INT pin 1 or 2
*
* @param[in] acc_int_config : Structure instance of bmi055_accel_int_sett.
* @param[in] dev : Structure instance of bmi055_dev.
*
* @return Result of API execution status
* @retval zero -> Success / -ve value -> Error.
*/
static int8_t map_accel_low_g_int(const struct bmi055_accel_int_sett *acc_int_config, const struct bmi055_dev *dev);
/*!
* @brief This internal API writes the data source definition for
* low-g interrupt - filtered or unfiltered.
*
* @param[in] acc_int_config : Structure instance of bmi055_accel_int_sett.
* @param[in] dev : Structure instance of bmi055_dev.
*
* @note Value = 0 for filtered data , 1 for unfiltered data
*
* @return Result of API execution status
* @retval zero -> Success / -ve value -> Error.
*/
static int8_t config_int_low_g_src(const struct bmi055_accel_int_sett *acc_int_config, const struct bmi055_dev *dev);
/*!
* @brief This internal API configures registers for low-g interrupt
*
* @param[in] acc_int_config : Structure instance of bmi055_accel_int_sett.
* @param[in] dev : Structure instance of bmi055_dev.
*
* @return Result of API execution status
* @retval zero -> Success / -ve value -> Error.
*/
static int8_t config_low_g_reg(struct bmi055_accel_int_sett *acc_int_config, const struct bmi055_dev *dev);
/*!
* @brief This internal API sets the high-g interrupt of the sensor.This
* interrupt occurs when accel values exceeds a preset threshold and it is
* used for the detection of shock or other high-acceleration events.
*
* @param[in] acc_int_config : Structure instance of bmi055_accel_int_sett.
* @param[in] dev : Structure instance of bmi055_dev.
*
* @return Result of API execution status
* @retval zero -> Success / -ve value -> Error.
*/
static int8_t set_accel_high_g_int(struct bmi055_accel_int_sett *acc_int_config, const struct bmi055_dev *dev);
/*!
* @brief This internal API enables the high-g interrupt
*
* @param[in] acc_int_config : Structure instance of bmi055_accel_int_sett.
* @param[in] dev : Structure instance of bmi055_dev.
*
* @return Result of API execution status
* @retval zero -> Success / -ve value -> Error.
*/
static int8_t enable_accel_high_g_int(struct bmi055_accel_int_sett *acc_int_config, const struct bmi055_dev *dev);
/*!
* @brief This internal API maps the high-g interrupt to either
* INT pin 1 or 2
*
* @param[in] acc_int_config : Structure instance of bmi055_accel_int_sett.
* @param[in] dev : Structure instance of bmi055_dev.
*
* @return Result of API execution status
* @retval zero -> Success / -ve value -> Error.
*/
static int8_t map_accel_high_g_int(const struct bmi055_accel_int_sett *acc_int_config, const struct bmi055_dev *dev);
/*!
* @brief This internal API writes the data source definition for
* high-g interrupt - filtered or unfiltered.
*
* @param[in] acc_int_config : Structure instance of bmi055_accel_int_sett.
* @param[in] dev : Structure instance of bmi055_dev.
*
* @note Value = 0 for filtered data , 1 for unfiltered data
*
* @return Result of API execution status
* @retval zero -> Success / -ve value -> Error.
*/
static int8_t config_int_high_g_src(const struct bmi055_accel_int_sett *acc_int_config, const struct bmi055_dev *dev);
/*!
* @brief This internal API configures registers for high-g interrupt
*
* @param[in] acc_int_config : Structure instance of bmi055_accel_int_sett.
* @param[in] dev : Structure instance of bmi055_dev.
*
* @return Result of API execution status
* @retval zero -> Success / -ve value -> Error.
*/
static int8_t config_high_g_reg(struct bmi055_accel_int_sett *acc_int_config, const struct bmi055_dev *dev);
/*!
* @brief This API sets the data ready interrupt for accel.
* This interrupt occurs when new z-axis accel data comes.
*
* @param[in] acc_int_config : Structure instance of bmi055_accel_int_sett.
* @param[in] dev : Structure instance of bmi055_dev.
*
* @return Result of API execution status
* @retval zero -> Success / -ve value -> Error.
*/
static int8_t set_accel_new_data_int(struct bmi055_accel_int_sett *acc_int_config, const struct bmi055_dev *dev);
/*!
* @brief This internal API enables the data ready interrupt
*
* @param[in] dev : Structure instance of bmi055_dev.
*
* @return Result of API execution status
* @retval zero -> Success / -ve value -> Error.
*/
static int8_t enable_accel_new_data_int(const struct bmi055_accel_int_sett *acc_int_config,
const struct bmi055_dev *dev);
/*!
* @brief This internal API maps the data ready interrupt to either
* INT pin 1 or 2
*
* @param[in] acc_int_config : Structure instance of bmi055_accel_int_sett.
* @param[in] dev : Structure instance of bmi055_dev.
*
* @return Result of API execution status
* @retval zero -> Success / -ve value -> Error.
*/
static int8_t map_accel_new_data_int(const struct bmi055_accel_int_sett *acc_int_config,
const struct bmi055_dev *dev);
/*!
* @brief This internal API writes the data source definition for
* data ready interrupt - filtered or unfiltered.
*
* @note Value = 0 for filtered data , 1 for unfiltered data
*
* @param[in] acc_int_config : Structure instance of bmi055_accel_int_sett.
* @param[in] dev : Structure instance of bmi055_dev.
*
* @return Result of API execution status
* @retval zero -> Success / -ve value -> Error.
*/
static int8_t config_int_new_data_src(const struct bmi055_accel_int_sett *acc_int_config,
const struct bmi055_dev *dev);
/***************************************************************************/
/**\name User Function Definitions
****************************************************************************/
/*!
* @brief This API is the entry point for accelerometer sensor. It reads
* the chip-id and initializes accelerometer parameters with default values.
*/
int8_t bmi055_accel_init(struct bmi055_dev *dev)
{
/* Variable to define error */
int8_t rslt;
/* Variable to assign chip id */
uint8_t chip_id = 0;
/* Null-pointer check */
rslt = bmi055_accel_null_ptr_check(dev);
if (rslt == BMI055_OK) {
/* Read chip-id of the accelerometer */
rslt = bmi055_get_accel_regs(BMI055_ACC_CHIP_ID_ADDR, &chip_id, 1, dev);
if (rslt == BMI055_OK) {
/* Validate chip-id */
if (chip_id == BMI055_ACCEL_CHIP_ID) {
/* Assign chip id to the structure */
dev->accel_chip_id = chip_id;
/* Reset the accelerometer sensor */
rslt = bmi055_accel_soft_reset(dev);
/* waiting time required prior to any
configuration register access */
dev->delay_ms(5);
} else {
rslt = BMI055_E_DEV_NOT_FOUND;
}
} else {
rslt = BMI055_E_COM_FAIL;
}
/* Initializing accelerometer sensor parameters
with default values */
dev->accel_cfg.bw = BMI055_ACCEL_BW_1000_HZ;
dev->accel_cfg.power = BMI055_ACCEL_PM_NORMAL;
dev->accel_cfg.range = BMI055_ACCEL_RANGE_2G;
}
return rslt;
}
/*!
* @brief This API reads the data from the given register address
* of accelerometer sensor.
*/
int8_t bmi055_get_accel_regs(uint8_t reg_addr, uint8_t *data, uint16_t len, const struct bmi055_dev *dev)
{
/* Variable to define error */
int8_t rslt;
/* Null-pointer check */
rslt = bmi055_accel_null_ptr_check(dev);
if (rslt == BMI055_OK) {
/* Configuring reg_addr for SPI Interface */
if (dev->interface == BMI055_SPI_INTF)
reg_addr = (reg_addr | BMI055_SPI_RD_MASK);
/* Read accelerometer register */
rslt = dev->read(dev->accel_id, reg_addr, data, len);
dev->delay_ms(1);
if (rslt != 0)
rslt = BMI055_E_COM_FAIL;
}
return rslt;
}
/*!
* @brief This API writes the given data to the register address of
* accelerometer sensor.
*/
int8_t bmi055_set_accel_regs(uint8_t reg_addr, uint8_t *data, uint16_t len, const struct bmi055_dev *dev)
{
/* Variable to define error */
int8_t rslt;
uint8_t burst_cnt;
/* Null-pointer check */
rslt = bmi055_accel_null_ptr_check(dev);
if (rslt == BMI055_OK) {
/* Configuring reg_addr for SPI Interface */
if (dev->interface == BMI055_SPI_INTF)
reg_addr = (reg_addr & BMI055_SPI_WR_MASK);
/* Burst write */
for (burst_cnt = 0; burst_cnt < len; burst_cnt++) {
/* Write to an accelerometer register */
rslt = dev->write(dev->accel_id, reg_addr, &data[burst_cnt], len);
reg_addr++;
dev->delay_ms(1);
}
if (rslt != 0)
rslt = BMI055_E_COM_FAIL;
}
return rslt;
}
/*!
* @brief This API resets and restarts the accelerometer sensor. All register
* values are overwritten with default parameters.
*/
int8_t bmi055_accel_soft_reset(const struct bmi055_dev *dev)
{
/* Variable to define error */
int8_t rslt;
/* Variable to define soft reset value */
uint8_t data = BMI055_SOFT_RESET_VAL;
/* Null-pointer check */
rslt = bmi055_accel_null_ptr_check(dev);
if (rslt == BMI055_OK) {
/* Reset accelerometer device */
rslt = bmi055_set_accel_regs(BMI055_ACC_SOFTRESET_ADDR, &data, 1, dev);
}
return rslt;
}
/*!
* @brief This API sets the power mode of the accelerometer sensor.
*/
int8_t bmi055_set_accel_power_mode(const struct bmi055_dev *dev)
{
/* Variable to define error */
int8_t rslt;
/* Variable to define register address of power */
uint8_t reg_addr = BMI055_ACC_PMU_LPW_ADDR;
/* Variable defined to store data in the register*/
uint8_t reg_data = 0;
/* Variable to define power */
uint8_t power = 0;
/* Null-pointer check */
rslt = bmi055_accel_null_ptr_check(dev);
if (rslt == BMI055_OK) {
/* Power range check */
if ((dev->accel_cfg.power < BMI055_ACC_POWER_MAX)
&& (dev->accel_cfg.power != BMI055_ACCEL_INVALID_POWER)) {
/* Get power mode from the register */
rslt = bmi055_get_accel_regs(reg_addr, &power, 1, dev);
if (rslt == BMI055_OK) {
/* Write the corresponding power mode in the
register variable */
reg_data = BMI055_SET_BITS(power, BMI055_ACC_POWER, dev->accel_cfg.power);
/* Set the configured power to the address */
rslt = bmi055_set_accel_regs(reg_addr, &reg_data, 1, dev);
} else {
/* Communication fail */
rslt = BMI055_E_COM_FAIL;
}
} else {
/* Not within range */
rslt = BMI055_E_OUT_OF_RANGE;
}
}
return rslt;
}
/*!
* @brief This API sets the bandwidth and range for bmi055 accelerometer
*/
int8_t bmi055_set_accel_sensor_config(uint8_t bmi055_config, const struct bmi055_dev *dev)
{
/* Variable to define error */
int8_t rslt;
/* Check for null pointer in the device structure*/
rslt = bmi055_accel_null_ptr_check(dev);
if (rslt == BMI055_OK) {
/* Check whether configuration is valid) */
if (bmi055_config & (BANDWIDTH_CONFIG | RANGE_CONFIG)) {
/* Set accelerometer bandwidth */
if (bmi055_config & BANDWIDTH_CONFIG)
rslt = bmi055_set_accel_bandwidth(dev);
/* Set accelerometer range */
if (bmi055_config & RANGE_CONFIG)
rslt = bmi055_set_accel_range(dev);
} else {
/* Configuration setting failed */
rslt = BMI055_E_CONFIG_FAIL;
}
}
return rslt;
}
/*!
* @brief This API reads the accelerometer data from the sensor, and stores it
* in the bmi055_sensor_data structure instance passed by the user.
*/
int8_t bmi055_get_accel_data(struct bmi055_sensor_data *accel, const struct bmi055_dev *dev)
{
/* Variable to define error */
int8_t rslt;
/* Variable to define index for array */
uint8_t index = 0;
/* Array to store accelerometer data */
uint8_t data_array[6] = {0};
/* Variable to store LSB */
uint16_t lsb = 0;
/* Variable to store MSB */
uint16_t msb = 0;
/* Variable to store MSB-LSB value*/
uint16_t msblsb = 0;
/* Null-pointer check */
rslt = bmi055_accel_null_ptr_check(dev);
if (rslt == BMI055_OK) {
/* Read accelerometer sensor data */
rslt = bmi055_get_accel_regs(BMI055_ACC_X_L_ADDR, data_array, 6, dev);
if (rslt == BMI055_OK) {
/* Parse X-axis accelerometer data */
lsb = (uint16_t)data_array[index++];
msb = ((uint16_t)data_array[index++]) << 8;
msblsb = msb | lsb;
/* Right shift by 4 since resolution is 12 bit */
accel->x = (int16_t)(msblsb) / (int16_t)(0x10);
/*Parse Y-axis accelerometer data */
lsb = (uint16_t)data_array[index++];
msb = ((uint16_t)data_array[index++]) << 8;
msblsb = msb | lsb;
/* Right shift by 4 since resolution is 12 bit */
accel->y = (int16_t)(msblsb) / (int16_t)(0x10);
/* Parse Z-axis accelerometer data */
lsb = (uint16_t)data_array[index++];
msb = ((uint16_t)data_array[index++]) << 8;
msblsb = msb | lsb;
/* Right shift by 4 since resolution is 12 bit */
accel->z = (int16_t)(msblsb) / (int16_t)(0x10);
} else {
/* Communication fail */
rslt = BMI055_E_COM_FAIL;
}
}
return rslt;
}
/* TODO Code Cleanup */
/*!
* @brief This API configures the necessary accelerometer interrupt based on
* the user settings in the bmi055_accel_int_sett structure instance.
*/
int8_t bmi055_set_accel_int_config(struct bmi055_accel_int_sett *acc_int_config, const struct bmi055_dev *dev)
{
/* Variable to define error */
int8_t rslt;
/* Null pointer error check */
rslt = bmi055_accel_null_ptr_check(dev);
if ((rslt == BMI055_OK) && (acc_int_config != NULL)) {
switch (acc_int_config->acc_int_types) {
case BMI055_ACC_SLOPE_INT:
/*Any motion or slope interrupt*/
rslt = set_accel_slope_int(acc_int_config, dev);
break;
#if CODE_UNDER_MODIFICATION
case BMI055_ACC_DOUBLE_TAP_INT:
case BMI055_ACC_SINGLE_TAP_INT:
/* Double tap and single tap Interrupt */
rslt = set_accel_tap_int(acc_int_config, dev);
break;
case BMI055_ACC_FLAT_INT:
/* Flat detection interrupt */
rslt = set_accel_flat_detect_int(acc_int_config, dev);
break;
#endif
case BMI055_ACC_ORIENT_INT:
/* Orientation interrupt */
rslt = set_accel_orientation_int(acc_int_config, dev);
break;
case BMI055_ACC_SLOW_NO_MOTION_INT:
/* Slow or no motion interrupt */
rslt = set_accel_slow_no_motion_int(acc_int_config, dev);
break;
case BMI055_ACC_NEW_DATA_INT:
/* New data interrupt */
rslt = set_accel_new_data_int(acc_int_config, dev);
break;
case BMI055_ACC_LOW_G_INT:
/* Low-g interrupt */
rslt = set_accel_low_g_int(acc_int_config, dev);
break;
case BMI055_ACC_HIGH_G_INT:
/* High-g interrupt */
rslt = set_accel_high_g_int(acc_int_config, dev);
break;
default:
break;
}
} else {
rslt = BMI055_E_NULL_PTR;
}
return rslt;
}
/*! This API retrieves the status of accelerometer interrupts
* when set
*/
int8_t bmi055_get_accel_int_status(uint32_t *intr_status, const struct bmi055_dev *dev)
{
/* Variable to define error */
int8_t rslt;
/* Variable to declare status register address */
uint8_t status_reg_addr = BMI055_ACC_INT_STATUS_0_ADDR;
/* Array to store the status of the interrupts */
uint8_t status_array[4] = {0};
/* Variable for loop */
uint8_t i = 0;
/* Null pointer error check */
rslt = bmi055_accel_null_ptr_check(dev);
if ((rslt == BMI055_OK) && (intr_status != NULL)) {
/* Get the interrupt status from the register*/
rslt = bmi055_get_accel_regs(status_reg_addr, status_array, 4, dev);
if (rslt == BMI055_OK) {
while (i < 4) {
*((uint8_t *)intr_status + i) = status_array[i];
i++;
}
}
} else {
rslt = BMI055_E_NULL_PTR;
}
return rslt;
}
/*!
* @brief This API enables/disables individual or all accelerometer interrupts.
*/
int8_t bmi055_set_reset_accel_int(struct bmi055_accel_int_sett *acc_int_config, const struct bmi055_dev *dev,
uint8_t set_en_bit)
{
/* Variable to define error */
int8_t rslt;
/* Variable to define accelerometer interrupt */
uint8_t accel_int = acc_int_config->acc_int_types;
/* Null pointer error check */
rslt = bmi055_accel_null_ptr_check(dev);
if ((rslt == BMI055_OK) && (acc_int_config != NULL)) {
switch (accel_int) {
case BMI055_ACC_NEW_DATA_INT:
/* Flag to enable/disable new-data interrupt */
acc_int_config->acc_int_type_cfg.accel_new_data_en = set_en_bit;
/* Set the interrupt configuration */
rslt = bmi055_set_accel_int_config(acc_int_config, dev);
break;
case BMI055_ACC_LOW_G_INT:
/* Flag to enable/disable low-g interrupt */
acc_int_config->acc_int_type_cfg.acc_low_g_int.low_g_en = set_en_bit;
/* Set the interrupt configuration */
rslt = bmi055_set_accel_int_config(acc_int_config, dev);
break;
case BMI055_ACC_HIGH_G_INT:
/* Flag to enable/disable x, y and z axis for
high-g interrupt */
acc_int_config->acc_int_type_cfg.acc_high_g_int.high_g_en_x = set_en_bit;
acc_int_config->acc_int_type_cfg.acc_high_g_int.high_g_en_y = set_en_bit;
acc_int_config->acc_int_type_cfg.acc_high_g_int.high_g_en_z = set_en_bit;
/* Set the interrupt configuration */
rslt = bmi055_set_accel_int_config(acc_int_config, dev);
break;
case BMI055_ACC_SLOW_NO_MOTION_INT:
/* Flag to enable/disable x, y and z axis for
slow/no-motion interrupt */
acc_int_config->acc_int_type_cfg.acc_slow_no_mot_int.slow_no_mot_en_x = set_en_bit;
acc_int_config->acc_int_type_cfg.acc_slow_no_mot_int.slow_no_mot_en_y = set_en_bit;
acc_int_config->acc_int_type_cfg.acc_slow_no_mot_int.slow_no_mot_en_z = set_en_bit;
/* Set the interrupt configuration */
rslt = bmi055_set_accel_int_config(acc_int_config, dev);
break;
case BMI055_ACC_SLOPE_INT:
/* Flag to enable/disable x, y and z axis for
slope interrupt */
acc_int_config->acc_int_type_cfg.acc_slope_int.slope_en_x = set_en_bit;
acc_int_config->acc_int_type_cfg.acc_slope_int.slope_en_y = set_en_bit;
acc_int_config->acc_int_type_cfg.acc_slope_int.slope_en_z = set_en_bit;
/* Set the interrupt configuration */
rslt = bmi055_set_accel_int_config(acc_int_config, dev);
break;
case BMI055_ACC_ORIENT_INT:
/* Flag to enable/disable orient interrupt */
acc_int_config->acc_int_type_cfg.acc_orient_int.orient_en = set_en_bit;
/* Set the interrupt configuration */
rslt = bmi055_set_accel_int_config(acc_int_config, dev);
break;
case BMI055_ALL_ACCEL_INT:
rslt = enable_disable_all_accel_int(set_en_bit, dev);
break;
default:
break;
}
} else {
rslt = BMI055_E_NULL_PTR;
}
return rslt;
}
/*!
* @brief This API clears all the latched interrupts of the accelerometer.
*/
int8_t bmi055_reset_accel_latch_int(struct bmi055_accel_int_sett *acc_int_config, const struct bmi055_dev *dev)
{
/* Variable to define error */
int8_t rslt;
/* Variable to define register address */
uint8_t reg_addr = BMI055_ACC_INT_LATCH_ADDR;
/* Variable defined to store register data temporarily */
uint8_t temp_reg_data;
/* Variable defined to store data temporarily */
uint8_t temp_data = 0;
/* Null pointer error check */
rslt = bmi055_accel_null_ptr_check(dev);
if ((rslt == BMI055_OK) && (acc_int_config != NULL)) {
/* Update the local structure with the pin configuration
structure */
struct bmi055_int_pin_sett *int_pin_cfg = &(acc_int_config->int_pin_sett);
/* Get the reset latch status */
rslt = bmi055_get_accel_regs(reg_addr, &temp_data, 1, dev);
if (rslt == BMI055_OK) {
/* Configuring interrupt reset - '1' clears all latched
interrupts and '0' keeps latched interrupt active */
temp_reg_data = BMI055_SET_BIT_POS0(temp_data, BMI055_ACC_RESET_INT,
int_pin_cfg->reset_int);
/* Write reset status to INT_RST_LATCH address */
rslt = bmi055_set_accel_regs(reg_addr, &temp_reg_data, 1, dev);
}
} else {
rslt = BMI055_E_NULL_PTR;
}
return rslt;
}
/***************************************************************************/
/**\name Local Function Definitions
****************************************************************************/
/*!
* @brief This internal API sets the bandwidth of accelerometer sensor.
*/
static int8_t bmi055_set_accel_bandwidth(const struct bmi055_dev *dev)
{
/* Variable to define error */
int8_t rslt;
/* Variable to define register address of bandwidth */
uint8_t reg_addr = BMI055_ACC_BW_ADDR;
/* Variable defined to store data in the register*/
uint8_t reg_data = 0;
/* Variable to define bandwidth */
uint8_t bw = 0;
/* Null-pointer check */
rslt = bmi055_accel_null_ptr_check(dev);
if (rslt == BMI055_OK) {
/* Bandwidth range check */
if ((dev->accel_cfg.bw >= BMI055_ACCEL_BW_7_81_HZ) && (dev->accel_cfg.bw <= BMI055_ACCEL_BW_1000_HZ)) {
/* Get accelerometer bandwidth from the register*/
rslt = bmi055_get_accel_regs(reg_addr, &bw, 1, dev);
if (rslt == BMI055_OK) {
/* Write the corresponding Bandwidth mode in the
register variable */
reg_data = BMI055_SET_BIT_POS0(bw, BMI055_ACC_BW, dev->accel_cfg.bw);
/* Set the configured accelerometer bandwidth */
rslt = bmi055_set_accel_regs(reg_addr, &reg_data, 1, dev);
} else {
/* Communication fail */
rslt = BMI055_E_COM_FAIL;
}
} else {
/* Not within range */
rslt = BMI055_E_OUT_OF_RANGE;
}
}
return rslt;
}
/*!
* @brief This internal API sets the range of accelerometer sensor.
*/
static int8_t bmi055_set_accel_range(const struct bmi055_dev *dev)
{
/* Variable to define error */
int8_t rslt;
/* Variable to define register address of range */
uint8_t reg_addr = BMI055_ACC_RANGE_ADDR;
/* Variable defined to store data in the register*/
uint8_t reg_data = 0;
/* Variable to define range */
uint8_t range = 0;
/* Null-pointer check */
rslt = bmi055_accel_null_ptr_check(dev);
if (rslt == BMI055_OK) {
/* Range check */
if ((dev->accel_cfg.range == BMI055_ACCEL_RANGE_2G) ||
(dev->accel_cfg.range == BMI055_ACCEL_RANGE_4G) ||
(dev->accel_cfg.range == BMI055_ACCEL_RANGE_8G) ||
(dev->accel_cfg.range == BMI055_ACCEL_RANGE_16G)) {
/* Get accelerometer range from the register*/
rslt = bmi055_get_accel_regs(reg_addr, &range, 1, dev);
if (rslt == BMI055_OK) {
/* Write the corresponding range in the register
variable */
reg_data = BMI055_SET_BIT_POS0(range, BMI055_ACC_RANGE, dev->accel_cfg.range);
/* Set the configured range */
rslt = bmi055_set_accel_regs(reg_addr, &reg_data, 1, dev);
} else {
/* Communication fail */
rslt = BMI055_E_COM_FAIL;
}
} else {
/* Not within range */
rslt = BMI055_E_OUT_OF_RANGE;
}
}
return rslt;
}
/*!
* @brief This internal API sets the new data interrupt for accelerometer.
* This interrupt occurs when new z-axis accelerometer data is stored
* in the register.
*/
static int8_t set_accel_new_data_int(struct bmi055_accel_int_sett *acc_int_config, const struct bmi055_dev *dev)
{
/* Variable to define error */
int8_t rslt;
/* Enable new data interrupt */
rslt = enable_accel_new_data_int(acc_int_config, dev);
if (rslt == BMI055_OK) {
/* Map new data interrupt to either INT 1 or 2 */
rslt = map_accel_new_data_int(acc_int_config, dev);
if (rslt == BMI055_OK) {
/* Write data source definition for new data
interrupt */
rslt = config_int_new_data_src(acc_int_config, dev);
if (rslt == BMI055_OK) {
/* Configuring interrupt pins */
rslt = set_int_pin_config(acc_int_config, dev);
}
}
}
return rslt;
}
/*!
* @brief This internal API enables the new data interrupt
*/
static int8_t enable_accel_new_data_int(const struct bmi055_accel_int_sett *acc_int_config,
const struct bmi055_dev *dev)
{
/* Variable to define error */
int8_t rslt;
/* Variable to define address of Interrupt enable 1 register*/
uint8_t reg_addr = BMI055_ACC_INT_EN_1_ADDR;
/* Variable defined to retrieve data */
uint8_t data = 0;
/* Variable defined to set data in register */
uint8_t reg_data;
/* Get interrupt enable status from the register */
rslt = bmi055_get_accel_regs(reg_addr, &data, 1, dev);
if (rslt == BMI055_OK) {
/* Write interrupt enable bits in the variable */
reg_data = BMI055_SET_BITS(data, BMI055_ACC_NEW_DATA_INT_EN_1,
acc_int_config->acc_int_type_cfg.accel_new_data_en);
/* Enable new data interrupt in Int Enable 1 register */
rslt = bmi055_set_accel_regs(reg_addr, &reg_data, 1, dev);
}
return rslt;
}
/*!
* @brief This internal API maps the new data interrupt to either
* INT pin 1 or 2
*/
static int8_t map_accel_new_data_int(const struct bmi055_accel_int_sett *acc_int_config, const struct bmi055_dev *dev)
{
/* Variable to define error */
int8_t rslt;
/* Variable to define register address of Map1 register */
uint8_t reg_addr = BMI055_ACC_INT_MAP_1_ADDR;
/* Variable defined to retrieve data */
uint8_t data = 0;
/* Variable defined to set data in register */
uint8_t reg_data;
/* Get interrupt map status from the register */
rslt = bmi055_get_accel_regs(reg_addr, &data, 1, dev);
if (rslt == BMI055_OK) {
if (acc_int_config->acc_int_channel == BMI055_INT_CHANNEL_1) {
/* Map new data interrupt to INT1 pin */
reg_data = BMI055_SET_BIT_POS0(data, BMI055_ACC_INT1_MAP_1_NEW_DATA, BMI055_ENABLE);
} else if (acc_int_config->acc_int_channel == BMI055_INT_CHANNEL_2) {
/* Map new data interrupt to INT2 pin */
reg_data = BMI055_SET_BITS(data, BMI055_ACC_INT2_MAP_1_NEW_DATA, BMI055_ENABLE);
} else {
rslt = BMI055_E_INVALID_CHANNEL;
}
if (rslt == BMI055_OK) {
/* Configure the Interrupt map register to map new data
interrupt to either INT1 or INT2 pin*/
rslt = bmi055_set_accel_regs(reg_addr, &reg_data, 1, dev);
}
}
return rslt;
}
/*!
* @brief This internal API writes the data source definition for
* new data interrupt - filtered or unfiltered.
*
* @note Value = 0(BMI055_FALSE) for filtered data , 1(BMI055_TRUE)
* for unfiltered data
*/
static int8_t config_int_new_data_src(const struct bmi055_accel_int_sett *acc_int_config, const struct bmi055_dev *dev)
{
/* Variable to define error */
int8_t rslt;
/* Variable to define register address of Interrupt source */
uint8_t reg_addr = BMI055_ACC_INT_SRC_ADDR;
/* Variable defined to retrieve data */
uint8_t data = 0;
/* Variable defined to set data in register */
uint8_t reg_data;
/* Get interrupt source data from the register */
rslt = bmi055_get_accel_regs(reg_addr, &data, 1, dev);
if (rslt == BMI055_OK) {
/* Write the interrupt source data in a variable*/
reg_data = BMI055_SET_BITS(data, BMI055_ACC_SRC_NEW_DATA, acc_int_config->int_data_src_type);
/* Write data source definition for new data interrupt */
rslt = bmi055_set_accel_regs(reg_addr, &reg_data, 1, dev);
}
return rslt;
}
/*!
* @brief This internal API sets the low-g interrupt of the sensor.This
* interrupt occurs when the absolute value of sum of all accelerations or
* acceleration of each axis are lower than the preset threshold.
*/
static int8_t set_accel_low_g_int(struct bmi055_accel_int_sett *acc_int_config, const struct bmi055_dev *dev)
{
/* Variable to define error */
int8_t rslt;
/* Enable low-g interrupt */
rslt = enable_accel_low_g_int(acc_int_config, dev);
if (rslt == BMI055_OK) {
/* Map low-g interrupt to either INT 1 or 2 */
rslt = map_accel_low_g_int(acc_int_config, dev);
if (rslt == BMI055_OK) {
/* Write data source definition for low-g
interrupt */
rslt = config_int_low_g_src(acc_int_config, dev);
if (rslt == BMI055_OK) {
/* Configuring interrupt pins */
rslt = set_int_pin_config(acc_int_config, dev);
if (rslt == BMI055_OK) {
/* Configure Low-g registers */
rslt = config_low_g_reg(acc_int_config, dev);
}
}
}
}
return rslt;
}
/*!
* @brief This internal API enables the low-g interrupt
*/
static int8_t enable_accel_low_g_int(struct bmi055_accel_int_sett *acc_int_config, const struct bmi055_dev *dev)
{
/* Variable to define error */
int8_t rslt;
/* Variable to define address of Interrupt enable 1 register*/
uint8_t reg_addr = BMI055_ACC_INT_EN_1_ADDR;
/* Variable defined to retrieve data */
uint8_t data = 0;
/* Variable defined to set data in register */
uint8_t reg_data;
/* Updating the interrupt structure to local structure */
struct bmi055_acc_low_g_int_cfg *low_g_int_cfg = &(acc_int_config->acc_int_type_cfg.acc_low_g_int);
/* Get interrupt enable status from the register */
rslt = bmi055_get_accel_regs(reg_addr, &data, 1, dev);
if (rslt == BMI055_OK) {
/* Write interrupt enable bits in the variable */
reg_data = BMI055_SET_BITS(data, BMI055_ACC_LOW_G_INT_EN_1, low_g_int_cfg->low_g_en);
/* Enable low-g interrupt in Interrupt Enable 1 register */
rslt = bmi055_set_accel_regs(reg_addr, &reg_data, 1, dev);
}
return rslt;
}
/*!
* @brief This internal API maps the low-g interrupt to either
* INT pin 1 or 2
*/
static int8_t map_accel_low_g_int(const struct bmi055_accel_int_sett *acc_int_config, const struct bmi055_dev *dev)
{
/* Variable to define error */
int8_t rslt;
/* Variable to define register address */
uint8_t reg_addr = 0;
/* Variable defined to retrieve data */
uint8_t data = 0;
/* Variable defined to set data in register */
uint8_t reg_data = 0;
if (acc_int_config->acc_int_channel == BMI055_INT_CHANNEL_1) {
/* Define Interrupt map 0 register */
reg_addr = BMI055_ACC_INT_MAP_0_ADDR;
/* Get interrupt map status from the register */
rslt = bmi055_get_accel_regs(reg_addr, &data, 1, dev);
if (rslt == BMI055_OK) {
/* Map low-g interrupt to INT1 pin */
reg_data = BMI055_SET_BIT_POS0(data, BMI055_ACC_INT1_MAP_0_LOW_G, BMI055_ENABLE);
}
} else if (acc_int_config->acc_int_channel == BMI055_INT_CHANNEL_2) {
/* Define Interrupt map 2 register */
reg_addr = BMI055_ACC_INT_MAP_2_ADDR;
/* Get interrupt map status from the register */
rslt = bmi055_get_accel_regs(reg_addr, &data, 1, dev);
if (rslt == BMI055_OK) {
/* Map low-g interrupt to INT2 pin */
reg_data = BMI055_SET_BIT_POS0(data, BMI055_ACC_INT2_MAP_2_LOW_G, BMI055_ENABLE);
}
} else {
rslt = BMI055_E_INVALID_CHANNEL;
}
if (rslt == BMI055_OK) {
/* Configure the Interrupt map register to map low-g
interrupt to either INT1 or INT2 pin*/
rslt = bmi055_set_accel_regs(reg_addr, &reg_data, 1, dev);
}
return rslt;
}
/*!
* @brief This internal API writes the data source definition for
* low-g interrupt - filtered or unfiltered.
*
* @note Value = 0(BMI055_FALSE) for filtered data , 1(BMI055_TRUE)
* for unfiltered data
*/
static int8_t config_int_low_g_src(const struct bmi055_accel_int_sett *acc_int_config, const struct bmi055_dev *dev)
{
/* Variable to define error */
int8_t rslt;
/* Variable to define register address of Interrupt source */
uint8_t reg_addr = BMI055_ACC_INT_SRC_ADDR;
/* Variable defined to retrieve data */
uint8_t data = 0;
/* Variable defined to set data in register */
uint8_t reg_data;
/* Get interrupt source data from the register */
rslt = bmi055_get_accel_regs(reg_addr, &data, 1, dev);
if (rslt == BMI055_OK) {
/* Write the interrupt source data in a variable */
reg_data = BMI055_SET_BIT_POS0(data, BMI055_ACC_SRC_LOW_G, acc_int_config->int_data_src_type);
/* Write data source definition for low-g interrupt */
rslt = bmi055_set_accel_regs(reg_addr, &reg_data, 1, dev);
}
return rslt;
}
/*!
* @brief This internal API configures registers for low-g interrupt
*/
static int8_t config_low_g_reg(struct bmi055_accel_int_sett *acc_int_config, const struct bmi055_dev *dev)
{
/* Variable to define error */
int8_t rslt;
/* Variable to define register address */
uint8_t reg_addr;
/* Variable defined to set data in register */
uint8_t reg_data = 0;
/* Variable defined to retrieve data */
uint8_t data = 0;
/* Array defined to store data */
uint8_t data_array[3] = {0};
/* Updating the interrupt structure to local structure */
struct bmi055_acc_low_g_int_cfg *low_g_int_cfg = &(acc_int_config->acc_int_type_cfg.acc_low_g_int);
/* Configuring Low-g registers */
/* Store the low duration in the array */
data_array[0] = low_g_int_cfg->low_dur;
/* Store the low threshold in the array */
data_array[1] = low_g_int_cfg->low_thres;
reg_addr = BMI055_ACC_INT_LH_2_ADDR;
/*Get the low-g interrupt mode and hysteresis setting */
rslt = bmi055_get_accel_regs(reg_addr, &data, 1, dev);
if (rslt == BMI055_OK) {
/* Get low hysteresis value */
reg_data = BMI055_SET_BIT_POS0(data, BMI055_ACC_LOW_HYST, low_g_int_cfg->low_hyst);
/* Get Low mode */
reg_data = BMI055_SET_BITS(reg_data, BMI055_ACC_LOW_MODE, low_g_int_cfg->low_mode);
/* Store low hysteresis and low mode in the array */
data_array[2] = reg_data;
reg_addr = BMI055_ACC_INT_LH_0_ADDR;
/* Write the data simultaneously since addresses are located in
consecutive positions.*/
rslt = bmi055_set_accel_regs(reg_addr, data_array, 3, dev);
dev->delay_ms(1);
}
return rslt;
}
/*!
* @brief This internal API sets the high-g interrupt of the sensor.This
* interrupt occurs when either of the accel values exceeds a preset threshold.
* It is used for the detection of shock or other high-acceleration events.
*/
static int8_t set_accel_high_g_int(struct bmi055_accel_int_sett *acc_int_config, const struct bmi055_dev *dev)
{
/* Variable to define error */
int8_t rslt;
/* Enable high-g interrupt */
rslt = enable_accel_high_g_int(acc_int_config, dev);
if (rslt == BMI055_OK) {
/* Map high-g interrupt to either INT 1 or 2 */
rslt = map_accel_high_g_int(acc_int_config, dev);
if (rslt == BMI055_OK) {
/* Write data source definition for high-g
interrupt */
rslt = config_int_high_g_src(acc_int_config, dev);
if (rslt == BMI055_OK) {
/* Configuring interrupt pins */
rslt = set_int_pin_config(acc_int_config, dev);
if (rslt == BMI055_OK) {
/* Configure high-g registers */
rslt = config_high_g_reg(acc_int_config, dev);
}
}
}
}
return rslt;
}
/*!
* @brief This internal API enables the high-g interrupt
*/
static int8_t enable_accel_high_g_int(struct bmi055_accel_int_sett *acc_int_config, const struct bmi055_dev *dev)
{
/* Variable to define error */
int8_t rslt;
/* Variable to define register address of enable 1 register*/
uint8_t reg_addr = BMI055_ACC_INT_EN_1_ADDR;
/* Variable defined to retrieve data */
uint8_t data = 0;
/* Variable defined to set data in register */
uint8_t reg_data;
struct bmi055_acc_high_g_int_cfg *high_g_int_cfg = &(acc_int_config->acc_int_type_cfg.acc_high_g_int);
/* Get interrupt enable status from the register */
rslt = bmi055_get_accel_regs(reg_addr, &data, 1, dev);
if (rslt == BMI055_OK) {
/* Enabling High-g x axis */
reg_data = BMI055_SET_BIT_POS0(data, BMI055_ACC_HIGH_G_X_INT_EN_1, high_g_int_cfg->high_g_en_x);
/* Enabling High-g y axis */
reg_data = BMI055_SET_BITS(reg_data, BMI055_ACC_HIGH_G_Y_INT_EN_1, high_g_int_cfg->high_g_en_y);
/* Enabling High-g z axis */
reg_data = BMI055_SET_BITS(reg_data, BMI055_ACC_HIGH_G_Z_INT_EN_1, high_g_int_cfg->high_g_en_z);
/* Enable high-g interrupt in Int Enable 1 register */
rslt = bmi055_set_accel_regs(reg_addr, &reg_data, 1, dev);
}
return rslt;
}
/*!
* @brief This internal API maps the high-g interrupt to either
* INT pin 1 or 2
*/
static int8_t map_accel_high_g_int(const struct bmi055_accel_int_sett *acc_int_config, const struct bmi055_dev *dev)
{
/* Variable to define error */
int8_t rslt;
/* Variable to define register address */
uint8_t reg_addr = 0;
/* Variable defined to retrieve data */
uint8_t data = 0;
/* Variable defined to set data in register */
uint8_t reg_data;
if (acc_int_config->acc_int_channel == BMI055_INT_CHANNEL_1) {
/* Define Interrupt map 0 register */
reg_addr = BMI055_ACC_INT_MAP_0_ADDR;
/* Get interrupt map status from the register */
rslt = bmi055_get_accel_regs(reg_addr, &data, 1, dev);
if (rslt == BMI055_OK) {
/* Map high-g interrupt to INT1 pin */
reg_data = BMI055_SET_BITS(data, BMI055_ACC_INT1_MAP_0_HIGH_G, BMI055_ENABLE);
}
} else if (acc_int_config->acc_int_channel == BMI055_INT_CHANNEL_2) {
/* Define Interrupt map 2 register */
reg_addr = BMI055_ACC_INT_MAP_2_ADDR;
/* Get interrupt map status from the register */
rslt = bmi055_get_accel_regs(reg_addr, &data, 1, dev);
if (rslt == BMI055_OK) {
/* Map high-g interrupt to INT2 pin */
reg_data = BMI055_SET_BITS(data, BMI055_ACC_INT2_MAP_2_HIGH_G, BMI055_ENABLE);
}
} else {
rslt = BMI055_E_INVALID_CHANNEL;
}
if (rslt == BMI055_OK) {
/* Configure the Interrupt map register to map high-g interrupt
to either INT1 or INT2 pin*/
rslt = bmi055_set_accel_regs(reg_addr, &reg_data, 1, dev);
}
return rslt;
}
/*!
* @brief This internal API writes the data source definition for
* high-g interrupt - filtered or unfiltered.
*
* @note Value = 0(BMI055_FALSE) for filtered data , 1(BMI055_TRUE)
* for unfiltered data
*/
static int8_t config_int_high_g_src(const struct bmi055_accel_int_sett *acc_int_config, const struct bmi055_dev *dev)
{
/* Variable to define error */
int8_t rslt;
/* Variable to define register address of Interrupt source */
uint8_t reg_addr = BMI055_ACC_INT_SRC_ADDR;
/* Variable defined to retrieve data */
uint8_t data = 0;
/* Variable defined to set data in register */
uint8_t reg_data;
/* Get interrupt source data from the register */
rslt = bmi055_get_accel_regs(reg_addr, &data, 1, dev);
if (rslt == BMI055_OK) {
/* Write the interrupt source data in a variable*/
reg_data = BMI055_SET_BITS(data, BMI055_ACC_SRC_HIGH_G, acc_int_config->int_data_src_type);
/* Write data source definition for high-g interrupt */
rslt = bmi055_set_accel_regs(reg_addr, &reg_data, 1, dev);
}
return rslt;
}
/*!
* @brief This internal API configures registers for high-g interrupt.
*/
static int8_t config_high_g_reg(struct bmi055_accel_int_sett *acc_int_config, const struct bmi055_dev *dev)
{
/* Variable to define error */
int8_t rslt;
/* Variable to define register address */
uint8_t reg_addr = BMI055_ACC_INT_LH_2_ADDR;
/* Variable defined to set data in register */
uint8_t reg_data = 0;
/* Variable defined to retrieve data */
uint8_t data = 0;
/* Array defined to store data */
uint8_t data_array[3] = {0};
/* Updating the interrupt structure to local structure */
struct bmi055_acc_high_g_int_cfg *high_g_int_cfg = &(acc_int_config->acc_int_type_cfg.acc_high_g_int);
/*Get the high-g interrupt hysteresis setting */
rslt = bmi055_get_accel_regs(reg_addr, &data, 1, dev);
if (rslt == BMI055_OK) {
/* Set default high hysteresis value */
reg_data = BMI055_SET_BITS(data, BMI055_ACC_HIGH_HYST, high_g_int_cfg->high_hy);
/* Store high hysteresis value in the array */
data_array[0] = reg_data;
/* Store the high duration in the array */
data_array[1] = high_g_int_cfg->high_dur;
/* Store the low threshold in the array */
data_array[2] = high_g_int_cfg->high_thres;
/* Write the data simultaneously since addresses are located in
consecutive positions.*/
rslt = bmi055_set_accel_regs(reg_addr, data_array, 3, dev);
dev->delay_ms(1);
}
return rslt;
}
/*!
* @brief This internal API sets the slow/no-motion interrupt of the sensor.
* Slow motion interrupt occurs when slope of atleast one enabled axis exceeds
* preset threshold for programmable number of samples. No motion interrupt
* occurs when when slope of all enabled axes is less than the preset threshold
* for a programmable time.
*/
static int8_t set_accel_slow_no_motion_int(struct bmi055_accel_int_sett *acc_int_config, const struct bmi055_dev *dev)
{
/* Variable to define error */
int8_t rslt;
/* Enable slow/no-motion interrupt */
rslt = enable_accel_slow_no_motion_int(acc_int_config, dev);
if (rslt == BMI055_OK) {
/* Map slow/no-motion interrupt to either INT 1 or 2 */
rslt = map_accel_slow_no_motion_int(acc_int_config, dev);
if (rslt == BMI055_OK) {
/* Write data source definition for slow/no-motion
interrupt */
rslt = config_int_slow_no_motion_src(acc_int_config, dev);
if (rslt == BMI055_OK) {
/* Configuring interrupt pins */
rslt = set_int_pin_config(acc_int_config, dev);
if (rslt == BMI055_OK) {
/* Configure slow-motion duration
and threshold */
rslt = config_slow_no_motion_reg(acc_int_config, dev);
}
}
}
}
return rslt;
}
/*!
* @brief This internal API enables the slow/no-motion interrupt
*
* @note For slow_no_mot_sel: 1 -> No-motion; 0-> Slow-motion
*/
static int8_t enable_accel_slow_no_motion_int(struct bmi055_accel_int_sett *acc_int_config,
const struct bmi055_dev *dev)
{
/* Variable to define error */
int8_t rslt;
/* Variable to define address of Interrupt enable 2 register */
uint8_t reg_addr = BMI055_ACC_INT_EN_2_ADDR;
/* Variable defined to retrieve data */
uint8_t data = 0;
/* Variable defined to set data in register */
uint8_t reg_data;
struct bmi055_acc_slow_no_mot_int_cfg *slow_no_mot_int_cfg =
&(acc_int_config->acc_int_type_cfg.acc_slow_no_mot_int);
/* Get interrupt enable status from the register */
rslt = bmi055_get_accel_regs(reg_addr, &data, 1, dev);
if (rslt == BMI055_OK) {
/* Select between slow and no-motion interrupt */
reg_data = BMI055_SET_BITS(data,
BMI055_ACC_SLOW_NO_MOT_SEL_INT_EN_2, slow_no_mot_int_cfg->slow_no_mot_sel);
/* Enabling slow/no-motion x axis */
reg_data = BMI055_SET_BIT_POS0(reg_data,
BMI055_ACC_SLOW_NO_MOT_X_INT_EN_2, slow_no_mot_int_cfg->slow_no_mot_en_x);
/* Enabling slow/no-motion y axis */
reg_data = BMI055_SET_BITS(reg_data,
BMI055_ACC_SLOW_NO_MOT_Y_INT_EN_2, slow_no_mot_int_cfg->slow_no_mot_en_y);
/* Enabling slow/no-motion z axis */
reg_data = BMI055_SET_BITS(reg_data,
BMI055_ACC_SLOW_NO_MOT_Z_INT_EN_2, slow_no_mot_int_cfg->slow_no_mot_en_z);
/* Enable slow/no-motion interrupt in Int Enable 2 register */
rslt = bmi055_set_accel_regs(reg_addr, &reg_data, 1, dev);
}
return rslt;
}
/*!
* @brief This internal API maps the slow/no-motion interrupt to either
* INT pin 1 or 2
*/
static int8_t map_accel_slow_no_motion_int(const struct bmi055_accel_int_sett *acc_int_config,
const struct bmi055_dev *dev)
{
/* Variable to define error */
int8_t rslt;
/* Variable to define register address */
uint8_t reg_addr = 0;
/* Variable defined to retrieve data */
uint8_t data = 0;
/* Variable defined to set data in register */
uint8_t reg_data;
if (acc_int_config->acc_int_channel == BMI055_INT_CHANNEL_1) {
/* Define Interrupt map 0 register */
reg_addr = BMI055_ACC_INT_MAP_0_ADDR;
/* Get interrupt map status from the register */
rslt = bmi055_get_accel_regs(reg_addr, &data, 1, dev);
if (rslt == BMI055_OK) {
/* Map slow/no-motion interrupt to INT1 pin */
reg_data = BMI055_SET_BITS(data,
BMI055_ACC_INT1_MAP_0_SLOW_NO_MOT, BMI055_ENABLE);
}
} else if (acc_int_config->acc_int_channel == BMI055_INT_CHANNEL_2) {
/* Define Interrupt map 2 register */
reg_addr = BMI055_ACC_INT_MAP_2_ADDR;
/* Get interrupt map status from the register */
rslt = bmi055_get_accel_regs(reg_addr, &data, 1, dev);
if (rslt == BMI055_OK) {
/* Map slow/no-motion interrupt to INT2 pin */
reg_data = BMI055_SET_BITS(data,
BMI055_ACC_INT2_MAP_2_SLOW_NO_MOT, BMI055_ENABLE);
}
} else {
rslt = BMI055_E_INVALID_CHANNEL;
}
if (rslt == BMI055_OK) {
/* Configure the Interrupt map register to map
slow/no-motion interrupt to either INT1 or INT2 pin */
rslt = bmi055_set_accel_regs(reg_addr, &reg_data, 1, dev);
}
return rslt;
}
/*!
* @brief This internal API writes the data source definition for
* slow/no-motion interrupt - filtered or unfiltered.
*
* @note Value = 0(BMI055_FALSE) for filtered data , 1(BMI055_TRUE)
* for unfiltered data
*/
static int8_t config_int_slow_no_motion_src(const struct bmi055_accel_int_sett *acc_int_config,
const struct bmi055_dev *dev)
{
/* Variable to define error */
int8_t rslt;
/* Variable to define register address of Interrupt source */
uint8_t reg_addr = BMI055_ACC_INT_SRC_ADDR;
/* Variable defined to retrieve data */
uint8_t data = 0;
/* Variable defined to set data in register */
uint8_t reg_data;
/* Get interrupt source data from the register */
rslt = bmi055_get_accel_regs(reg_addr, &data, 1, dev);
if (rslt == BMI055_OK) {
/* Write the interrupt source data in a variable*/
reg_data = BMI055_SET_BITS(data, BMI055_ACC_SRC_SLOW_NO_MOT,
acc_int_config->int_data_src_type);
/* Write data source definition for slow/no-motion interrupt */
rslt = bmi055_set_accel_regs(reg_addr, &reg_data, 1, dev);
}
return rslt;
}
/*!
* @brief This internal API configures registers for slow/no-motion interrupt.
*/
static int8_t config_slow_no_motion_reg(struct bmi055_accel_int_sett *acc_int_config, const struct bmi055_dev *dev)
{
/* Variable to define error */
int8_t rslt;
/* Configure duration for slow/no-motion interrupt */
rslt = config_slow_no_motion_dur(acc_int_config, dev);
if (rslt == BMI055_OK) {
/* Configure threshold for slow/no-motion interrupt */
rslt = config_slow_no_motion_thres(acc_int_config, dev);
}
return rslt;
}
/*!
* @brief This internal API configures duration for slow/no-motion interrupt.
*/
static int8_t config_slow_no_motion_dur(struct bmi055_accel_int_sett *acc_int_config, const struct bmi055_dev *dev)
{
/* Variable to define error */
int8_t rslt;
/* Variable to define register address */
uint8_t reg_addr = BMI055_ACC_INT_MOT_0_ADDR;
/* Variable defined to set data in register */
uint8_t reg_data = 0;
/* Variable defined to retrieve data */
uint8_t data = 0;
/* Updating the interrupt structure to local structure */
struct bmi055_acc_slow_no_mot_int_cfg *slow_no_mot_int_cfg =
&(acc_int_config->acc_int_type_cfg.acc_slow_no_mot_int);
/*Get the slow/no-motion duration setting */
rslt = bmi055_get_accel_regs(reg_addr, &data, 1, dev);
if (rslt == BMI055_OK) {
/* If slow-motion */
if (slow_no_mot_int_cfg->slow_no_mot_sel == 0) {
/* Set slow motion duration value */
reg_data = BMI055_SET_BITS(data,
BMI055_ACC_SLOW_DUR, slow_no_mot_int_cfg->slow_mot_dur);
rslt = bmi055_set_accel_regs(reg_addr, &reg_data, 1, dev);
} else if (slow_no_mot_int_cfg->slow_no_mot_sel == 1) {
/* Set no-motion duration value */
reg_data = BMI055_SET_BITS(data,
BMI055_ACC_NO_MOTION_DUR, slow_no_mot_int_cfg->no_mot_dur);
rslt = bmi055_set_accel_regs(reg_addr, &reg_data, 1, dev);
} else {
rslt = BMI055_E_INVALID_INPUT;
}
}
return rslt;
}
/*!
* @brief This internal API configures threshold for slow/no-motion interrupt.
*/
static int8_t config_slow_no_motion_thres(struct bmi055_accel_int_sett *acc_int_config, const struct bmi055_dev *dev)
{
/* Variable to define error */
int8_t rslt;
/* Variable to define register address */
uint8_t reg_addr = BMI055_ACC_INT_MOT_2_ADDR;
/* Variable defined to set data in register */
uint8_t reg_data;
/* Updating the interrupt structure to local structure */
struct bmi055_acc_slow_no_mot_int_cfg *slow_no_mot_int_cfg =
&(acc_int_config->acc_int_type_cfg.acc_slow_no_mot_int);
/* Set slow/no-motion threshold value */
reg_data = slow_no_mot_int_cfg->slow_no_mot_thres;
rslt = bmi055_set_accel_regs(reg_addr, &reg_data, 1, dev);
return rslt;
}
/*!
* @brief This internal API sets the slope interrupt of the sensor.This
* interrupt occurs when slope(absolute value of acceleration difference)
* exceeds a preset threshold.
*/
static int8_t set_accel_slope_int(struct bmi055_accel_int_sett *acc_int_config, const struct bmi055_dev *dev)
{
/* Variable to define error */
int8_t rslt;
/* Enable slope interrupt */
rslt = enable_accel_slope_int(acc_int_config, dev);
if (rslt == BMI055_OK) {
/* Map slope interrupt to either INT 1 or 2 */
rslt = map_accel_slope_int(acc_int_config, dev);
if (rslt == BMI055_OK) {
/* Write data source definition for slope
interrupt */
rslt = config_int_slope_src(acc_int_config, dev);
if (rslt == BMI055_OK) {
/* Configuring interrupt pins */
rslt = set_int_pin_config(acc_int_config, dev);
if (rslt == BMI055_OK) {
/* Configure slope registers */
rslt = config_slope_reg(acc_int_config, dev);
}
}
}
}
return rslt;
}
/*!
* @brief This internal API enables the slope interrupt
*/
static int8_t enable_accel_slope_int(struct bmi055_accel_int_sett *acc_int_config, const struct bmi055_dev *dev)
{
/* Variable to define error */
int8_t rslt;
/* Variable to define address of Interrupt enable 0 register */
uint8_t reg_addr = BMI055_ACC_INT_EN_0_ADDR;
/* Variable defined to retrieve data */
uint8_t data = 0;
/* Variable defined to set data in register */
uint8_t reg_data;
struct bmi055_acc_slop_int_cfg *slope_int_cfg = &(acc_int_config->acc_int_type_cfg.acc_slope_int);
/* Get interrupt enable status from the register */
rslt = bmi055_get_accel_regs(reg_addr, &data, 1, dev);
if (rslt == BMI055_OK) {
/* Enabling slope x axis */
reg_data = BMI055_SET_BIT_POS0(data, BMI055_ACC_ANY_MOTION_X_INT_EN_0, slope_int_cfg->slope_en_x);
/* Enabling slope y axis */
reg_data = BMI055_SET_BITS(reg_data, BMI055_ACC_ANY_MOTION_Y_INT_EN_0, slope_int_cfg->slope_en_y);
/* Enabling slope z axis */
reg_data = BMI055_SET_BITS(reg_data, BMI055_ACC_ANY_MOTION_Z_INT_EN_0, slope_int_cfg->slope_en_z);
/* Enable slope interrupt in Int Enable 0 register */
rslt = bmi055_set_accel_regs(reg_addr, &reg_data, 1, dev);
}
return rslt;
}
/*!
* @brief This internal API maps the slope interrupt to either
* INT pin 1 or 2
*/
static int8_t map_accel_slope_int(const struct bmi055_accel_int_sett *acc_int_config, const struct bmi055_dev *dev)
{
/* Variable to define error */
int8_t rslt;
/* Variable to define register address */
uint8_t reg_addr = 0;
/* Variable defined to retrieve data */
uint8_t data = 0;
/* Variable defined to set data in register */
uint8_t reg_data;
if (acc_int_config->acc_int_channel == BMI055_INT_CHANNEL_1) {
/* Define Interrupt map 0 register */
reg_addr = BMI055_ACC_INT_MAP_0_ADDR;
/* Get interrupt map status from the register */
rslt = bmi055_get_accel_regs(reg_addr, &data, 1, dev);
if (rslt == BMI055_OK) {
/* Map slope interrupt to INT1 pin */
reg_data = BMI055_SET_BITS(data, BMI055_ACC_INT1_MAP_0_SLOPE, BMI055_ENABLE);
}
} else if (acc_int_config->acc_int_channel == BMI055_INT_CHANNEL_2) {
/* Define Interrupt map 2 register */
reg_addr = BMI055_ACC_INT_MAP_2_ADDR;
/* Get interrupt map status from the register */
rslt = bmi055_get_accel_regs(reg_addr, &data, 1, dev);
if (rslt == BMI055_OK) {
/* Map slope interrupt to INT2 pin */
reg_data = BMI055_SET_BITS(data, BMI055_ACC_INT2_MAP_2_SLOPE, BMI055_ENABLE);
}
} else {
rslt = BMI055_E_INVALID_CHANNEL;
}
if (rslt == BMI055_OK) {
/* Configure the Interrupt map register to map slope
interrupt to either INT1 or INT2 pin*/
rslt = bmi055_set_accel_regs(reg_addr, &reg_data, 1, dev);
}
return rslt;
}
/*!
* @brief This internal API writes the data source definition for
* slope interrupt - filtered or unfiltered.
*
* @note Value = 0(BMI055_FALSE) for filtered data , 1(BMI055_TRUE)
* for unfiltered data
*/
static int8_t config_int_slope_src(const struct bmi055_accel_int_sett *acc_int_config, const struct bmi055_dev *dev)
{
/* Variable to define error */
int8_t rslt;
/* Variable to define register address of Interrupt source */
uint8_t reg_addr = BMI055_ACC_INT_SRC_ADDR;
/* Variable defined to retrieve data */
uint8_t data = 0;
/* Variable defined to set data in register */
uint8_t reg_data;
/* Get interrupt source data from the register */
rslt = bmi055_get_accel_regs(reg_addr, &data, 1, dev);
if (rslt == BMI055_OK) {
/* Write the interrupt source data in a variable*/
reg_data = BMI055_SET_BITS(data, BMI055_ACC_SRC_SLOPE, acc_int_config->int_data_src_type);
/* Write data source definition for slope interrupt */
rslt = bmi055_set_accel_regs(reg_addr, &reg_data, 1, dev);
}
return rslt;
}
/*!
* @brief This internal API configures registers for slope interrupt.
*/
static int8_t config_slope_reg(struct bmi055_accel_int_sett *acc_int_config, const struct bmi055_dev *dev)
{
/* Variable to define error */
int8_t rslt;
/* Variable to define register address */
uint8_t reg_addr = BMI055_ACC_INT_MOT_0_ADDR;
/* Variable defined to set data in register */
uint8_t reg_data = 0;
/* Variable defined to retrieve data */
uint8_t data = 0;
/* Array defined to store data */
uint8_t data_array[2] = {0};
/* Updating the interrupt structure to local structure */
struct bmi055_acc_slop_int_cfg *slope_int_cfg = &(acc_int_config->acc_int_type_cfg.acc_slope_int);
/*Get the slope interrupt duration */
rslt = bmi055_get_accel_regs(reg_addr, &data, 1, dev);
if (rslt == BMI055_OK) {
/* Set the slope duration */
reg_data = BMI055_SET_BIT_POS0(data, BMI055_ACC_SLOPE_DUR, slope_int_cfg->slope_dur);
/* Store the duration in the array */
data_array[0] = reg_data;
/* Store the threshold in the array */
data_array[1] = slope_int_cfg->slope_thr;
/* Write the data simultaneously since addresses are located in
consecutive positions.*/
rslt = bmi055_set_accel_regs(reg_addr, data_array, 2, dev);
dev->delay_ms(1);
}
return rslt;
}
/*!
*@brief This internal API sets the orientation interrupt of the sensor.This
* interrupt occurs when there is orientation change in the sensor
* with respect to gravitational field vector g.
*/
static int8_t set_accel_orientation_int(struct bmi055_accel_int_sett *acc_int_config, const struct bmi055_dev *dev)
{
/* Variable to define error */
int8_t rslt;
/* Enable orientation interrupt */
rslt = enable_accel_orient_int(acc_int_config, dev);
if (rslt == BMI055_OK) {
/* Map orientation interrupt to either INT 1 or 2 */
rslt = map_accel_orient_int(acc_int_config, dev);
if (rslt == BMI055_OK) {
/* Configuring interrupt pins */
rslt = set_int_pin_config(acc_int_config, dev);
if (rslt == BMI055_OK) {
/* Configure orientation registers */
rslt = config_orient_reg(acc_int_config, dev);
}
}
}
return rslt;
}
/*!
* @brief This internal API enables the orientation interrupt
*/
static int8_t enable_accel_orient_int(struct bmi055_accel_int_sett *acc_int_config, const struct bmi055_dev *dev)
{
/* Variable to define error */
int8_t rslt;
/* Variable to define address of Interrupt enable 0 register */
uint8_t reg_addr = BMI055_ACC_INT_EN_0_ADDR;
/* Variable defined to retrieve data */
uint8_t data = 0;
/* Variable defined to set data in register */
uint8_t reg_data;
/* Updating the interrupt structure to local structure */
struct bmi055_acc_orient_int_cfg *orient_int_cfg = &(acc_int_config->acc_int_type_cfg.acc_orient_int);
/* Get interrupt enable status from the register */
rslt = bmi055_get_accel_regs(reg_addr, &data, 1, dev);
if (rslt == BMI055_OK) {
/* Write interrupt enable bits in the variable */
reg_data = BMI055_SET_BITS(data, BMI055_ACC_ORIENT_INT_EN_0, orient_int_cfg->orient_en);
/* Enable orientation interrupt in Interrupt Enable 1
register */
rslt = bmi055_set_accel_regs(reg_addr, &reg_data, 1, dev);
}
return rslt;
}
/*!
* @brief This internal API maps the orientation interrupt to either
* INT pin 1 or 2
*/
static int8_t map_accel_orient_int(const struct bmi055_accel_int_sett *acc_int_config, const struct bmi055_dev *dev)
{
/* Variable to define error */
int8_t rslt;
/* Variable to define register address */
uint8_t reg_addr = 0;
/* Variable defined to retrieve data */
uint8_t data = 0;
/* Variable defined to set data in register */
uint8_t reg_data = 0;
if (acc_int_config->acc_int_channel == BMI055_INT_CHANNEL_1) {
/* Define Interrupt map 0 register */
reg_addr = BMI055_ACC_INT_MAP_0_ADDR;
/* Get interrupt map status from the register */
rslt = bmi055_get_accel_regs(reg_addr, &data, 1, dev);
if (rslt == BMI055_OK) {
/* Map orientation interrupt to INT1 pin */
reg_data = BMI055_SET_BITS(data, BMI055_ACC_INT1_MAP_0_ORIENT, BMI055_ENABLE);
}
} else if (acc_int_config->acc_int_channel == BMI055_INT_CHANNEL_2) {
/* Define Interrupt map 2 register */
reg_addr = BMI055_ACC_INT_MAP_2_ADDR;
/* Get interrupt map status from the register */
rslt = bmi055_get_accel_regs(reg_addr, &data, 1, dev);
if (rslt == BMI055_OK) {
/* Map orientation interrupt to INT2 pin */
reg_data = BMI055_SET_BITS(data, BMI055_ACC_INT2_MAP_2_ORIENT, BMI055_ENABLE);
}
} else {
rslt = BMI055_E_INVALID_CHANNEL;
}
if (rslt == BMI055_OK) {
/* Configure the Interrupt map register to map orientation
interrupt to either INT1 or INT2 pin*/
rslt = bmi055_set_accel_regs(reg_addr, &reg_data, 1, dev);
}
return rslt;
}
/*!
* @brief This internal API configures registers for orientation interrupt
*/
static int8_t config_orient_reg(struct bmi055_accel_int_sett *acc_int_config, const struct bmi055_dev *dev)
{
/* Variable to define error */
int8_t rslt;
/* Variable to define register address */
uint8_t reg_addr;
/* Variable defined to set data in register */
uint8_t reg_data = 0;
/* Variable defined to retrieve data */
uint8_t data = 0;
/* Array defined to store data */
uint8_t data_array[2] = {0};
/* Updating the interrupt structure to local structure */
struct bmi055_acc_orient_int_cfg *orient_int_cfg = &(acc_int_config->acc_int_type_cfg.acc_orient_int);
/* Configuring orientation registers */
reg_addr = BMI055_ACC_INT_ORIENT_0_ADDR;
/* Get the previous settings */
rslt = bmi055_get_accel_regs(reg_addr, &data, 1, dev);
if (rslt == BMI055_OK) {
/* Set orientation hysteresis */
reg_data = BMI055_SET_BITS(data, BMI055_ACC_ORIENT_HYST, orient_int_cfg->orient_hyst);
/* Set orient blocking */
reg_data = BMI055_SET_BITS(reg_data, BMI055_ACC_ORIENT_BLOCKING, orient_int_cfg->orient_blocking);
/* Set orient mode */
reg_data = BMI055_SET_BIT_POS0(reg_data, BMI055_ACC_ORIENT_MODE, orient_int_cfg->orient_mode);
/* Store orientation hysteresis, blocking and
mode in the array */
data_array[0] = reg_data;
/* Configuring rest of the settings in another
register */
reg_addr = BMI055_ACC_INT_ORIENT_1_ADDR;
/* Get the previous settings */
rslt = bmi055_get_accel_regs(reg_addr, &data, 1, dev);
if (rslt == BMI055_OK) {
/* Set up/down masking : '0' -> generates interrupt
only with x-y plane */
reg_data = BMI055_SET_BITS(data, BMI055_ACC_ORIENT_UD_EN, orient_int_cfg->orient_ud_en);
/* Set orient theta */
reg_data = BMI055_SET_BIT_POS0(reg_data, BMI055_ACC_ORIENT_THETA, orient_int_cfg->orient_theta);
/* Store up/down enable and theta angle in the
next byte */
data_array[1] = reg_data;
/* Write the data simultaneously since addresses are
located in consecutive positions.*/
rslt = bmi055_set_accel_regs(BMI055_ACC_INT_ORIENT_0_ADDR, data_array, 2, dev);
dev->delay_ms(1);
}
}
return rslt;
}
/*!
* @brief This internal API configures the pins to fire the interrupt signal
* when it occurs.
*/
static int8_t set_int_pin_config(struct bmi055_accel_int_sett *acc_int_config, const struct bmi055_dev *dev)
{
/* Variable to define error */
int8_t rslt;
/* Variable to define register address */
uint8_t reg_addr = BMI055_ACC_INT_OUT_CTRL_ADDR;
/* Variable defined to retrieve and set data in the register */
uint8_t reg_data_array[2] = {0};
/* Variable defined to store data temporarily */
uint8_t temp_data = 0;
/* Variable defined to get data temporarily */
uint8_t temp_out_data = 0;
/* Update the local structure with the pin configuration
structure */
struct bmi055_int_pin_sett *int_pin_cfg = &(acc_int_config->int_pin_sett);
/* Get the electrical behavior configuration of interrupt pin */
rslt = bmi055_get_accel_regs(reg_addr, reg_data_array, 2, dev);
if (rslt == BMI055_OK) {
/* Get the first byte of the data array */
temp_data = reg_data_array[0];
/* Configure input output configuration of interrupt pins */
rslt = config_in_out_int(int_pin_cfg, acc_int_config, temp_data, &temp_out_data);
if (rslt == BMI055_OK) {
/* Copy register value to the first byte of array */
reg_data_array[0] = temp_out_data;
/* Get the second byte of the data array */
temp_data = reg_data_array[1];
/* Configure latch and reset configuration of
interrupt pins */
config_reset_latch_int(int_pin_cfg, temp_data, &temp_out_data);
/* Copy register value to the second byte of array */
reg_data_array[1] = temp_out_data;
/* Write data to INT_OUT_CTRL and INT_RST_LATCH
simultaneously as they lie in consecutive places */
rslt = bmi055_set_accel_regs(reg_addr, reg_data_array, 2, dev);
}
}
return rslt;
}
/*!
* @brief This internal API configures the input output configuration of the
* interrupt pins
*/
static int8_t config_in_out_int(const struct bmi055_int_pin_sett *int_pin_cfg,
const struct bmi055_accel_int_sett *acc_int_config, uint8_t temp_data,
uint8_t *temp_out_data)
{
/* Variable to define error */
int8_t rslt = 0;
if (acc_int_config->acc_int_channel == BMI055_INT_CHANNEL_1) {
/* Configuring output type for INT1 pin */
temp_data = BMI055_SET_BIT_POS0(temp_data, BMI055_ACC_INT1_LVL,
int_pin_cfg->output_type);
/* Configuring output mode for INT1 pin */
temp_data = BMI055_SET_BITS(temp_data, BMI055_ACC_INT1_OD,
int_pin_cfg->output_mode);
} else if (acc_int_config->acc_int_channel == BMI055_INT_CHANNEL_2) {
/* Configuring output type for INT2 pin */
temp_data = BMI055_SET_BITS(temp_data, BMI055_ACC_INT2_LVL,
int_pin_cfg->output_type);
/* Configuring output mode for INT2 pin */
temp_data = BMI055_SET_BITS(temp_data, BMI055_ACC_INT2_OD,
int_pin_cfg->output_mode);
} else {
rslt = BMI055_E_INVALID_CHANNEL;
}
if (rslt == BMI055_OK)
*temp_out_data = temp_data;
return rslt;
}
/*!
* @brief This internal API configures the latch and the reset configuration of
* the interrupt pins
*/
static void config_reset_latch_int(const struct bmi055_int_pin_sett *int_pin_cfg,
uint8_t temp_data, uint8_t *temp_out_data)
{
/* Configuring Latch duration */
temp_data = BMI055_SET_BIT_POS0(temp_data, BMI055_ACC_LATCH_DUR,
int_pin_cfg->latch_dur);
/* Configuring interrupt reset - '1' clears all latched
interrupts and '0' keeps latched interrupt active */
temp_data = BMI055_SET_BITS(temp_data, BMI055_ACC_RESET_INT,
int_pin_cfg->reset_int);
*temp_out_data = temp_data;
}
/*!
* @brief This internal API enables/disables all accelerometer interrupts.
*/
static int8_t enable_disable_all_accel_int(uint8_t set_en_bit, const struct bmi055_dev *dev)
{
/* Variable to define error */
int8_t rslt;
/* Variable to define register address */
uint8_t reg_addr = BMI055_ACC_INT_EN_0_ADDR;
/* Variable defined to store data in the register*/
uint8_t reg_data[3] = {0};
/* Variable defined for loop*/
uint8_t count = 0;
if (set_en_bit == 1) {
while (count < 3)
reg_data[count++] = 0xFF;
}
/* Write '0XFF' to enable or '0' to disable
all interrupt registers */
rslt = bmi055_set_accel_regs(reg_addr, reg_data, 3, dev);
return rslt;
}
/*!
* @brief This internal API is used to validate the device structure pointer for
* null conditions.
*/
static int8_t bmi055_accel_null_ptr_check(const struct bmi055_dev *dev)
{
/* Variable to define error */
int8_t rslt;
if ((dev == NULL) || (dev->read == NULL) || (dev->write == NULL) || (dev->delay_ms == NULL)) {
/* Device structure pointer is not valid */
rslt = BMI055_E_NULL_PTR;
} else {
/* Device structure is fine */
rslt = BMI055_OK;
}
return rslt;
}
/** @}*/
/**
* Copyright (C) 2015 - 2016 Bosch Sensortec GmbH
*
* 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.
*
* @file bmi055_gyro.c
* @date 16 Feb 2017
* @version 0.2.0
* @brief
*
*/
/*!
* @defgroup bmi055_gyro
* @brief Sensor driver for BMI055 sensor
* @{*/
/***************************************************************************/
/**\name Header files
****************************************************************************/
#include "bmi055.h"
/***************************************************************************/
/**\name Local Function Prototypes
****************************************************************************/
/*!
* @brief This API sets the range of accel sensor.
*
* @param[in] dev : Structure instance of bmi055_dev.
* @note : Refer user guide for detailed info.
*
* @return Result of API execution status
* @retval zero -> Success / -ve value -> Error.
*/
static int8_t bmi055_set_gyro_range(const struct bmi055_dev *dev);
/*!
* @brief This API sets the bandwidth of gyroscope sensor.
*
* @param[in] dev : Structure instance of bmi055_dev.
* @note : Refer user guide for detailed info.
*
* @return Result of API execution status
* @retval zero -> Success / -ve value -> Error.
*/
static int8_t bmi055_set_gyro_bandwidth(const struct bmi055_dev *dev);
/*!
* @brief This internal API is used to validate the device pointer for
* null conditions.
*
* @param[in] dev : Structure instance of bmi055_dev.
*
* @return Result of API execution status
* @retval zero -> Success / +ve value -> Warning / -ve value -> Error
*/
static int8_t bmi055_gyro_null_ptr_check(const struct bmi055_dev *dev);
/*!
* @brief This API configures the pins to fire the
* interrupt signal when it occurs.
*
* @param[in] int_config : Structure instance of bmi055_int_sett.
* @param[in] dev : Structure instance of bmi055_dev.
*
* @return Result of API execution status
* @retval zero -> Success / -ve value -> Error.
*/
#if CODE_UNDER_MODIFICATION
static int8_t set_int_pin_config(struct bmi055_int_sett *int_config, struct bmi055_dev *dev);
/*!
* @brief This API sets the any motion/slope interrupt of the sensor.
* This interrupt occurs when slope bet. gyro values exceeds preset
* threshold.
*
* @param[in] int_config : Structure instance of bmi055_int_sett.
* @param[in] dev : Structure instance of bmi055_dev.
*
* @return Result of API execution status
* @retval zero -> Success / -ve value -> Error.
*/
static int8_t set_gyro_any_motion_int(struct bmi055_int_sett *int_config, struct bmi055_dev *dev);
/*!
* @brief This API sets the high-rate interrupt.This interrupt occurs
* if gyro values exceeds a preset threshold and is used for the
* detection of shock or other high-angular rate events
*
* @param[in] int_config : Structure instance of bmi055_int_sett.
* @param[in] dev : Structure instance of bmi055_dev.
*
* @return Result of API execution status
* @retval zero -> Success / -ve value -> Error.
*/
static int8_t set_gyro_high_rate_int(struct bmi055_int_sett *int_config, struct bmi055_dev *dev);
/*!
* @brief This API sets the data ready interrupt for gyro.
* This interrupt occurs when new z-axis gyro data comes.
*
* @param[in] int_config : Structure instance of bmi055_int_sett.
* @param[in] dev : Structure instance of bmi055_dev.
*
* @return Result of API execution status
* @retval zero -> Success / -ve value -> Error.
*/
static int8_t set_gyro_data_ready_int(struct bmi055_int_sett *int_config, struct bmi055_dev *dev);
/*!
* @brief This API sets the auto-offset tap interrupt for gyro.
*
* @param[in] int_config : Structure instance of bmi055_int_sett.
* @param[in] dev : Structure instance of bmi055_dev.
*
* @return Result of API execution status
* @retval zero -> Success / -ve value -> Error.
*/
static int8_t set_gyro_auto_offset_tap_int(struct bmi055_int_sett *int_config, struct bmi055_dev *dev);
/*!
* @brief This API sets the slow-offset interrupt for gyro.
*
* @param[in] int_config : Structure instance of bmi055_int_sett.
* @param[in] dev : Structure instance of bmi055_dev.
*
* @return Result of API execution status
* @retval zero -> Success / -ve value -> Error.
*/
static int8_t set_gyro_slow_offset_int(struct bmi055_int_sett *int_config, struct bmi055_dev *dev);
/*!
* @brief This API sets the fast-offset interrupt for gyro.
*
* @param[in] int_config : Structure instance of bmi055_int_sett.
* @param[in] dev : Structure instance of bmi055_dev.
*
* @return Result of API execution status
* @retval zero -> Success / -ve value -> Error.
*/
static int8_t set_gyro_fast_offset_int(struct bmi055_int_sett *int_config, struct bmi055_dev *dev);
#endif
/***************************************************************************/
/**\name User Function Definitions
****************************************************************************/
/*!
* @brief This API is the entry point for gyroscope sensor. It reads the
* chip-id and initializes gyroscope parameters with default values.
*/
int8_t bmi055_gyro_init(struct bmi055_dev *dev)
{
/* Variable to define error */
int8_t rslt;
/* Variable to assign chip id */
uint8_t chip_id = 0;
/* Null-pointer check */
rslt = bmi055_gyro_null_ptr_check(dev);
if (rslt == BMI055_OK) {
/* Read chip-id of the gyroscope */
rslt = bmi055_get_gyro_regs(BMI055_GYR_CHIP_ID_ADDR, &chip_id, 1, dev);
if (rslt == BMI055_OK) {
/* Validate chip-id */
if (chip_id == BMI055_GYRO_CHIP_ID) {
/* Assign chip id to the structure */
dev->gyro_chip_id = chip_id;
/* Reset the gyroscope sensor */
rslt = bmi055_gyro_soft_reset(dev);
/* waiting time required prior to any
*configuration register access */
dev->delay_ms(5);
} else {
/* Communication fail */
rslt = BMI055_E_DEV_NOT_FOUND;
}
} else {
/* Invalid sensor */
rslt = BMI055_E_COM_FAIL;
}
/* Initializing gyroscope parameters with default values */
dev->gyro_cfg.bw = BMI055_GYRO_BW_523_HZ;
dev->gyro_cfg.power = BMI055_GYRO_PM_NORMAL;
dev->gyro_cfg.range = BMI055_GYRO_RANGE_2000_DPS;
}
return rslt;
}
/*!
* @brief This API reads the data from the given register address of the
*gyroscope sensor.
*/
int8_t bmi055_get_gyro_regs(uint8_t reg_addr, uint8_t *data, uint16_t len, const struct bmi055_dev *dev)
{
/* Variable to define error */
int8_t rslt;
/* Null-pointer check */
rslt = bmi055_gyro_null_ptr_check(dev);
if (rslt == BMI055_OK) {
/* Configuring reg_addr for SPI Interface */
if (dev->interface == BMI055_SPI_INTF)
reg_addr = (reg_addr | BMI055_SPI_RD_MASK);
/* Read the gyroscope register */
rslt = dev->read(dev->gyro_id, reg_addr, data, len);
dev->delay_ms(1);
if (rslt != 0)
/* Communication fail */
rslt = BMI055_E_COM_FAIL;
}
return rslt;
}
/*!
* @brief This API writes the given data to the register address of the
*gyroscope sensor.
*/
int8_t bmi055_set_gyro_regs(uint8_t reg_addr, uint8_t *data, uint16_t len, const struct bmi055_dev *dev)
{
int8_t rslt;
/* Null-pointer check */
rslt = bmi055_gyro_null_ptr_check(dev);
if (rslt == BMI055_OK) {
/* Configuring reg_addr for SPI Interface */
if (dev->interface == BMI055_SPI_INTF)
reg_addr = (reg_addr & BMI055_SPI_WR_MASK);
/* Write to the gyroscope register */
rslt = dev->write(dev->gyro_id, reg_addr, data, len);
dev->delay_ms(1);
if (rslt != 0)
rslt = BMI055_E_COM_FAIL;
}
return rslt;
}
/*!
* @brief This API resets and restarts the gyroscope sensor. All register values
* are overwritten with default values.
*/
int8_t bmi055_gyro_soft_reset(const struct bmi055_dev *dev)
{
int8_t rslt;
/* Variable to define the soft reset Value */
uint8_t data = BMI055_SOFT_RESET_VAL;
/* Null-pointer check */
rslt = bmi055_gyro_null_ptr_check(dev);
if (rslt == BMI055_OK) {
/* Reset the gyroscope */
rslt = bmi055_set_gyro_regs(BMI055_GYR_SOFTRESET_ADDR, &data, 1, dev);
}
return rslt;
}
/*!
* @brief This API sets the power mode of the gyroscope sensor.
*/
int8_t bmi055_set_gyro_power_mode(const struct bmi055_dev *dev)
{
/* Variable to define error */
int8_t rslt;
uint8_t reg_addr = 0, data = 0;
/* Variable to define power */
uint8_t power = 0;
/* Variable to define register to store data */
uint8_t reg_data = 0;
/* Null-pointer check */
rslt = bmi055_gyro_null_ptr_check(dev);
if (rslt == BMI055_OK) {
/* Configure gyroscope power */
if (dev->gyro_cfg.power <= BMI055_GYRO_PM_SUSPEND) {
/* Define address for gyroscope power */
reg_addr = BMI055_GYR_LPM1_ADDR;
/* Get gyroscope power from the register*/
rslt = bmi055_get_gyro_regs(reg_addr, &data, 1, dev);
if (rslt == BMI055_OK) {
/* Write the configured power mode */
switch (dev->gyro_cfg.power) {
/* Value of power on normal power mode */
case BMI055_GYRO_PM_NORMAL:
power = 0;
break;
/* Value of power on deep suspend power mode */
case BMI055_GYRO_PM_DEEP_SUSPEND:
power = 0x20;
break;
/* Value of power on suspend power mode */
case BMI055_GYRO_PM_SUSPEND:
power = 0x80;
break;
default:
break;
}
/* Write the configured power mode */
reg_data = BMI055_SET_BIT_POS0(data, BMI055_GYRO_POWER, power);
/* Set the configured power */
rslt = bmi055_set_gyro_regs(reg_addr, &reg_data, 1, dev);
} else {
/* Communication fail */
rslt = BMI055_E_COM_FAIL;
}
} else {
/* Out of range */
rslt = BMI055_E_OUT_OF_RANGE;
}
}
return rslt;
}
/*!
* @brief This API sets the bandwidth of gyroscope sensor.
*/
static int8_t bmi055_set_gyro_bandwidth(const struct bmi055_dev *dev)
{
/* Variable to define error */
int8_t rslt;
/* Variable to define reg address, temp value and buffer */
uint8_t reg_addr = 0;
/* Variable to define bandwidth */
uint8_t bw = 0;
/* Variable to define register to store data */
uint8_t reg_data = 0;
/* Null-pointer check */
rslt = bmi055_gyro_null_ptr_check(dev);
if (rslt == BMI055_OK) {
/* Bandwidth range check */
if (dev->gyro_cfg.bw <= BMI055_GYRO_BW_32_HZ) {
/* Address to get gyroscope bandwidth */
reg_addr = BMI055_GYR_BW_ADDR;
/* Get gyroscope bandwidth from the register*/
rslt = bmi055_get_gyro_regs(reg_addr, &bw, 1, dev);
if (rslt == BMI055_OK) {
/* Write the corresponding Bandwidth
mode in the register variable */
reg_data = BMI055_SET_BIT_POS0(bw, BMI055_GYRO_BW, dev->gyro_cfg.bw);
/* Set the configured gyroscope
bandwidth */
rslt = bmi055_set_gyro_regs(reg_addr, &reg_data, 1, dev);
} else {
/* Communication fail */
rslt = BMI055_E_COM_FAIL;
}
} else{
/* Not within range */
rslt = BMI055_E_OUT_OF_RANGE;
}
}
return rslt;
}
/*!
* @brief This API sets the range of gyroscope sensor.
*/
static int8_t bmi055_set_gyro_range(const struct bmi055_dev *dev)
{
/* Variable to define error */
int8_t rslt;
/* Variable to define reg address, temp value and buffer */
uint8_t reg_addr = 0;
/* Variable to define range */
uint8_t range = 0;
/* Variable to define register to store data */
uint8_t reg_data = 0;
/* Null-pointer check */
rslt = bmi055_gyro_null_ptr_check(dev);
if (rslt == BMI055_OK) {
/* Range check */
if (dev->gyro_cfg.range <= BMI055_GYRO_RANGE_125_DPS) {
/* Address to get range */
reg_addr = BMI055_GYR_RANGE_ADDR;
/* Get gyroscope range from the register*/
rslt = bmi055_get_gyro_regs(reg_addr, &range, 1, dev);
if (rslt == BMI055_OK) {
/* Write the corresponding range in the
register variable */
reg_data = BMI055_SET_BIT_POS0(range, BMI055_GYRO_RANGE, dev->gyro_cfg.range);
/* Set the configured range */
rslt = bmi055_set_gyro_regs(reg_addr, &reg_data, 1, dev);
} else {
/* Communication fail */
rslt = BMI055_E_COM_FAIL;
}
} else {
/* Not within range */
rslt = BMI055_E_OUT_OF_RANGE;
}
}
return rslt;
}
/*!
* @brief This API sets the bandwidth and range for bmi055 gyroscope
*/
int8_t bmi055_set_gyro_sensor_config(uint8_t bmi055_config, const struct bmi055_dev *dev)
{
int8_t rslt;
/* Check for null pointer in the device structure*/
rslt = bmi055_gyro_null_ptr_check(dev);
if (rslt == BMI055_OK) {
/* Check whether configuration is valid) */
if (bmi055_config & (BANDWIDTH_CONFIG | RANGE_CONFIG)) {
/* Set accelerometer bandwidth */
if (bmi055_config & BANDWIDTH_CONFIG)
rslt = bmi055_set_gyro_bandwidth(dev);
/* Set accelerometer range */
if (bmi055_config & RANGE_CONFIG)
rslt = bmi055_set_gyro_range(dev);
} else {
/* Configuration setting failed */
rslt = BMI055_E_CONFIG_FAIL;
}
}
return rslt;
}
/*! @brief This API reads the gyroscope data from the sensor, and stores it in the
* bmi055_sensor_data structure instance passed by the user.
*/
int8_t bmi055_get_gyro_data(struct bmi055_sensor_data *gyro, const struct bmi055_dev *dev)
{
int8_t rslt;
uint8_t index = 0, data_array[6] = {0};
uint16_t lsb = 0, msb = 0, msblsb = 0;
/* Null-pointer check */
rslt = bmi055_gyro_null_ptr_check(dev);
if (rslt == BMI055_OK) {
/* Read accelerometer sensor data */
rslt = bmi055_get_gyro_regs(BMI055_GYR_X_L_ADDR, data_array, 6, dev);
if (rslt == BMI055_OK) {
/* Parse X-axis accelerometer data */
lsb = (uint16_t)data_array[index++];
msb = ((uint16_t)data_array[index++]) << 8;
msblsb = msb | lsb;
gyro->x = (int16_t)msblsb;
/* Parse Y-axis gyroscope data */
lsb = (uint16_t)data_array[index++];
msb = ((uint16_t)data_array[index++]) << 8;
msblsb = msb | lsb;
gyro->y = (int16_t)msblsb;
/* Parse Z-axis accelerometer data */
lsb = (uint16_t)data_array[index++];
msb = ((uint16_t)data_array[index++]) << 8;
msblsb = msb | lsb;
gyro->z = (int16_t)msblsb;
} else {
/* Communication fail */
rslt = BMI055_E_COM_FAIL;
}
}
return rslt;
}
/*!
* @brief This internal API is used to validate the device structure pointer for
* null conditions.
*/
static int8_t bmi055_gyro_null_ptr_check(const struct bmi055_dev *dev)
{
int8_t rslt;
if ((dev == NULL) || (dev->read == NULL) || (dev->write == NULL) || (dev->delay_ms == NULL)) {
/* Device structure pointer is not valid */
rslt = BMI055_E_NULL_PTR;
} else {
/* Device structure is fine */
rslt = BMI055_OK;
}
return rslt;
}
/* TODO Code Cleanup */
#if 0
/*!
* @brief This API configures the necessary gyroscope interrupt
* based on the user settings in the bmi055_int_sett
* structure instance.
*/
int8_t bmi055_set_gyro_int_config(struct bmi055_int_sett *int_config, struct bmi055_dev *dev)
{
int8_t rslt = BMI055_OK;
switch (int_config->gyr_int_type)
{
case BMI055_GYRO_ANY_MOTION_INT:
/* Any motion interrupt */
rslt = set_gyro_any_motion_int(int_config, dev);
break;
case BMI055_GYRO_HIGH_RATE_INT:
/* High rate Interrupt */
rslt = set_gyro_high_rate_int(int_config, dev);
break;
case BMI055_GYRO_DATA_RDY_INT:
/* Data Ready interrupt */
rslt = set_gyro_data_ready_int(int_config, dev);
break;
case BMI055_GYRO_AUTO_OFFSET_INT:
/* Auto-offset interrupt */
rslt = set_gyro_auto_offset_tap_int(int_config, dev);
break;
case BMI055_GYRO_SLOW_OFFSET_INT:
/* Slow-offset interrupt */
rslt = set_gyro_slow_offset_int(int_config, dev);
break;
case BMI055_GYRO_FAST_OFFSET_INT:
/* Fast-offset interrupt */
rslt = set_gyro_fast_offset_int(int_config, dev);
break;
default:
break;
}
return rslt;
}
/***************************************************************************/
/**\name Local function definitions
****************************************************************************/
/*!
* @brief This API sets the any motion/slope interrupt of the sensor.
* This interrupt occurs when slope bet. gyro values exceeds preset
* threshold.
*/
static int8_t set_gyro_any_motion_int(struct bmi055_int_sett *int_config, struct bmi055_dev *dev)
{
int8_t rslt = BMI055_OK;
uint8_t reg_addr, data, temp, data_array[3];
/* Null-pointer check */
if ((dev == NULL) || (dev->read == NULL) || (dev->write == NULL) || (dev->delay_ms == NULL) || ((int_config == NULL)))
return BMI055_E_NULL_PTR;
/* updating the interrupt structure to local structure */
struct bmi055_gyr_any_mot_int_cfg *any_mot_int = &(int_config->int_type_cfg.gyr_any_mot_int);
/* Configuring interrupt pins */
rslt = set_int_pin_config(int_config, dev);
/* Configure Int Map register to map interrupt pin to any motion interrupt */
if (int_config->gyr_int_channel == BMI055_INT_CHANNEL_3) {
reg_addr = BMI055_GYR_INT_MAP_0_ADDR;
rslt = bmi055_get_gyro_regs(reg_addr, &data, 1, dev);
if (rslt != BMI055_OK)
return rslt;
temp = data & ~BMI055_GYR_INT1_MAP_0_ANY_MOT_MASK;
data = temp | ((1 << 1) & BMI055_GYR_INT1_MAP_0_ANY_MOT_MASK);//Mapping INT3 pin to any motion interrupt
}
else {
reg_addr = BMI055_GYR_INT_MAP_2_ADDR;
rslt = bmi055_get_gyro_regs(reg_addr, &data, 1, dev);
if (rslt != BMI055_OK)
return rslt;
temp = data & ~BMI055_GYR_INT2_MAP_2_ANY_MOT_MASK;
data = temp | ((1 << 1) & BMI055_GYR_INT2_MAP_2_ANY_MOT_MASK);//Mapping INT4 pin to any motion interrupt
}
rslt = bmi055_set_gyro_regs(reg_addr, &data, 1, dev);/* write to appropriate Map register */
if (rslt != BMI055_OK)
return rslt;
/* Configuring any motion registers */
reg_addr = BMI055_GYRO_0_REG;
rslt = bmi055_get_gyro_regs(reg_addr, data_array, 3, dev);
dev->delay_ms(1);
if (rslt != BMI055_OK)
return rslt;
/* Write to INT_SRC register */
data = data_array[0];
temp = data & ~BMI055_GYR_SRC_ANY_MOT_MASK;
data = temp | ((0 << 1) & BMI055_GYR_SRC_ANY_MOT_MASK);// // Adding data source for Any-motion Interrupt
data_array[0] = data;
data = data_array[1];
temp = data & ~BMI055_GYR_ANY_THRES_MASK;
data = temp | (any_mot_int->any_thr & BMI055_GYR_ANY_THRES_MASK);// Adding any motion threshold
data_array[1] = data;
data = data_array[2];
temp = data & ~BMI055_GYR_ANY_EN_X_MASK;
data = temp | ((any_mot_int->any_en_x) & BMI055_GYR_ANY_EN_X_MASK);// Adding any motion interrupt x flag
temp = data & ~BMI055_GYR_ANY_EN_Y_MASK;
data = temp | ((any_mot_int->any_en_y << 1) & BMI055_GYR_ANY_EN_Y_MASK);// Adding any motion interrupt y flag
temp = data & ~BMI055_GYR_ANY_EN_Z_MASK;
data = temp | ((any_mot_int->any_en_z << 2) & BMI055_GYR_ANY_EN_Z_MASK);// Adding any motion interrupt z flag
temp = data & ~BMI055_GYR_ANY_DURSAMPLE_MASK;
data = temp | ((any_mot_int->any_dursample << 4) & BMI055_GYR_ANY_DURSAMPLE_MASK);// Adding any motion sample duration
temp = data & ~BMI055_GYR_AWAKE_DUR_MASK;
data = temp | ((any_mot_int->awake_dur << 6) & BMI055_GYR_AWAKE_DUR_MASK);// Adding any motion awake duration
data_array[2] = data;
/* Writing data to any motion interrupt registers simultaneously since required registers are located consecutively */
rslt = bmi055_set_gyro_regs(reg_addr, data_array, 3, dev);
dev->delay_ms(1);
return rslt;
}
/*!
* @brief This API sets the high-rate interrupt.This interrupt occurs
* if gyro values exceeds a preset threshold and is used for the
* detection of shock or other high-angular rate events
*/
static int8_t set_gyro_high_rate_int(struct bmi055_int_sett *int_config, struct bmi055_dev *dev)
{
int8_t rslt = BMI055_OK;
uint8_t reg_addr, data, temp, data_array[6];
/* Null-pointer check */
if ((dev == NULL) || (dev->read == NULL) || (dev->write == NULL) || (dev->delay_ms == NULL) || ((int_config == NULL)))
return BMI055_E_NULL_PTR;
/* updating the interrupt structure to local structure */
struct bmi055_gyr_high_rate_int_cfg *high_rate_int = &(int_config->int_type_cfg.gyr_high_rate_int);
/* Configuring interrupt pins */
rslt = set_int_pin_config(int_config, dev);
if (rslt != BMI055_OK)
return rslt;
/* Configure Int Map register to map interrupt pin to High-rate interrupt */
if (int_config->gyr_int_channel == BMI055_INT_CHANNEL_3) {
reg_addr = BMI055_GYR_INT_MAP_0_ADDR;
rslt = bmi055_get_gyro_regs(reg_addr, &data, 1, dev);
if (rslt != BMI055_OK)
return rslt;
temp = data & ~BMI055_GYR_INT1_MAP_0_HIGHRATE_MASK;
data = temp | ((1 << 3) & BMI055_GYR_INT1_MAP_0_HIGHRATE_MASK);//Mapping INT3 pin to High-rate interrupt
}
else {
reg_addr = BMI055_GYR_INT_MAP_2_ADDR;
rslt = bmi055_get_gyro_regs(reg_addr, &data, 1, dev);
if (rslt != BMI055_OK)
return rslt;
temp = data & ~BMI055_GYR_INT2_MAP_2_HIGHRATE_MASK;
data = temp | ((1 << 3) & BMI055_GYR_INT2_MAP_2_HIGHRATE_MASK);//Mapping INT4 pin to High-rate interrupt
}
rslt = bmi055_set_gyro_regs(reg_addr, &data, 1, dev);/* write to appropriate Map register */
if(rslt != BMI055_OK)
return rslt;
/* Write to INT_SRC register */
reg_addr = BMI055_GYRO_0_REG;
rslt = bmi055_get_gyro_regs(reg_addr, &data, 1, dev);
if (rslt != BMI055_OK)
return rslt;
temp = data & ~BMI055_GYR_SRC_HIGHRATE_MASK;
data = temp | ((0 << 3) & BMI055_GYR_SRC_HIGHRATE_MASK);// Adding data source for High-rate Interrupt
rslt = bmi055_set_gyro_regs(reg_addr, &data, 1, dev);
if (rslt != BMI055_OK)
return rslt;
/* Configuring High rate Interrupt registers */
reg_addr = BMI055_GYR_INT_HR_0_ADDR;
/* Adding High-rate interrupt for x-axis, High-rate threshold for x-axis and high-rate hysteresis for x-axis */
data_array[0] = (high_rate_int->high_en_x | (high_rate_int->high_thr_x << 1) | (high_rate_int->high_hy_x << 6));
/* Adding High-rate duration for x-axis */
data_array[1] = high_rate_int->high_dur_x;
/* Adding High-rate interrupt for y-axis, High-rate threshold for y-axis and high-rate hysteresis for y-axis */
data_array[2] = (high_rate_int->high_en_y | (high_rate_int->high_thr_y << 1) | (high_rate_int->high_hy_y << 6));
/* Adding High-rate duration for y-axis */
data_array[3] = high_rate_int->high_dur_y;
/* Adding High-rate interrupt for z-axis, High-rate threshold for z-axis and high-rate hysteresis for z-axis */
data_array[4] = (high_rate_int->high_en_z | (high_rate_int->high_thr_z << 1) | (high_rate_int->high_hy_z << 6));
/* Adding High-rate duration for z-axis */
data_array[5] = high_rate_int->high_dur_z;
/* Writing data to High-rate interrupt registers simultaneously since required registers are located consecutively */
rslt = bmi055_set_gyro_regs(reg_addr, data_array, 6, dev);
dev->delay_ms(2);
return rslt;
}
/*!
* @brief This API sets the data ready interrupt for gyro.
* This interrupt occurs when new z-axis gyro data comes.
*/
static int8_t set_gyro_data_ready_int(struct bmi055_int_sett *int_config, struct bmi055_dev *dev)
{
int8_t rslt = BMI055_OK;
uint8_t reg_addr, data = 0, temp = 0;
/* Null-pointer check */
if ((dev == NULL) || (dev->read == NULL) || (dev->write == NULL) || (dev->delay_ms == NULL) || ((int_config == NULL)))
return BMI055_E_NULL_PTR;
/* Writing data to Int Enable 0 register */
reg_addr = BMI055_GYR_INT_EN_0_ADDR;
rslt = bmi055_get_gyro_regs(reg_addr, &data, 1, dev);
if (rslt != BMI055_OK)
return rslt;
temp = data & ~BMI055_GYR_DATA_INT_EN_0_MASK;
data = temp | ((1 << 7) & BMI055_GYR_DATA_INT_EN_0_MASK);// Adding new data interrupt flag
rslt = bmi055_set_gyro_regs(reg_addr, &data, 1, dev);/* write data to Int Enable 0 register */
if(rslt != BMI055_OK)
return rslt;
/* Configuring interrupt pins */
rslt = set_int_pin_config(int_config, dev);
if (rslt != BMI055_OK)
return rslt;
/* Configure Int Map register to map interrupt pin to new data interrupt */
reg_addr = BMI055_GYR_INT_MAP_1_ADDR;
rslt = bmi055_get_gyro_regs(reg_addr, &data, 1, dev);
if (rslt != BMI055_OK)
return rslt;
if (int_config->gyr_int_channel == BMI055_INT_CHANNEL_3) {
temp = data & ~BMI055_GYR_INT1_MAP_1_DATA_MASK;
data = temp | (1 & BMI055_GYR_INT1_MAP_1_DATA_MASK);//Mapping INT3 pin to new data interrupt
}
else {
temp = data & ~BMI055_GYR_INT2_MAP_1_DATA_MASK;
data = temp | ((1 << 7) & BMI055_GYR_INT2_MAP_1_DATA_MASK);//Mapping INT4 pin to new data interrupt
}
rslt = bmi055_set_gyro_regs(reg_addr, &data, 1, dev);/* write to Map register */
return rslt;
}
/*!
* @brief This API sets the auto-offset tap interrupt for gyro.
*/
static int8_t set_gyro_auto_offset_tap_int(struct bmi055_int_sett *int_config, struct bmi055_dev *dev)
{
int8_t rslt = BMI055_OK;
uint8_t reg_addr, data, temp;
/* Null-pointer check */
if ((dev == NULL) || (dev->read == NULL) || (dev->write == NULL) || (dev->delay_ms == NULL) || ((int_config == NULL)))
return BMI055_E_NULL_PTR;
/* updating the interrupt structure to local structure */
struct bmi055_gyr_auto_offset_int_cfg *auto_offset_int = &(int_config->int_type_cfg.gyr_auto_offset_int);
/* Writing data to Int Enable 0 register */
reg_addr = BMI055_GYR_INT_EN_0_ADDR;
rslt = bmi055_get_gyro_regs(reg_addr, &data, 1, dev);
if (rslt != BMI055_OK)
return rslt;
temp = data & ~BMI055_GYR_AUTO_OFF_INT_EN_0_MASK;
data = temp | ((1 << 2) & BMI055_GYR_AUTO_OFF_INT_EN_0_MASK);// Adding auto-offset flag
rslt = bmi055_set_gyro_regs(reg_addr, &data, 1, dev);/* write data to Int Enable 0 register */
if(rslt != BMI055_OK)
return rslt;
/* Configuring interrupt pins */
rslt = set_int_pin_config(int_config, dev);
if (rslt != BMI055_OK)
return rslt;
/* Configure Int Map register to map interrupt pin to new data interrupt */
reg_addr = BMI055_GYR_INT_MAP_1_ADDR;
rslt = bmi055_get_gyro_regs(reg_addr, &data, 1, dev);
if (rslt != BMI055_OK)
return rslt;
if (int_config->gyr_int_channel == BMI055_INT_CHANNEL_3) {
temp = data & ~BMI055_GYR_INT1_MAP_1_AUTO_OFF_MASK;
data = temp | ((1 << 3) & BMI055_GYR_INT1_MAP_1_AUTO_OFF_MASK);//Mapping INT3 pin to auto-offset interrupt
}
else {
temp = data & ~BMI055_GYR_INT2_MAP_1_AUTO_OFF_MASK;
data = temp | ((1 << 4) & BMI055_GYR_INT2_MAP_1_AUTO_OFF_MASK);//Mapping INT4 pin to auto-offset interrupt
}
rslt = bmi055_set_gyro_regs(reg_addr, &data, 1, dev);/* write to Map register */
if(rslt != BMI055_OK)
return rslt;
/* Writing data to register to configure auto-offset word length */
reg_addr = BMI055_GYR_A_FOC_ADDR;
rslt = bmi055_get_gyro_regs(reg_addr, &data, 1, dev);
if (rslt != BMI055_OK)
return rslt;
temp = data & ~BMI055_GYR_AUTO_OFF_WORD_LEN_MASK;
data = temp | ((auto_offset_int->auto_offset_wordlen << 6) & BMI055_GYR_AUTO_OFF_WORD_LEN_MASK);// Adding auto-offset word length
rslt = bmi055_set_gyro_regs(reg_addr, &data, 1, dev);/* write data to register */
return rslt;
}
/*!
* @brief This API sets the slow-offset interrupt for gyro.
*/
static int8_t set_gyro_slow_offset_int(struct bmi055_int_sett *int_config, struct bmi055_dev *dev)
{
int8_t rslt = BMI055_OK;
uint8_t reg_addr, data, temp;
/* Null-pointer check */
if ((dev == NULL) || (dev->read == NULL) || (dev->write == NULL) || (dev->delay_ms == NULL) || ((int_config == NULL)))
return BMI055_E_NULL_PTR;
/* updating the interrupt structure to local structure */
struct bmi055_gyr_slow_offset_int_cfg *gyr_slow_offset_int = &(int_config->int_type_cfg.gyr_slow_offset_int);
/* Configuring interrupt pins */
rslt = set_int_pin_config(int_config, dev);
if (rslt != BMI055_OK)
return rslt;
/* Write to data source register */
reg_addr = BMI055_GYRO_0_REG;
rslt = bmi055_get_gyro_regs(reg_addr, &data, 1, dev);
if (rslt != BMI055_OK)
return rslt;
temp = data & ~BMI055_GYR_SRC_SLOW_OFFSET_MASK;
data = temp | ((0 << 5) & BMI055_GYR_SRC_SLOW_OFFSET_MASK);// Adding data source for slow-offset interrupt
rslt = bmi055_set_gyro_regs(reg_addr, &data, 1, dev);//Writing data to src register
if (rslt != BMI055_OK)
return rslt;
/* Configuring Slow-offset register */
reg_addr = BMI055_GYR_SOC_ADDR;
rslt = bmi055_get_gyro_regs(reg_addr, &data, 1, dev);
if (rslt != BMI055_OK)
return rslt;
temp = data & ~BMI055_GYR_SLOW_OFF_EN_X_MASK;
data = temp | (gyr_slow_offset_int->slow_offset_en_x & BMI055_GYR_SLOW_OFF_EN_X_MASK);// Adding slow-offset x-axis flag
temp = data & ~BMI055_GYR_SLOW_OFF_EN_Y_MASK;
data = temp | ((gyr_slow_offset_int->slow_offset_en_y << 1) & BMI055_GYR_SLOW_OFF_EN_Y_MASK);// Adding slow-offset y-axis flag
temp = data & ~BMI055_GYR_SLOW_OFF_EN_Z_MASK;
data = temp | ((gyr_slow_offset_int->slow_offset_en_z << 2) & BMI055_GYR_SLOW_OFF_EN_Z_MASK);// Adding slow-offset z-axis flag
temp = data & ~BMI055_GYR_SLOW_OFF_DUR_MASK;
data = temp | ((gyr_slow_offset_int->slow_offset_dur << 3) & BMI055_GYR_SLOW_OFF_DUR_MASK);// Adding slow-offset duration
temp = data & ~BMI055_GYR_SLOW_OFF_THR_MASK;
data = temp | ((gyr_slow_offset_int->slow_offset_thres << 6) & BMI055_GYR_SLOW_OFF_THR_MASK);// Adding slow-offset threshold
rslt = bmi055_set_gyro_regs(reg_addr, &data, 1, dev);//writing data to slow-offset register
return rslt;
}
/*!
* @brief This API sets the fast-offset interrupt for gyro.
*/
static int8_t set_gyro_fast_offset_int(struct bmi055_int_sett *int_config, struct bmi055_dev *dev)
{
int8_t rslt = BMI055_OK;
uint8_t reg_addr, data, temp;
/* Null-pointer check */
if ((dev == NULL) || (dev->read == NULL) || (dev->write == NULL) || (dev->delay_ms == NULL) || ((int_config == NULL)))
return BMI055_E_NULL_PTR;
/* updating the interrupt structure to local structure */
struct bmi055_gyr_fast_offset_int_cfg *gyr_fast_offset_int = &(int_config->int_type_cfg.gyr_fast_offset_int);
/* Configuring interrupt pins */
rslt = set_int_pin_config(int_config, dev);
if (rslt != BMI055_OK)
return rslt;
/* Configure Int Map register to map interrupt pin to fast-offset interrupt */
reg_addr = BMI055_GYR_INT_MAP_1_ADDR;
rslt = bmi055_get_gyro_regs(reg_addr, &data, 1, dev);
if (rslt != BMI055_OK)
return rslt;
if (int_config->gyr_int_channel == BMI055_INT_CHANNEL_3) {
temp = data & ~BMI055_GYR_INT1_MAP_1_FAST_OFF_MASK;
data = temp | ((1 << 1) & BMI055_GYR_INT1_MAP_1_FAST_OFF_MASK);//Mapping INT3 pin to fast-offset interrupt
}
else {
temp = data & ~BMI055_GYR_INT2_MAP_1_FAST_OFF_MASK;
data = temp | ((1 << 6) & BMI055_GYR_INT2_MAP_1_FAST_OFF_MASK);//Mapping INT4 pin to fast-offset interrupt
}
rslt = bmi055_set_gyro_regs(reg_addr, &data, 1, dev);/* write to Map register */
if(rslt != BMI055_OK)
return rslt;
/* Write to data source register */
reg_addr = BMI055_GYRO_1_REG;
rslt = bmi055_get_gyro_regs(reg_addr, &data, 1, dev);
if (rslt != BMI055_OK)
return rslt;
temp = data & ~BMI055_GYR_SRC_FAST_OFFSET_MASK;
data = temp | ((0 << 7) & BMI055_GYR_SRC_FAST_OFFSET_MASK);// Adding data source for fast-offset interrupt
rslt = bmi055_set_gyro_regs(reg_addr, &data, 1, dev);//Writing to data source register
if (rslt != BMI055_OK)
return rslt;
/* Configuring fast-offset register */
reg_addr = BMI055_GYR_A_FOC_ADDR;
rslt = bmi055_get_gyro_regs(reg_addr, &data, 1, dev);
if(rslt != BMI055_OK)
return rslt;
temp = data & ~BMI055_GYR_FAST_OFF_EN_X_MASK;
data = temp | (gyr_fast_offset_int->fast_offset_en_x & BMI055_GYR_FAST_OFF_EN_X_MASK);// Adding fast-offset enable x-axis
temp = data & ~BMI055_GYR_FAST_OFF_EN_Y_MASK;
data = temp | ((gyr_fast_offset_int->fast_offset_en_y << 1) & BMI055_GYR_FAST_OFF_EN_Y_MASK);// Adding fast-offset enable y-axis
temp = data & ~BMI055_GYR_FAST_OFF_EN_Z_MASK;
data = temp | ((gyr_fast_offset_int->fast_offset_en_z << 2) & BMI055_GYR_FAST_OFF_EN_Z_MASK);// Adding fast-offset enable z-axis
temp = data & ~BMI055_GYR_FAST_OFF_EN_MASK;
data = temp | ((gyr_fast_offset_int->fast_offset_en << 3) & BMI055_GYR_FAST_OFF_EN_MASK);// Adding fast-offset enable
temp = data & ~BMI055_GYR_FAST_OFF_WORD_LEN_MASK;
data = temp | ((gyr_fast_offset_int->fast_offset_wordlen << 4) & BMI055_GYR_FAST_OFF_WORD_LEN_MASK);// Adding fast-offset word length
rslt = bmi055_set_gyro_regs(reg_addr, &data, 1, dev);/* write data to fast-offset register */
return rslt;
}
/*!
* @brief This API configures the pins to fire the
* interrupt signal when it occurs.
*/
static int8_t set_int_pin_config(struct bmi055_int_sett *int_config, struct bmi055_dev *dev)
{
int8_t rslt = BMI055_OK;
uint8_t reg_addr, data, temp;
/* updating the interrupt structure to local structure */
struct bmi055_int_pin_sett *int_pin_cfg = &(int_config->int_pin_sett);
/* Configuration of output interrupt signals on pins INT1 and INT2 are done in Int Enable 1 register*/
reg_addr = BMI055_GYR_INT_EN_1_ADDR;
rslt = bmi055_get_gyro_regs(reg_addr, &data, 1, dev);
if (rslt != BMI055_OK)
return rslt;
if (int_config->gyr_int_channel == BMI055_INT_CHANNEL_3) {
temp = data & ~BMI055_GYR_INT1_LVL_INT_EN_1_MASK;
data = temp | (int_pin_cfg->output_type & BMI055_GYR_INT1_LVL_INT_EN_1_MASK);// Adding output_type to INT3 pin
temp = data & ~BMI055_GYR_INT1_OD_INT_EN_1_MASK;
data = temp | ((int_pin_cfg->output_mode << 1) & BMI055_GYR_INT1_OD_INT_EN_1_MASK);// Adding output_mode to INT3 pin
}
else {
temp = data & ~BMI055_GYR_INT2_LVL_INT_EN_1_MASK;
data = temp | ((int_pin_cfg->output_type << 2) & BMI055_GYR_INT2_LVL_INT_EN_1_MASK);// Adding output_type to INT4 pin
temp = data & ~BMI055_GYR_INT2_OD_INT_EN_1_MASK;
data = temp | ((int_pin_cfg->output_mode << 3) & BMI055_GYR_INT2_OD_INT_EN_1_MASK);// Adding output_mode to INT4 pin
}
/* Write to Int Enable 1 register */
rslt = bmi055_set_gyro_regs(reg_addr, &data, 1, dev);
if (rslt != BMI055_OK)
return rslt;
/* Configuring INT_RST_LATCH register */
reg_addr = BMI055_GYR_INT_LATCH_ADDR;
rslt = bmi055_get_gyro_regs(reg_addr, &data, 1, dev);
if (rslt != BMI055_OK)
return rslt;
temp = data & ~BMI055_GYR_LATCH_DUR_MASK;
data = temp | ((int_pin_cfg->latch_dur) & BMI055_GYR_LATCH_DUR_MASK);// Adding Latch duration
temp = data & ~BMI055_GYR_RESET_INT_MASK;
data = temp | ((int_pin_cfg->reset_int << 7) & BMI055_GYR_RESET_INT_MASK);// Adding reset_int
// Adding Offset_reset in case of auto-offset, slow-offset and fast-offset interrupts
if ((int_config->gyr_int_type == BMI055_GYRO_AUTO_OFFSET_INT) || (int_config->gyr_int_type == BMI055_GYRO_SLOW_OFFSET_INT)
|| (int_config->gyr_int_type == BMI055_GYRO_FAST_OFFSET_INT)) {
temp = data & ~BMI055_GYR_OFFSET_RESET_MASK;
data = temp | ((int_pin_cfg->offset_reset << 6) & BMI055_GYR_OFFSET_RESET_MASK);
}
/* Write to INT_RST_LATCH register */
rslt = bmi055_set_gyro_regs(reg_addr, &data, 1, dev);
return rslt;
}
#endif
/** @}*/
/*
****************************************************************************
* Copyright (C) 2015 - 2016 Bosch Sensortec GmbH
*
* File :bmi088_accel.c
*
* Date: 30 Oct 2017
*
* Revision:
*
* Usage: Sensor Driver for BMI088 family of sensors
*
****************************************************************************
* Disclaimer
*
* Common:
* Bosch Sensortec products are developed for the consumer goods industry.
* They may only be used within the parameters of the respective valid
* product data sheet. Bosch Sensortec products are provided with the
* express understanding that there is no warranty of fitness for a
* particular purpose.They are not fit for use in life-sustaining,
* safety or security sensitive systems or any system or device
* that may lead to bodily harm or property damage if the system
* or device malfunctions. In addition,Bosch Sensortec products are
* not fit for use in products which interact with motor vehicle systems.
* The resale and or use of products are at the purchasers own risk and
* his own responsibility. The examination of fitness for the intended use
* is the sole responsibility of the Purchaser.
*
* The purchaser shall indemnify Bosch Sensortec from all third party
* claims, including any claims for incidental, or consequential damages,
* arising from any product use not covered by the parameters of
* the respective valid product data sheet or not approved by
* Bosch Sensortec and reimburse Bosch Sensortec for all costs in
* connection with such claims.
*
* The purchaser must monitor the market for the purchased products,
* particularly with regard to product safety and inform Bosch Sensortec
* without delay of all security relevant incidents.
*
* Engineering Samples are marked with an asterisk (*) or (e).
* Samples may vary from the valid technical specifications of the product
* series. They are therefore not intended or fit for resale to third
* parties or for use in end products. Their sole purpose is internal
* client testing. The testing of an engineering sample may in no way
* replace the testing of a product series. Bosch Sensortec assumes
* no liability for the use of engineering samples.
* By accepting the engineering samples, the Purchaser agrees to indemnify
* Bosch Sensortec from all claims arising from the use of engineering
* samples.
*
* Special:
* This software module (hereinafter called "Software") and any information
* on application-sheets (hereinafter called "Information") is provided
* free of charge for the sole purpose to support your application work.
* The Software and Information is subject to the following
* terms and conditions:
*
* The Software is specifically designed for the exclusive use for
* Bosch Sensortec products by personnel who have special experience
* and training. Do not use this Software if you do not have the
* proper experience or training.
*
* This Software package is provided `` as is `` and without any expressed
* or implied warranties,including without limitation, the implied warranties
* of merchantability and fitness for a particular purpose.
*
* Bosch Sensortec and their representatives and agents deny any liability
* for the functional impairment
* of this Software in terms of fitness, performance and safety.
* Bosch Sensortec and their representatives and agents shall not be liable
* for any direct or indirect damages or injury, except as
* otherwise stipulated in mandatory applicable law.
*
* The Information provided is believed to be accurate and reliable.
* Bosch Sensortec 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 Bosch. Specifications mentioned in the Information are
* subject to change without notice.
**************************************************************************/
/*! \file bmi088_accel.c
\brief Sensor Driver for BMI088 family of sensors */
/***************************************************************************/
/**\name Header files
****************************************************************************/
#include "bmi088.h"
/***************************************************************************/
/**\name Local structures
****************************************************************************/
/***************************************************************************/
/*! Static Function Declarations
****************************************************************************/
/*!
* @brief This API is used to validate the device structure pointer for
* null conditions.
*
* @param[in] dev : Structure instance of bmi088_dev.
*
* @return Result of API execution status
* @retval zero -> Success
* @retval Any non zero value -> Fail
*/
static uint16_t null_ptr_check(struct bmi088_dev *dev);
/*!
* @brief This API configures the pins which fire the
* interrupt signal when any interrupt occurs.
*
* @param[in] int_config : Structure instance of bmi088_int_cfg.
* @param[in] dev : Structure instance of bmi088_dev.
*
* @return Result of API execution status
* @retval zero -> Success
* @retval Any non zero value -> Fail
*/
static uint16_t set_int_pin_config(const struct bmi088_int_cfg *int_config, struct bmi088_dev *dev);
/*!
* @brief This API sets the data ready interrupt for accel sensor
*
* @param[in] int_config : Structure instance of bmi088_int_cfg.
* @param[in] dev : Structure instance of bmi088_dev.
*
* @return Result of API execution status
* @retval zero -> Success
* @retval Any non zero value -> Fail
*/
static uint16_t set_accel_data_ready_int(const struct bmi088_int_cfg *int_config, struct bmi088_dev *dev);
/*!
* @brief This API writes the config stream data in memory using burst mode
*
* @param[in] stream_data : Pointer to store data of 32 bytes
* @param[in] index : Represents value in multiple of 32 bytes
* @param[in] dev : Structure instance of bmi088_dev.
*
* @return Result of API execution status
* @retval 0 -> Success
* @retval Any non zero value -> Fail
*/
static uint16_t stream_transfer_write(const uint8_t *stream_data, uint16_t index, struct bmi088_dev *dev);
/*!
* @brief This function enables and configures the Accel which is needed
* for Self test operation.
*
* @param[in] dev : Structure instance of bmi088_dev
*
* @return results of self test
* @retval zero -> Success
* @retval Any non zero value -> Fail
*/
static uint16_t set_accel_selftest_config(struct bmi088_dev *dev);
/*!
* @brief This function validates the Accel Self test data and decides the
* result of Self test operation.
*
* @param[in] accel_data_diff : Pointer to structure variable which holds
* the Accel data difference of Self test operation
*
* @return results of self test operation
* @retval zero -> Success
* @retval Any non zero value -> Fail
*/
static uint16_t validate_selftest(const struct bmi088_sensor_data *accel_data_diff);
/*!
* @brief This API converts lsb value of axes to mg for self-test
*
* @param[in] accel_data_diff : Pointer variable used to pass accel difference
* values in g
* @param[out] accel_data_diff_mg : Pointer variable used to store accel
* difference values in mg
*
* @return None
*/
static void convert_lsb_g(const struct bmi088_sensor_data *accel_data_diff,
struct bmi088_sensor_data *accel_data_diff_mg);
/*!
* @brief This API is used to calculate the power of given
* base value.
*
* @param[in] base : value of base
* @param[in] resolution : resolution of the sensor
*
* @return : returns the value of base^resolution
*/
static int32_t power(int16_t base, uint8_t resolution);
/***************************************************************************/
/**\name Extern Declarations
****************************************************************************/
/***************************************************************************/
/**\name Globals
****************************************************************************/
/* Copy of accel_cfg structure of device structure.It
* prevents overwriting same accel configuration data */
static struct bmi088_cfg accel_cfg_copy;
/***************************************************************************/
/**\name Function definitions
****************************************************************************/
/*!
* @brief This API is the entry point for accel sensor.
* It performs the selection of I2C/SPI read mechanism according to the
* selected interface and reads the chip-id of accel sensor.
*/
uint16_t bmi088_accel_init(struct bmi088_dev *dev)
{
uint16_t rslt = BMI088_OK;
uint8_t data = 0, reg_addr;
/* Check for null pointer in the device structure*/
rslt = null_ptr_check(dev);
/* Proceed if null check is fine */
if (rslt == BMI088_OK)
{
if (dev->interface == BMI088_SPI_INTF)
{
/* Set dummy byte in case of SPI interface*/
dev->dummy_byte = 1;
}
else
{
/* Make dummy byte 0 in case of I2C interface*/
dev->dummy_byte = 0;
}
reg_addr = BMI088_ACCEL_CHIP_ID_REG;
rslt |= bmi088_get_accel_regs(reg_addr, &data, BMI088_ONE, dev);
if (rslt == BMI088_OK)
{
/* Assign Chip Id */
dev->accel_chip_id = data;
/* Initializing accel sensor parameters with default values */
dev->accel_cfg.bw = BMI088_ACCEL_ODR_100_HZ;
dev->accel_cfg.power = BMI088_ACCEL_PM_SUSPEND;
dev->accel_cfg.range = BMI088_ACCEL_RANGE_6G;
/* Copying accel_cfg parameters of device structure to
* accel_cfg_copy structure to maintain a copy */
accel_cfg_copy.bw = dev->accel_cfg.bw;
accel_cfg_copy.power = dev->accel_cfg.power;
accel_cfg_copy.range = dev->accel_cfg.range;
}
else
{
rslt = BMI088_E_COM_FAIL;
}
}
return rslt;
}
/*!
* @brief This API is used to write the binary configuration in the sensor.
*/
uint16_t bmi088_write_config_file(struct bmi088_dev *dev)
{
uint16_t rslt = 0;
/* Disable advance power save*/
uint8_t adv_power_save = 0, reg_addr;
/* Config loading disable*/
uint8_t config_load = BMI088_DISABLE;
uint16_t index = 0;
uint8_t config_stream_status = 0;
reg_addr = BMI088_ACCEL_PWR_CONF_REG;
/* Disable advanced power save*/
rslt |= bmi088_set_accel_regs(reg_addr, &adv_power_save, BMI088_ONE, dev);
/* Wait for sensor time synchronization. Refer the data-sheet for
more information*/
dev->delay_ms(BMI088_ONE);
if (rslt == BMI088_OK)
{
reg_addr = BMI088_ACCEL_INIT_CTRL_REG;
/* Disable config loading*/
rslt |= bmi088_set_accel_regs(reg_addr, &config_load, BMI088_ONE, dev);
/* Write the config stream */
for (index = 0; index < BMI088_CONFIG_STREAM_SIZE; index += dev->read_write_len)
{
rslt |= stream_transfer_write((dev->config_file_ptr + index), index, dev);
}
/* Enable config loading and FIFO mode */
config_load = BMI088_ENABLE;
rslt |= bmi088_set_accel_regs(reg_addr, &config_load, BMI088_ONE, dev);
/* Wait till ASIC is initialized. Refer the data-sheet for
more information*/
dev->delay_ms(BMI088_ONE_FIFTY);
reg_addr = BMI088_ACCEL_INTERNAL_STAT_REG;
/* Read the status of config stream operation */
rslt |= bmi088_get_accel_regs(reg_addr, &config_stream_status, BMI088_ONE, dev);
if (config_stream_status != BMI088_ASIC_INITIALIZED)
{
rslt |= BMI088_E_CONFIG_STREAM_ERROR;
}
}
return rslt;
}
/*!
* @brief This API reads the data from the given register address of accel sensor.
*/
uint16_t bmi088_get_accel_regs(uint8_t reg_addr, uint8_t *data, uint16_t len,
struct bmi088_dev *dev)
{
/* variable used to return the status of communication result*/
uint16_t rslt = BMI088_OK;
uint16_t temp_len = len + dev->dummy_byte;
uint16_t i;
uint8_t temp_buff[temp_len];
/* Check for null pointer in the device structure*/
rslt = null_ptr_check(dev);
/* Proceed if null check is fine */
if (rslt == BMI088_OK)
{
/* Configuring reg_addr for SPI Interface */
if (dev->interface == BMI088_SPI_INTF)
{
reg_addr = reg_addr | BMI088_SPI_RD_MASK;
}
/* Read the data from the register */
rslt |= dev->read(dev->accel_id, reg_addr, temp_buff, temp_len);
for (i = 0; i < len; i++)
{
data[i] = temp_buff[i + dev->dummy_byte];
}
}
return rslt;
}
/*!
* @brief This API writes the given data to the register address
* of accel sensor.
*/
uint16_t bmi088_set_accel_regs(uint8_t reg_addr, uint8_t *data, uint16_t len,
struct bmi088_dev *dev)
{
uint16_t rslt = BMI088_OK;
/* Check for null pointer in the device structure*/
rslt = null_ptr_check(dev);
/* Proceed if null check is fine */
if ((rslt == BMI088_OK) && (data != NULL) && (len != 0))
{
/* Configuring reg_addr for SPI Interface */
if (dev->interface == BMI088_SPI_INTF)
{
reg_addr = (reg_addr & BMI088_SPI_WR_MASK);
}
/* write to an accel register */
rslt = dev->write(dev->accel_id, reg_addr, data, len);
if (rslt != BMI088_OK)
{
rslt = BMI088_E_COM_FAIL;
}
}
return rslt;
}
/*!
* @brief This API reads the error status from the accel sensor.
*/
uint16_t bmi088_get_accel_error_status(struct bmi088_err_reg *err_reg, struct bmi088_dev *dev)
{
uint16_t rslt = 0;
uint8_t data = 0, reg_addr;
/* Check for null pointer in the device structure*/
rslt = null_ptr_check(dev);
/* Proceed if null check is fine */
if (rslt == BMI088_OK)
{
reg_addr = BMI088_ACCEL_ERR_REG;
/* Read the error codes */
rslt = bmi088_get_accel_regs(reg_addr, &data, BMI088_ONE, dev);
if (rslt == BMI088_OK)
{
/* Fatal error */
err_reg->fatal_err = BMI088_GET_BITSLICE(data, BMI088_FATAL_ERR);
/* Cmd error */
err_reg->cmd_err = BMI088_GET_BITSLICE(data, BMI088_CMD_ERR);
/* User error */
err_reg->err_code = BMI088_GET_BITSLICE(data, BMI088_ERR_CODE);
}
}
return rslt;
}
/*!
* @brief This API reads the status of the accel sensor.
*/
uint16_t bmi088_get_accel_status(uint8_t *status, struct bmi088_dev *dev)
{
uint16_t rslt = 0;
uint8_t data = 0, reg_addr;
/* Check for null pointer in the device structure*/
rslt = null_ptr_check(dev);
/* Proceed if null check is fine */
if (rslt == BMI088_OK)
{
reg_addr = BMI088_ACCEL_STATUS_REG;
/* Read the status */
rslt = bmi088_get_accel_regs(reg_addr, &data, BMI088_ONE, dev);
if (rslt == BMI088_OK)
{
*status = data;
}
}
return rslt;
}
/*!
* @brief This API resets the accel sensor.
*/
uint16_t bmi088_accel_soft_reset(struct bmi088_dev *dev)
{
uint16_t rslt = BMI088_OK;
uint8_t reg_addr, data;
/* Check for null pointer in the device structure*/
rslt = null_ptr_check(dev);
/* Proceed if null check is fine */
if (rslt == BMI088_OK)
{
reg_addr = BMI088_ACCEL_SOFTRESET_REG;
data = BMI088_SOFT_RESET_VAL;
/* Reset accel device */
rslt = bmi088_set_accel_regs(reg_addr, &data, BMI088_ONE, dev);
if (rslt == BMI088_OK)
{
/* Delay 1 ms after reset value is written to its register */
dev->delay_ms(BMI088_ACCEL_SOFTRESET_DELAY);
}
}
return rslt;
}
/*!
* @brief This API sets the output data rate, range and bandwidth
* of accel sensor.
*/
uint16_t bmi088_set_accel_meas_conf(struct bmi088_dev *dev)
{
uint16_t rslt = BMI088_OK;
uint8_t reg_addr, data;
uint8_t bw, range, odr;
bool is_odr_invalid = false, is_bw_invalid = false, is_range_invalid = false;
/* Check for null pointer in the device structure*/
rslt = null_ptr_check(dev);
/* Proceed if null check is fine */
if (rslt == BMI088_OK)
{
odr = dev->accel_cfg.odr;
bw = dev->accel_cfg.bw;
range = dev->accel_cfg.range;
/* Check if odr and bandwidth are not previously configured odr and bandwidth */
if ((odr != accel_cfg_copy.odr) || (bw != accel_cfg_copy.bw))
{
/* Check for valid odr */
if ((odr < BMI088_ACCEL_ODR_12_5_HZ) || (odr > BMI088_ACCEL_ODR_1600_HZ))
{
is_odr_invalid = true;
/* Since odr and bandwidth are written to the same
* register, use previous odr in case of invalid ODR.
* This will be helpful if valid bandwidth arrives */
odr = accel_cfg_copy.odr;
}
/* Check for valid bandwidth */
if (bw > BMI088_ACCEL_BW_NORMAL)
{
is_bw_invalid = true;
/* Since bandwidth and odr are written to the same
* register, use previous bandwidth in case of
* invalid bandwidth.This will be helpful if valid
* odr arrives */
bw = accel_cfg_copy.bw;
}
/* If either odr or bw is valid, write it to accel config. registers */
if ((!is_odr_invalid) || (!is_bw_invalid))
{
reg_addr = BMI088_ACCEL_CONF_REG;
/* Read accel config. register */
rslt = bmi088_get_accel_regs(reg_addr, &data, BMI088_ONE, dev);
if (rslt == BMI088_OK)
{
/* Update data with new odr and bw values */
data = BMI088_SET_BITSLICE(data, BMI088_ACCEL_ODR, odr);
data = BMI088_SET_BITSLICE(data, BMI088_ACCEL_BW, bw);
/* write to accel config. register */
rslt = bmi088_set_accel_regs(reg_addr, &data, BMI088_ONE, dev);
/* If rslt is ok, copy the current odr
* and bw to accel_cfg_copy structure to
* maintain a copy */
if (rslt == BMI088_OK)
{
accel_cfg_copy.odr = odr;
accel_cfg_copy.bw = bw;
}
}
}
}
/* Check if range is not previously configured range */
if (range != accel_cfg_copy.range)
{
/* Check if range is valid */
if (range <= BMI088_ACCEL_RANGE_24G)
{
reg_addr = BMI088_ACCEL_RANGE_REG;
/* Read range register */
rslt = bmi088_get_accel_regs(reg_addr, &data, BMI088_ONE, dev);
if (rslt == BMI088_OK)
{
/* Update data with current range values */
data = BMI088_SET_BITSLICE(data, BMI088_ACCEL_RANGE, range);
/* write to range register */
rslt = bmi088_set_accel_regs(reg_addr, &data, BMI088_ONE, dev);
/* If rslt is ok, copy the current range
* to accel_cfg_copy structure to
* maintain a copy */
if (rslt == BMI088_OK)
{
accel_cfg_copy.range = range;
}
}
}
else
{
/* Range is invalid */
is_range_invalid = true;
}
}
}
/* If invalid odr or bw or range arrive, make rslt invalid input */
if (is_odr_invalid || is_bw_invalid || is_range_invalid)
{
rslt = BMI088_E_INVALID_INPUT;
}
return rslt;
}
/*!
* @brief This API sets the power mode of the accel sensor.
*/
uint16_t bmi088_set_accel_power_mode(struct bmi088_dev *dev)
{
uint16_t rslt = BMI088_OK;
uint8_t reg_addr, power;
uint8_t data[2];
/* Check for null pointer in the device structure*/
rslt = null_ptr_check(dev);
/* Proceed if null check is fine */
if (rslt == BMI088_OK)
{
power = dev->accel_cfg.power;
/* Check if current power is not previously configured power */
if (power != accel_cfg_copy.power)
{
/* Configure data array to write to accel power configuration register */
if (power == BMI088_ACCEL_PM_ACTIVE)
{
data[0] = BMI088_ACCEL_PM_ACTIVE;
data[1] = BMI088_ACCEL_POWER_ENABLE;
}
else if (power == BMI088_ACCEL_PM_SUSPEND)
{
data[0] = BMI088_ACCEL_PM_SUSPEND;
data[1] = BMI088_ACCEL_POWER_DISABLE;
}
else
{
/* Invalid power input */
rslt = BMI088_E_INVALID_INPUT;
}
if (rslt == BMI088_OK)
{
reg_addr = BMI088_ACCEL_PWR_CONF_REG;
/* write to accel power configuration register */
rslt = bmi088_set_accel_regs(reg_addr, data, BMI088_TWO, dev);
/* If rslt is ok, copy the current power
* to accel_cfg_copy structure to maintain
* a copy */
if (rslt == BMI088_OK)
{
accel_cfg_copy.power = power;
}
}
}
}
return rslt;
}
/*!
* @brief This API reads the accel data from the sensor,
* store it in the bmi088_sensor_data structure instance
* passed by the user.
*/
uint16_t bmi088_get_accel_data(struct bmi088_sensor_data *accel,
struct bmi088_dev *dev)
{
uint16_t rslt = BMI088_OK;
uint8_t index = 0, reg_addr, data[6];
uint32_t lsb, msb, msblsb;
/* Check for null pointer in the device structure*/
rslt = null_ptr_check(dev);
/* Proceed if null check is fine */
if ((rslt == BMI088_OK) && (accel != NULL))
{
/* Read accel sensor data */
reg_addr = BMI088_ACCEL_X_LSB_REG;
rslt = bmi088_get_accel_regs(reg_addr, data, BMI088_SIX, dev);
if (rslt == BMI088_OK)
{
lsb = (uint32_t)data[index++];
msb = (uint32_t)data[index++];
msblsb = (msb << BMI088_EIGHT) | lsb;
accel->x = ((int16_t)msblsb); /* Data in X axis */
lsb = (uint32_t)data[index++];
msb = (uint32_t)data[index++];
msblsb = (msb << BMI088_EIGHT) | lsb;
accel->y = ((int16_t)msblsb); /* Data in Y axis */
lsb = (uint32_t)data[index++];
msb = (uint32_t)data[index++];
msblsb = (msb << BMI088_EIGHT) | lsb;
accel->z = ((int16_t)msblsb); /* Data in Z axis */
}
}
return rslt;
}
/*!
* @brief This API configures the necessary accel interrupt
* based on the user settings in the bmi088_int_cfg
* structure instance.
*/
uint16_t bmi088_set_accel_int_config(const struct bmi088_int_cfg *int_config, struct bmi088_dev *dev)
{
uint16_t rslt = BMI088_OK;
switch (int_config->accel_int_type)
{
case BMI088_ACCEL_DATA_RDY_INT:
{
/* Data ready interrupt */
rslt = set_accel_data_ready_int(int_config, dev);
}
break;
default:
break;
}
return rslt;
}
/*!
* @brief This API switches accel sensor on or off.
*/
uint16_t bmi088_accel_switch_control(struct bmi088_dev *dev, uint8_t switch_input)
{
uint16_t rslt = BMI088_OK;
uint8_t reg_addr, data = switch_input;
/* Check for null pointer in the device structure*/
rslt = null_ptr_check(dev);
/* Proceed if null check is fine */
if (rslt == BMI088_OK)
{
/* Check if switch input is valid */
if ((data == BMI088_ACCEL_POWER_DISABLE) || (data == BMI088_ACCEL_POWER_ENABLE))
{
reg_addr = BMI088_ACCEL_PWR_CTRL_REG;
/* write to accel power control register */
rslt = bmi088_set_accel_regs(reg_addr, &data, BMI088_ONE, dev);
}
else
{
rslt = BMI088_E_INVALID_INPUT;
}
}
return rslt;
}
/*!
* @brief This API reads the temperature of the sensor in ° Celcius.
*/
uint16_t bmi088_get_sensor_temperature(struct bmi088_dev *dev, float *sensor_temp)
{
uint16_t rslt = BMI088_OK;
uint8_t reg_addr, data[2] = { 0 };
uint16_t msb, lsb;
int16_t msblsb;
/* Check for null pointer in the device structure*/
rslt = null_ptr_check(dev);
/* Proceed if null check is fine */
if (rslt == BMI088_OK)
{
reg_addr = BMI088_TEMP_MSB_REG;
/* Read sensor temperature */
rslt = bmi088_get_accel_regs(reg_addr, data, BMI088_TWO, dev);
if (rslt == BMI088_OK)
{
msb = (data[0] << BMI088_THREE); /* MSB data */
lsb = (data[1] >> BMI088_FIVE); /* LSB data */
msblsb = (int16_t)(msb + lsb);
if (msblsb > 1023)
{
msblsb = msblsb - 2048;
}
/* sensor temperature */
*sensor_temp = (msblsb * 0.125) + 23;
}
}
return rslt;
}
/*!
* @brief This API reads the sensor time of the sensor.
*/
uint16_t bmi088_get_sensor_time(struct bmi088_dev *dev, uint32_t *sensor_time)
{
uint16_t rslt = BMI088_OK;
uint8_t reg_addr, data[3] = { 0 };
uint32_t byte2, byte1, byte0;
/* Check for null pointer in the device structure*/
rslt = null_ptr_check(dev);
/* Proceed if null check is fine */
if (rslt == BMI088_OK)
{
reg_addr = BMI088_ACCEL_SENSORTIME_0_REG;
/* Read 3-byte sensor time */
rslt = bmi088_get_accel_regs(reg_addr, data, BMI088_THREE, dev);
if (rslt == BMI088_OK)
{
byte0 = data[0]; /* Lower byte */
byte1 = (data[1] << BMI088_EIGHT); /* Middle byte */
byte2 = (data[2] << BMI088_SIXTEEN); /* Higher byte */
/* Sensor time */
*sensor_time = (byte2 | byte1 | byte0);
}
}
return rslt;
}
/*!
* @brief This API checks whether the self test functionality of the sensor
* is working or not.
*/
uint16_t bmi088_perform_accel_selftest(int8_t *result, struct bmi088_dev *dev)
{
uint16_t rslt = BMI088_OK;
struct bmi088_sensor_data positive = { 0 };
struct bmi088_sensor_data negative = { 0 };
/*! Structure for difference of accel values in g*/
struct bmi088_sensor_data accel_data_diff = { 0 };
/*! Structure for difference of accel values in mg*/
struct bmi088_sensor_data accel_data_diff_mg = { 0 };
*result = BMI088_SELFTEST_FAIL;
/* Check for null pointer in the device structure*/
rslt = null_ptr_check(dev);
/* Proceed if null check is fine */
if (rslt == BMI088_OK)
{
rslt |= set_accel_selftest_config(dev);
dev->delay_ms(20);
rslt |= bmi088_set_accel_selftest(BMI088_ACCEL_POSITIVE_SELF_TEST, dev);
if (rslt == BMI088_OK)
{
dev->delay_ms(BMI088_HUNDRED);
rslt |= bmi088_get_accel_data(&positive, dev);
rslt |= bmi088_set_accel_selftest(BMI088_ACCEL_NEGATIVE_SELF_TEST, dev);
if (rslt == BMI088_OK)
{
dev->delay_ms(100);
rslt |= bmi088_get_accel_data(&negative, dev);
rslt |= bmi088_set_accel_selftest(BMI088_ACCEL_SWITCH_OFF_SELF_TEST, dev);
accel_data_diff.x = ABS(positive.x) + ABS(negative.x);
accel_data_diff.y = ABS(positive.y) + ABS(negative.y);
accel_data_diff.z = ABS(positive.z) + ABS(negative.z);
/*! Converting LSB of the differences of
accel values to mg */
convert_lsb_g(&accel_data_diff, &accel_data_diff_mg);
/*! Validating self test for
accel values in mg */
rslt |= validate_selftest(&accel_data_diff_mg);
if (rslt == BMI088_OK)
{
*result = BMI088_SELFTEST_PASS;
dev->delay_ms(BMI088_HUNDRED);
}
/* Triggers a soft reset */
rslt |= bmi088_accel_soft_reset(dev);
}
}
}
return rslt;
}
/*!
* @brief This API enables or disables the Accel Self test feature in the
* sensor.
*/
uint16_t bmi088_set_accel_selftest(uint8_t selftest, struct bmi088_dev *dev)
{
uint16_t rslt = BMI088_OK;
uint8_t reg_addr, data = 0;
/* Check for null pointer in the device structure*/
rslt = null_ptr_check(dev);
/* Proceed if null check is fine */
if (rslt == BMI088_OK)
{
reg_addr = BMI088_ACCEL_SELF_TEST_REG;
data = selftest;
/* Write to accel selftest register */
rslt = bmi088_set_accel_regs(reg_addr, &data, BMI088_ONE, dev);
}
return rslt;
}
/*****************************************************************************/
/* Static function definition */
/*!
* @brief This API is used to validate the device structure pointer for
* null conditions.
*/
static uint16_t null_ptr_check(struct bmi088_dev *dev)
{
uint16_t rslt;
if ((dev == NULL) || (dev->read == NULL) || (dev->write == NULL) || (dev->delay_ms == NULL))
{
/* Device structure pointer is not valid */
rslt = BMI088_E_NULL_PTR;
}
else
{
/* Device structure is fine */
rslt = BMI088_OK;
}
return rslt;
}
/*!
* @brief This API configures the pins which fire the
* interrupt signal when any interrupt occurs.
*/
static uint16_t set_int_pin_config(const struct bmi088_int_cfg *int_config, struct bmi088_dev *dev)
{
uint16_t rslt = BMI088_OK;
uint8_t reg_addr, data;
/* Check for null pointer in the device structure*/
rslt = null_ptr_check(dev);
/* Proceed if null check is fine */
if ((rslt == BMI088_OK) && (int_config != NULL))
{
/* update reg_addr based on channel inputs */
if (int_config->accel_int_channel == BMI088_INT_CHANNEL_1)
{
reg_addr = BMI088_ACCEL_INT1_IO_CONF_REG;
}
if (int_config->accel_int_channel == BMI088_INT_CHANNEL_2)
{
reg_addr = BMI088_ACCEL_INT2_IO_CONF_REG;
}
/* Read interrupt pin configuration register */
rslt = bmi088_get_accel_regs(reg_addr, &data, BMI088_ONE, dev);
if (rslt == BMI088_OK)
{
/* Update data with user configured bmi088_int_cfg structure */
data = BMI088_SET_BITSLICE(data, BMI088_ACCEL_INT2_LVL, int_config->accel_int_pin_cfg.lvl);
data = BMI088_SET_BITSLICE(data, BMI088_ACCEL_INT2_OD, int_config->accel_int_pin_cfg.output_mode);
data = BMI088_SET_BITSLICE(data, BMI088_ACCEL_INT2_IO, int_config->accel_int_pin_cfg.enable_int_pin);
/* Write to interrupt pin configuration register */
rslt = bmi088_set_accel_regs(reg_addr, &data, BMI088_ONE, dev);
}
}
return rslt;
}
/*!
* @brief This API sets the data ready interrupt for accel sensor.
*/
static uint16_t set_accel_data_ready_int(const struct bmi088_int_cfg *int_config, struct bmi088_dev *dev)
{
uint16_t rslt = BMI088_OK;
uint8_t reg_addr, data;
/* Check for null pointer in the device structure*/
rslt = null_ptr_check(dev);
/* Proceed if null check is fine */
if ((rslt == BMI088_OK) && (int_config != NULL))
{
reg_addr = BMI088_ACCEL_INT1_INT2_MAP_DATA_REG;
/* Read interrupt map register */
rslt = bmi088_get_accel_regs(reg_addr, &data, BMI088_ONE, dev);
if (rslt == BMI088_OK)
{
/* Update data to map data ready interrupt to appropriate interrupt pins */
if (int_config->accel_int_channel == BMI088_INT_CHANNEL_1)
{
data = BMI088_SET_BITSLICE(data, BMI088_ACCEL_INT1_DRDY, BMI088_ENABLE);
}
if (int_config->accel_int_channel == BMI088_INT_CHANNEL_2)
{
data = BMI088_SET_BITSLICE(data, BMI088_ACCEL_INT2_DRDY, BMI088_ENABLE);
}
/* Write to interrupt map register */
rslt = bmi088_set_accel_regs(reg_addr, &data, BMI088_ONE, dev);
/* Configure interrupt pins */
rslt |= set_int_pin_config(int_config, dev);
}
}
return rslt;
}
/*!
* @brief This API writes the config stream data in memory using burst mode.
*/
static uint16_t stream_transfer_write(const uint8_t *stream_data, uint16_t index, struct bmi088_dev *dev)
{
uint16_t rslt = 0;
uint8_t asic_msb = (uint8_t)((index / 2) >> 4);
uint8_t asic_lsb = ((index / 2) & 0x0F);
uint8_t reg_addr;
/* Write to feature config register */
reg_addr = BMI088_ACCEL_RESERVED_5B_REG;
rslt |= bmi088_set_accel_regs(reg_addr, &asic_lsb, BMI088_ONE, dev);
if (rslt == BMI088_OK)
{
/* Write to feature config register */
reg_addr = BMI088_ACCEL_RESERVED_5C_REG;
rslt |= bmi088_set_accel_regs(reg_addr, &asic_msb, BMI088_ONE, dev);
if (rslt == BMI088_OK)
{
/* Write to feature config registers */
reg_addr = BMI088_ACCEL_FEATURE_CFG_REG;
rslt |= bmi088_set_accel_regs(reg_addr, (uint8_t *)stream_data, dev->read_write_len, dev);
}
}
return rslt;
}
/*!
* @brief This function enables and configures the Accel which is needed
* for Self test operation.
*/
static uint16_t set_accel_selftest_config(struct bmi088_dev *dev)
{
uint16_t rslt = BMI088_OK;
/* Configuring sensors to perform accel self test */
dev->accel_cfg.odr = BMI088_ACCEL_ODR_1600_HZ;
dev->accel_cfg.bw = BMI088_ACCEL_BW_NORMAL;
dev->accel_cfg.range = BMI088_ACCEL_RANGE_24G;
/* Enable Accel sensor */
rslt = bmi088_accel_switch_control(dev, BMI088_ACCEL_POWER_ENABLE);
/* Configure sensors with above configured settings */
rslt |= bmi088_set_accel_meas_conf(dev);
return rslt;
}
/*!
* @brief This function validates the Accel Self test data and decides the
* result of Self test operation.
*/
static uint16_t validate_selftest(const struct bmi088_sensor_data *accel_data_diff)
{
uint16_t rslt;
/* Validating accel data by comparing with minimum value of the axes in mg */
/* x axis limit 1000mg, y axis limit 1000mg and z axis limit 500mg */
if (accel_data_diff->x >= 1000 && accel_data_diff->y >= 1000 && accel_data_diff->z >= 500)
{
rslt = BMI088_OK;
}
else
{
rslt = BMI088_E_SELF_TEST_FAIL;
}
return rslt;
}
/*!
* @brief This API converts lsb value of axes to mg for self-test.
*/
static void convert_lsb_g(const struct bmi088_sensor_data *accel_data_diff,
struct bmi088_sensor_data *accel_data_diff_mg)
{
uint32_t lsb_per_g;
/* Range considered for self-test is 24g */
uint8_t range = 16;
/* lsb_per_g for the 16-bit resolution and 24g range*/
lsb_per_g = (uint32_t)(power(2, BMI088_16_BIT_RESOLUTION) / (2 * range));
/* accel x value in mg */
accel_data_diff_mg->x = (accel_data_diff->x / (int32_t)lsb_per_g) * 1000;
/* accel y value in mg */
accel_data_diff_mg->y = (accel_data_diff->y / (int32_t)lsb_per_g) * 1000;
/* accel z value in mg */
accel_data_diff_mg->z = (accel_data_diff->z / (int32_t)lsb_per_g) * 1000;
}
/*!
* @brief This API is used to calculate the power of given
* base value.
*/
static int32_t power(int16_t base, uint8_t resolution)
{
uint8_t i = 1;
/* Initialize variable to store the power of 2 value */
int32_t value = 1;
for (; i <= resolution; i++)
{
value = (int32_t)(value * base);
}
return value;
}
/** @}*/
/*
****************************************************************************
* Copyright (C) 2015 - 2016 Bosch Sensortec GmbH
*
* File :bmi088_fifo.c
*
* Date: 30 Oct 2017
*
* Revision:
*
* Usage: Sensor Driver for BMI088 family of sensors
*
****************************************************************************
* Disclaimer
*
* Common:
* Bosch Sensortec products are developed for the consumer goods industry.
* They may only be used within the parameters of the respective valid
* product data sheet. Bosch Sensortec products are provided with the
* express understanding that there is no warranty of fitness for a
* particular purpose.They are not fit for use in life-sustaining,
* safety or security sensitive systems or any system or device
* that may lead to bodily harm or property damage if the system
* or device malfunctions. In addition,Bosch Sensortec products are
* not fit for use in products which interact with motor vehicle systems.
* The resale and or use of products are at the purchasers own risk and
* his own responsibility. The examination of fitness for the intended use
* is the sole responsibility of the Purchaser.
*
* The purchaser shall indemnify Bosch Sensortec from all third party
* claims, including any claims for incidental, or consequential damages,
* arising from any product use not covered by the parameters of
* the respective valid product data sheet or not approved by
* Bosch Sensortec and reimburse Bosch Sensortec for all costs in
* connection with such claims.
*
* The purchaser must monitor the market for the purchased products,
* particularly with regard to product safety and inform Bosch Sensortec
* without delay of all security relevant incidents.
*
* Engineering Samples are marked with an asterisk (*) or (e).
* Samples may vary from the valid technical specifications of the product
* series. They are therefore not intended or fit for resale to third
* parties or for use in end products. Their sole purpose is internal
* client testing. The testing of an engineering sample may in no way
* replace the testing of a product series. Bosch Sensortec assumes
* no liability for the use of engineering samples.
* By accepting the engineering samples, the Purchaser agrees to indemnify
* Bosch Sensortec from all claims arising from the use of engineering
* samples.
*
* Special:
* This software module (hereinafter called "Software") and any information
* on application-sheets (hereinafter called "Information") is provided
* free of charge for the sole purpose to support your application work.
* The Software and Information is subject to the following
* terms and conditions:
*
* The Software is specifically designed for the exclusive use for
* Bosch Sensortec products by personnel who have special experience
* and training. Do not use this Software if you do not have the
* proper experience or training.
*
* This Software package is provided `` as is `` and without any expressed
* or implied warranties,including without limitation, the implied warranties
* of merchantability and fitness for a particular purpose.
*
* Bosch Sensortec and their representatives and agents deny any liability
* for the functional impairment
* of this Software in terms of fitness, performance and safety.
* Bosch Sensortec and their representatives and agents shall not be liable
* for any direct or indirect damages or injury, except as
* otherwise stipulated in mandatory applicable law.
*
* The Information provided is believed to be accurate and reliable.
* Bosch Sensortec 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 Bosch. Specifications mentioned in the Information are
* subject to change without notice.
**************************************************************************/
/*! \file bmi088_fifo.c
\brief Sensor Driver for BMI088 family of sensors */
/***************************************************************************/
/**\name Header files
****************************************************************************/
#ifdef USE_FIFO
#include "bmi088_fifo.h"
/***************************************************************************/
/**\name Local structures
****************************************************************************/
/***************************************************************************/
/*! Static Function Declarations
****************************************************************************/
/*!
* @brief This API is used to validate the device structure pointer for
* null conditions.
*
* @param[in] dev : Structure instance of bmi088_dev.
*
* @return Result of API execution status
* @retval zero -> Success
* @retval Any non zero value -> Fail
*
*/
static uint16_t null_ptr_check(const struct bmi088_dev *dev);
/*!
* @brief This API is used to reset the accel FIFO related configurations
* in the fifo_frame structure.
*
* @param dev[in,out] : Structure instance of bmi088_dev
*
* @return None
*/
static void reset_accel_fifo_data_structure(const struct bmi088_dev *dev);
/*!
* @brief This API computes the number of bytes of accel FIFO data
* which is to be parsed in header-less mode
*
* @param[out] start_idx : The start index for parsing data
* @param[out] len : Number of bytes to be parsed
* @param[in] accel_count : Number of accelerometer frames to be read
* @param[in] dev : Structure instance of bmi088_dev.
*
* @return None
*/
static void get_accel_len_to_parse(uint16_t *start_idx, uint16_t *len, const uint16_t *accel_count, const struct bmi088_dev *dev);
/*!
* @brief This API checks the accel fifo read data as empty frame, if it
* is empty frame then moves the index to last byte.
*
* @param[in,out] data_index : The index of the current data to
* be parsed from accelerometer fifo data
* @param[in] dev : Structure instance of bmi088_dev.
*
* @return None
*/
static void check_empty_accel_fifo(uint16_t *data_index, const struct bmi088_dev *dev);
/*!
* @brief This API is used to parse the accelerometer data from the
* FIFO data in header mode.
*
* @param[in,out] accel_data : Structure instance of bmi088_sensor_data where
* the accelerometer data in FIFO is stored.
* @param[in,out] accel_length : Number of accelerometer frames
* (x,y,z axes data)
* @param[in,out] dev : Structure instance of bmi088_dev.
*
* @return None
*/
static void extract_accel_header_mode(struct bmi088_sensor_data *accel_data, uint16_t *accel_length, const struct bmi088_dev *dev);
/*!
* @brief This API is used to parse the accelerometer data from the
* FIFO data in both header mode and header-less mode.
* It updates the idx value which is used to store the index of
* the current data byte which is parsed.
*
* @param[in,out] accel : Structure instance of bmi088_sensor_data.
* @param[in,out] idx : Index value of number of bytes parsed
* @param[in,out] accel_idx : Index value of accelerometer data
* (x,y,z axes) frame to be parsed
* @param[in] frm : It consists of either fifo_data_enable
* parameter (Accel enabled in FIFO)
* in header-less mode or frame header data
* in header mode
* @param[in] dev : Structure instance of bmi088_dev.
*
* @return None
*/
static void unpack_accel_frm(struct bmi088_sensor_data *accel, uint16_t *idx, uint16_t *accel_idx, uint8_t frm, const struct bmi088_dev *dev);
/*!
* @brief This API is used to parse the accelerometer data from the
* FIFO data and store it in the instance of the structure bmi088_sensor_data.
*
* @param[out] accel_data : Structure instance of bmi088_sensor_data where
* the parsed accel data bytes are stored.
* @param[in] data_start_index : Index value of the accel data bytes
* which is to be parsed from the fifo data.
* @param[in] dev : Structure instance of bmi088_dev.
*
* @return None
*
*/
static void unpack_accel_data(struct bmi088_sensor_data *accel_data, uint16_t data_start_index, const struct bmi088_dev *dev);
/*!
* @brief This API is used to parse and store the sensor time from the
* FIFO data in the structure instance dev.
*
* @param[in,out] data_index : Index of the FIFO data which
* has the sensor time.
* @param[in,out] dev : Structure instance of bmi088_dev.
*
* @return None
*/
static void unpack_sensortime_frame(uint16_t *data_index, const struct bmi088_dev *dev);
/*!
* @brief This API is used to parse and store the skipped_frame_count from
* the accelerometer FIFO data in the structure instance dev.
*
* @param[in,out] data_index : Index of the FIFO data which
* has the skipped frame count.
* @param[in,out] dev : Structure instance of bmi088_dev.
*
* @return None
*/
static void unpack_accel_skipped_frame(uint16_t *data_index, const struct bmi088_dev *dev);
/*!
* @brief This API is used to parse and store the dropped_frame_count from
* the accelerometer FIFO data in the structure instance dev.
*
* @param[in,out] data_index : Index of the FIFO data which
* has the dropped frame data.
* @param[in,out] dev : Structure instance of bmi088_dev.
*
* @return None
*/
static void unpack_accel_dropped_frame(uint16_t *data_index, const struct bmi088_dev *dev);
/*!
* @brief This API is used to move the data index ahead of the
* current_frame_length parameter when unnecessary FIFO data appears while
* extracting the accelerometer data.
*
* @param[in,out] data_index : Index of the FIFO data which
* is to be moved ahead of the
* current_frame_length
* @param[in] current_frame_length : Number of bytes in a particular frame
* @param[in] dev : Structure instance of bmi088_dev.
*
* @return None
*/
static void move_to_next_accel_frame(uint16_t *data_index, uint8_t current_frame_length, const struct bmi088_dev *dev);
/*!
* @brief This API is used to reset the gyro FIFO related configurations
* in the fifo_frame structure.
*
* @param dev[in,out] : Structure instance of bmi088_dev
*
* @return None
*/
static void reset_gyro_fifo_data_structure(const struct bmi088_dev *dev);
/*!
* @brief This API computes the number of bytes of Gyro FIFO data which is
* to be parsed in header-less mode
*
* @param[out] start_idx : The start index for parsing data
* @param[out] len : Number of bytes to be parsed
* @param[in] gyro_count : Number of gyroscope frames to be read
* @param[in] dev : Structure instance of bmi088_dev.
*
* @return None
*/
static void get_gyro_len_to_parse(uint16_t *start_idx, uint16_t *len, const uint16_t *gyro_count, const struct bmi088_dev *dev);
/*!
* @brief This API is used to parse the gyroscope data from the
* FIFO data in header-less mode and update the idx value
* which is used to store the index of the current data byte
* which is parsed.
*
* @param[in,out] data : Structure instance of bmi088_sensor_data.
* @param[in,out] idx : Index value of number of bytes parsed
* @param[in,out] gyro_idx : Index value gyroscope data frame (x,y,z,r)
* to be parsed
* @param[in] frm : It consists of either the fifo_data_enable parameter
* (Gyro data enabled in FIFO) in header-less mode
* @param[in] dev : Structure instance of bmi088_dev.
*
* @return Result of API execution status
* @retval 0 -> Success
* @retval Any non zero value -> Fail
*
*/
static uint16_t unpack_gyro_frm(struct bmi088_sensor_data *data, uint16_t *idx, uint16_t *gyro_idx, uint8_t frm, const struct bmi088_dev *dev);
/*!
* @brief This API is used to parse the gyroscope data from
* the FIFO data and store it in the instance of the structure
* gyro_data.
*
* @param[out] gyro_data : Structure instance of bmi088_sensor_data where the
* parsed gyroscope data bytes are stored.
* @param[in] start_idx : Index value of the gyroscope data bytes
* which is to be parsed from the FIFO data
* @param[in] dev : Structure instance of bmi088_dev.
*
* @return None
*/
static void unpack_gyro_data(struct bmi088_sensor_data *gyro_data, uint16_t start_idx, const struct bmi088_dev *dev);
/*!
* @brief This API checks the gyro fifo read data as empty frame, if it
* is empty frame then moves the index to last byte.
*
* @param[in,out] data_index : The index of the current data to
* be parsed from gyroscope fifo data
* @param[in] dev : Structure instance of bmi088_dev.
*
* @return None
*/
static void check_empty_gyro_fifo(uint16_t *data_index, const struct bmi088_dev *dev);
/***************************************************************************/
/**\name Extern Declarations
****************************************************************************/
/***************************************************************************/
/**\name Globals
****************************************************************************/
/***************************************************************************/
/**\name Function definitions
****************************************************************************/
/*!
* @brief This API reads the FIFO data of Accel sensor.
*/
uint16_t bmi088_get_accel_fifo_data(struct bmi088_dev *dev)
{
uint16_t rslt = 0;
uint8_t data = 0;
uint8_t reg_addr = BMI088_ACCEL_FIFO_DATA_REG;
/* Check for null pointer in the device structure*/
rslt = null_ptr_check(dev);
/* Proceed if null check is fine */
if (rslt == BMI088_OK)
{
/* Reset the Accel FIFO related configurations */
reset_accel_fifo_data_structure(dev);
if (dev->interface == BMI088_SPI_INTF)
{
reg_addr = reg_addr | BMI088_SPI_RD_MASK;
}
/* Read Accel FIFO data*/
rslt |= dev->read(dev->accel_id, reg_addr, dev->accel_fifo->data, dev->accel_fifo->length);
reg_addr = BMI088_ACCEL_FIFO_CONFIG_1_REG;
/* Read fifo frame content configuration*/
rslt |= bmi088_get_accel_regs(reg_addr, &data, BMI088_ONE, dev);
/* Filter fifo header enabled status */
dev->accel_fifo->fifo_header_enable = data & BMI088_FIFO_HEADER;
/* Filter accel data enabled status */
dev->accel_fifo->fifo_data_enable = data & BMI088_FIFO_A_ENABLE;
}
return rslt;
}
/*!
* @brief This API parses and extracts the accelerometer frames from
* FIFO data read by the "bmi088_get_accel_fifo_data" API and stores
* it in the "accel_data" structure instance.
*/
uint16_t bmi088_extract_accel(struct bmi088_sensor_data *accel_data, uint16_t *accel_length, const struct bmi088_dev *dev)
{
uint16_t rslt = 0;
uint16_t data_index = 0;
uint16_t accel_index = 0;
uint16_t data_read_length = 0;
/* Check for null pointer in the device structure*/
rslt = null_ptr_check(dev);
/* Proceed if null check is fine */
if (rslt == BMI088_OK)
{
/* Parsing the Accel FIFO data in header-less mode */
if (dev->accel_fifo->fifo_header_enable == 0)
{
/* Collects the number of bytes of Accel FIFO data
* which is to be parsed in header-less mode */
get_accel_len_to_parse(&data_index, &data_read_length, accel_length, dev);
for (; data_index < data_read_length;)
{
/* Unpack Accel data from fifo buffer */
unpack_accel_frm(accel_data, &data_index, &accel_index, dev->accel_fifo->fifo_data_enable, dev);
/*Check for the availability of next
two bytes of accel FIFO data */
check_empty_accel_fifo(&data_index, dev);
}
/* update number of Accel data read*/
*accel_length = accel_index;
/*update the Accel byte index*/
dev->accel_fifo->byte_start_idx = data_index;
}
else
{
/* Parsing the accel FIFO data in header mode */
extract_accel_header_mode(accel_data, accel_length, dev);
}
}
return rslt;
}
/*!
* @brief This API reads the accel FIFO water mark level which is set
* in the sensor.
*/
uint16_t bmi088_get_accel_fifo_wm(uint16_t *fifo_wm, struct bmi088_dev *dev)
{
uint16_t rslt = 0;
uint8_t data[2] = { 0, 0 };
uint8_t reg_addr;
/* Check for null pointer in the device structure*/
rslt = null_ptr_check(dev);
/* Proceed if null check is fine */
if (rslt == BMI088_OK)
{
reg_addr = BMI088_ACCEL_FIFO_WTM_0_REG;
/* Read the Accel FIFO watermark level*/
rslt |= bmi088_get_accel_regs(reg_addr, data, BMI088_TWO, dev);
if (rslt == BMI088_OK)
{
/* Update the fifo watermark level */
*fifo_wm = (data[1] << BMI088_EIGHT) | (data[0]);
}
}
return rslt;
}
/*!
* @brief This API sets the accel FIFO watermark level in the sensor.
*/
uint16_t bmi088_set_accel_fifo_wm(uint16_t fifo_wm, struct bmi088_dev *dev)
{
uint16_t rslt = 0;
uint8_t data[2] = { 0, 0 };
uint8_t reg_addr;
/* Check for null pointer in the device structure*/
rslt = null_ptr_check(dev);
/* Proceed if null check is fine */
if (rslt == BMI088_OK)
{
data[0] = BMI088_GET_LSB(fifo_wm);
data[1] = BMI088_GET_MSB(fifo_wm);
/* consecutive write is not possible in suspend mode hence
separate write is used with delay of 1 ms*/
/* Write the Accel fifo watermark level*/
reg_addr = BMI088_ACCEL_FIFO_WTM_0_REG;
rslt |= bmi088_set_accel_regs(reg_addr, &data[0], BMI088_ONE, dev);
dev->delay_ms(BMI088_ONE);
/* Write the Accel fifo watermark level */
rslt |= bmi088_set_accel_regs((reg_addr + BMI088_ONE), &data[1], BMI088_ONE, dev);
}
return rslt;
}
/*!
* @brief This API checks whether the Accel FIFO data is set for filtered
* or unfiltered mode.
*/
uint16_t bmi088_get_accel_fifo_filt_data(uint8_t *accel_fifo_filter, struct bmi088_dev *dev)
{
uint16_t rslt = 0;
uint8_t data = 0, reg_addr;
/* Check for null pointer in the device structure*/
rslt = null_ptr_check(dev);
/* Proceed if null check is fine */
if (rslt == BMI088_OK)
{
reg_addr = BMI088_ACCEL_FIFO_DOWN_REG;
/* Read the Accel FIFO filter data */
rslt |= bmi088_get_accel_regs(reg_addr, &data, BMI088_ONE, dev);
if (rslt == BMI088_OK)
{
/* Update the accel fifo filter info */
*accel_fifo_filter = BMI088_GET_BITSLICE(data, BMI088_ACCEL_FIFO_FILT_DATA);
}
}
return rslt;
}
/*!
* @brief This API sets the condition of Accel FIFO data either to
* filtered or unfiltered mode.
*/
uint16_t bmi088_set_accel_fifo_filt_data(uint8_t accel_fifo_filter, struct bmi088_dev *dev)
{
uint16_t rslt = 0;
uint8_t data = 0, reg_addr;
/* Check for null pointer in the device structure*/
rslt = null_ptr_check(dev);
/* Proceed if null check is fine */
if (rslt == BMI088_OK)
{
if (accel_fifo_filter <= BMI088_MAX_VALUE_FIFO_FILTER)
{
/* Read accel fifo down register */
reg_addr = BMI088_ACCEL_FIFO_DOWN_REG;
rslt |= bmi088_get_accel_regs(reg_addr, &data, BMI088_ONE, dev);
if (rslt == BMI088_OK)
{
/* Write Accel FIFO filter data */
data = BMI088_SET_BITSLICE(data, BMI088_ACCEL_FIFO_FILT_DATA, accel_fifo_filter);
rslt |= bmi088_set_accel_regs(reg_addr, &data, BMI088_ONE, dev);
}
}
else
{
rslt |= BMI088_E_OUT_OF_RANGE;
}
}
return rslt;
}
/*!
* @brief This API reads the down sampling rates which is configured
* for Accel FIFO data.
*/
uint16_t bmi088_get_fifo_down_accel(uint8_t *fifo_down, struct bmi088_dev *dev)
{
uint16_t rslt = 0;
uint8_t data = 0, reg_addr;
/* Check for null pointer in the device structure*/
rslt = null_ptr_check(dev);
/* Proceed if null check is fine */
if (rslt == BMI088_OK)
{
reg_addr = BMI088_ACCEL_FIFO_DOWN_REG;
/* Read the Accel FIFO down data */
rslt |= bmi088_get_accel_regs(reg_addr, &data, BMI088_ONE, dev);
if (rslt == BMI088_OK)
{
/* Update the fifo down value */
*fifo_down = BMI088_GET_BITSLICE(data, BMI088_ACCEL_FIFO_FILT_DOWN);
}
}
return rslt;
}
/*!
* @brief This API sets the down-sampling rates for Accel FIFO.
*/
uint16_t bmi088_set_fifo_down_accel(uint8_t fifo_down, struct bmi088_dev *dev)
{
uint16_t rslt = 0;
uint8_t data = 0, reg_addr;
/* Check for null pointer in the device structure*/
rslt = null_ptr_check(dev);
/* Proceed if null check is fine */
if (rslt == BMI088_OK)
{
if (fifo_down <= BMI088_MAX_VALUE_FIFO_DOWN)
{
reg_addr = BMI088_ACCEL_FIFO_DOWN_REG;
/* Read the Accel FIFO down register */
rslt |= bmi088_get_accel_regs(reg_addr, &data, BMI088_ONE, dev);
if (rslt == BMI088_OK)
{
data = BMI088_SET_BITSLICE(data, BMI088_ACCEL_FIFO_FILT_DOWN, fifo_down);
/* Write the Accel FIFO down data */
rslt |= bmi088_set_accel_regs(reg_addr, &data, BMI088_ONE, dev);
}
}
else
{
rslt |= BMI088_E_OUT_OF_RANGE;
}
}
return rslt;
}
/*!
* @brief This API reads the length of FIFO data available in the
* Accel sensor in the units of bytes.
*/
uint16_t bmi088_get_accel_fifo_length(uint16_t *fifo_length, struct bmi088_dev *dev)
{
uint16_t rslt = 0;
uint8_t index = 0, reg_addr;
uint8_t data[2] = { 0, 0 };
/* Check for null pointer in the device structure */
rslt = null_ptr_check(dev);
/* Proceed if null check is fine */
if (rslt == BMI088_OK)
{
reg_addr = BMI088_ACCEL_FIFO_LENGTH_0_REG;
/* Read Accel FIFO length */
rslt |= bmi088_get_accel_regs(reg_addr, data, BMI088_TWO, dev);
if (rslt == BMI088_OK)
{
/* Update fifo length */
index = BMI088_ONE;
data[index] = BMI088_GET_BITSLICE(data[index], BMI088_FIFO_BYTE_COUNTER_MSB);
*fifo_length = ((data[index] << BMI088_EIGHT) | data[index - BMI088_ONE]);
}
}
return rslt;
}
/*!
* @brief This API sets the FIFO full interrupt of the accel sensor.
*/
uint16_t bmi088_set_accel_fifo_full_int(struct bmi088_int_cfg *int_config, struct bmi088_dev *dev)
{
uint16_t rslt = 0;
uint8_t data = 0, reg_addr;
/* Check for null pointer in the device structure*/
rslt = null_ptr_check(dev);
/* Proceed if null check is fine */
if (rslt == BMI088_OK)
{
/* update reg_addr based on channel inputs */
if (int_config->accel_int_channel == BMI088_INT_CHANNEL_1)
{
reg_addr = BMI088_ACCEL_INT1_IO_CONF_REG;
}
if (int_config->accel_int_channel == BMI088_INT_CHANNEL_2)
{
reg_addr = BMI088_ACCEL_INT2_IO_CONF_REG;
}
/* Read interrupt pin configuration register */
rslt = bmi088_get_accel_regs(reg_addr, &data, BMI088_ONE, dev);
if (rslt == BMI088_OK)
{
/* Update data with user configured bmi088_int_cfg structure */
data = BMI088_SET_BITSLICE(data, BMI088_ACCEL_INT2_LVL, int_config->accel_int_pin_cfg.lvl);
data = BMI088_SET_BITSLICE(data, BMI088_ACCEL_INT2_OD, int_config->accel_int_pin_cfg.output_mode);
data = BMI088_SET_BITSLICE(data, BMI088_ACCEL_INT2_IO, int_config->accel_int_pin_cfg.enable_int_pin);
/* Write to interrupt pin configuration register */
rslt = bmi088_set_accel_regs(reg_addr, &data, BMI088_ONE, dev);
if (rslt == BMI088_OK)
{
reg_addr = BMI088_ACCEL_INT1_INT2_MAP_DATA_REG;
/* Read the Accel Interrupt Map Register */
rslt = bmi088_get_accel_regs(reg_addr, &data, BMI088_ONE, dev);
if (rslt == BMI088_OK)
{
/* Update data to map fifo full interrupt based on channel inputs */
if (int_config->accel_int_channel == BMI088_INT_CHANNEL_1)
{
data = BMI088_SET_BITSLICE(data, BMI088_ACCEL_INT1_FIFO_FULL, BMI088_ONE);
}
else if (int_config->accel_int_channel == BMI088_INT_CHANNEL_2)
{
data = BMI088_SET_BITSLICE(data, BMI088_ACCEL_INT2_FIFO_FULL, BMI088_ONE);
}
else
{
/* do nothing */
}
/* Write the Accel Interrupt Map Register */
rslt = bmi088_set_gyro_regs(reg_addr, &data, BMI088_ONE, dev);
}
}
}
}
return rslt;
}
/*!
* @brief This API sets the FIFO watermark interrupt of the accel sensor.
*/
uint16_t bmi088_set_accel_fifo_wm_int(struct bmi088_int_cfg *int_config, struct bmi088_dev *dev)
{
uint16_t rslt = 0;
uint8_t data = 0, reg_addr;
/* Check for null pointer in the device structure*/
rslt = null_ptr_check(dev);
/* Proceed if null check is fine */
if (rslt == BMI088_OK)
{
/* update reg_addr based on channel inputs */
if (int_config->accel_int_channel == BMI088_INT_CHANNEL_1)
{
reg_addr = BMI088_ACCEL_INT1_IO_CONF_REG;
}
if (int_config->accel_int_channel == BMI088_INT_CHANNEL_2)
{
reg_addr = BMI088_ACCEL_INT2_IO_CONF_REG;
}
/* Read interrupt pin configuration register */
rslt = bmi088_get_accel_regs(reg_addr, &data, BMI088_ONE, dev);
if (rslt == BMI088_OK)
{
/* Update data with user configured bmi088_int_cfg structure */
data = BMI088_SET_BITSLICE(data, BMI088_ACCEL_INT2_LVL, int_config->accel_int_pin_cfg.lvl);
data = BMI088_SET_BITSLICE(data, BMI088_ACCEL_INT2_OD, int_config->accel_int_pin_cfg.output_mode);
data = BMI088_SET_BITSLICE(data, BMI088_ACCEL_INT2_IO, int_config->accel_int_pin_cfg.enable_int_pin);
/* Write to interrupt pin configuration register */
rslt = bmi088_set_accel_regs(reg_addr, &data, BMI088_ONE, dev);
if (rslt == BMI088_OK)
{
reg_addr = BMI088_ACCEL_INT1_INT2_MAP_DATA_REG;
/* Read the Accel Interrupt Map Register */
rslt = bmi088_get_accel_regs(reg_addr, &data, BMI088_ONE, dev);
if (rslt == BMI088_OK)
{
/* Update data to map watermark interrupt based on channel inputs */
if (int_config->accel_int_channel == BMI088_INT_CHANNEL_1)
{
data = BMI088_SET_BITSLICE(data, BMI088_ACCEL_INT1_FIFO_WM, BMI088_ONE);
}
else if (int_config->accel_int_channel == BMI088_INT_CHANNEL_2)
{
data = BMI088_SET_BITSLICE(data, BMI088_ACCEL_INT2_FIFO_WM, BMI088_ONE);
}
else
{
/* do nothing */
}
/* Write to the Accel Interrupt Map Register */
rslt = bmi088_set_gyro_regs(reg_addr, &data, BMI088_ONE, dev);
}
}
}
}
return rslt;
}
/*!
* @brief This API reads the FIFO data of Gyro sensor.
*/
uint16_t bmi088_get_gyro_fifo_data(struct bmi088_dev *dev)
{
uint16_t rslt = 0;
uint8_t reg_addr = BMI088_GYRO_FIFO_DATA_REG;
/* Check for null pointer in the device structure*/
rslt = null_ptr_check(dev);
/* Proceed if null check is fine */
if (rslt == BMI088_OK)
{
/* Reset the gyro FIFO related configurations */
reset_gyro_fifo_data_structure(dev);
/* Read FIFO data*/
if (dev->interface == BMI088_SPI_INTF)
{
reg_addr = reg_addr | BMI088_SPI_RD_MASK;
}
rslt |= dev->read(dev->gyro_id, reg_addr, dev->gyro_fifo->data, dev->gyro_fifo->length);
/* Update the data select axes info in fifo_data_enable variable found in device structure */
rslt |= bmi088_get_gyro_fifo_data_sel(&dev->gyro_fifo->fifo_data_enable, dev);
}
return rslt;
}
/*!
* @brief This API parses and extracts the gyroscope frames from
* FIFO data read by the "bmi088_get_gyro_fifo_data" API and
* stores it in the "gyro_data" structure instance parameter of
* this API.
*/
uint16_t bmi088_extract_gyro(struct bmi088_sensor_data *gyro_data, uint16_t *gyro_length, const struct bmi088_dev *dev)
{
uint16_t rslt = 0;
uint16_t data_index = 0;
uint16_t gyro_index = 0;
uint16_t data_read_length = 0;
/* Check for null pointer in the device structure*/
rslt = null_ptr_check(dev);
/* Proceed if null check is fine */
if (rslt == BMI088_OK)
{
/* Collects the number of bytes of Gyro FIFO data
* which is to be parsed */
get_gyro_len_to_parse(&data_index, &data_read_length, gyro_length, dev);
for (; data_index < data_read_length;)
{
/* Unpack Gyro data from fifo buffer */
rslt |= unpack_gyro_frm(gyro_data, &data_index, &gyro_index, dev->gyro_fifo->fifo_data_enable, dev);
/* Check for the availability of next
two bytes of FIFO data */
check_empty_gyro_fifo(&data_index, dev);
}
/* Update number of gyro data read*/
*gyro_length = gyro_index;
/* Update the Gyro byte index*/
dev->gyro_fifo->byte_start_idx = data_index;
}
return rslt;
}
/*!
* @brief This API reads the Gyro FIFO water mark level which is set
* in the sensor.
*/
uint16_t bmi088_get_gyro_fifo_wm(uint8_t *fifo_wm, struct bmi088_dev *dev)
{
uint16_t rslt = 0;
uint8_t data, reg_addr;
/* Check for null pointer in the device structure*/
rslt = null_ptr_check(dev);
/* Proceed if null check is fine */
if (rslt == BMI088_OK)
{
reg_addr = BMI088_GYRO_FIFO_CONFIG_0_REG;
/* Read the Gyro FIFO water mark level*/
rslt = bmi088_get_gyro_regs(reg_addr, &data, BMI088_ONE, dev);
if (rslt == BMI088_OK)
{
/* Update the fifo watermark level */
*fifo_wm = BMI088_GET_BITSLICE(data, BMI088_GYRO_FIFO_WM);
}
}
return rslt;
}
/*!
* @brief This API sets the gyro FIFO watermark level in the sensor.
*/
uint16_t bmi088_set_gyro_fifo_wm(uint8_t fifo_wm, struct bmi088_dev *dev)
{
uint16_t rslt = 0;
uint8_t data, reg_addr;
/* Check for null pointer in the device structure*/
rslt = null_ptr_check(dev);
/* Proceed if null check is fine */
if (rslt == BMI088_OK)
{
if (fifo_wm <= BMI088_GYRO_FIFO_WM_MAX)
{
/* Read the fifo config 0 register */
reg_addr = BMI088_GYRO_FIFO_CONFIG_0_REG;
rslt |= bmi088_get_gyro_regs(reg_addr, &data, BMI088_ONE, dev);
/* Write the fifo watermark level*/
data = BMI088_SET_BITSLICE(data, BMI088_GYRO_FIFO_WM, fifo_wm);
rslt |= bmi088_set_gyro_regs(reg_addr, &data, BMI088_ONE, dev);
}
else
{
rslt = BMI088_E_OUT_OF_RANGE;
}
}
return rslt;
}
/*!
* @brief This API gets the FIFO operating mode in the gyro sensor.
*/
uint16_t bmi088_get_gyro_fifo_mode(uint8_t *fifo_mode, struct bmi088_dev *dev)
{
uint16_t rslt = 0;
uint8_t data, reg_addr;
/* Check for null pointer in the device structure*/
rslt = null_ptr_check(dev);
/* Proceed if null check is fine */
if (rslt == BMI088_OK)
{
reg_addr = BMI088_GYRO_FIFO_CONFIG_1_REG;
/* Read the Gyro fifo config 1 register */
rslt = bmi088_get_gyro_regs(reg_addr, &data, BMI088_ONE, dev);
if (rslt == BMI088_OK)
{
/* Update the fifo mode */
*fifo_mode = BMI088_GET_BITSLICE(data, BMI088_GYRO_FIFO_MODE);
}
}
return rslt;
}
/*!
* @brief This API sets the FIFO operating mode in the gyro sensor.
*/
uint16_t bmi088_set_gyro_fifo_mode(uint8_t fifo_mode, struct bmi088_dev *dev)
{
uint16_t rslt = 0;
uint8_t data, reg_addr;
/* Check for null pointer in the device structure*/
rslt = null_ptr_check(dev);
/* Proceed if null check is fine */
if (rslt == BMI088_OK)
{
if (fifo_mode <= BMI088_GYRO_STREAM_OP_MODE)
{
/* Read the fifo config 1 register */
reg_addr = BMI088_GYRO_FIFO_CONFIG_1_REG;
rslt |= bmi088_get_gyro_regs(reg_addr, &data, BMI088_ONE, dev);
/* Write the fifo operating mode */
data = BMI088_SET_BITSLICE(data, BMI088_GYRO_FIFO_MODE, fifo_mode);
rslt |= bmi088_set_gyro_regs(reg_addr, &data, BMI088_ONE, dev);
}
else
{
rslt = BMI088_E_OUT_OF_RANGE;
}
}
return rslt;
}
/*!
* @brief This API gets the data of axes to be stored in the FIFO in the gyro sensor.
*/
uint16_t bmi088_get_gyro_fifo_data_sel(uint8_t *fifo_data_select, struct bmi088_dev *dev)
{
uint16_t rslt = 0;
uint8_t data, reg_addr;
/* Check for null pointer in the device structure*/
rslt = null_ptr_check(dev);
/* Proceed if null check is fine */
if (rslt == BMI088_OK)
{
reg_addr = BMI088_GYRO_FIFO_CONFIG_1_REG;
/* Read the Gyro Fifo config 1 register */
rslt = bmi088_get_gyro_regs(reg_addr, &data, BMI088_ONE, dev);
if (rslt == BMI088_OK)
{
/* Update the fifo data select */
*fifo_data_select = BMI088_GET_BITSLICE(data, BMI088_GYRO_FIFO_DATA_SELECT);
}
}
return rslt;
}
/*!
* @brief This API sets the data of axes to be stored in the FIFO in the gyro sensor.
*/
uint16_t bmi088_set_gyro_fifo_data_sel(uint8_t fifo_data_select, struct bmi088_dev *dev)
{
uint16_t rslt = 0;
uint8_t data, reg_addr;
/* Check for null pointer in the device structure*/
rslt = null_ptr_check(dev);
/* Proceed if null check is fine */
if (rslt == BMI088_OK)
{
if (fifo_data_select <= BMI088_GYRO_Z_DATA)
{
/* Read the fifo config 1 register */
reg_addr = BMI088_GYRO_FIFO_CONFIG_1_REG;
rslt |= bmi088_get_gyro_regs(reg_addr, &data, BMI088_ONE, dev);
/* Write the fifo operating mode */
data = BMI088_SET_BITSLICE(data, BMI088_GYRO_FIFO_DATA_SELECT, fifo_data_select);
rslt |= bmi088_set_gyro_regs(reg_addr, &data, BMI088_ONE, dev);
}
else
{
rslt = BMI088_E_OUT_OF_RANGE;
}
}
return rslt;
}
/*!
* @brief This API reads the length of FIFO data available in the
* Gyro sensor in the units of bytes.
*/
uint16_t bmi088_get_gyro_fifo_length(uint8_t *fifo_length, struct bmi088_dev *dev)
{
uint16_t rslt = 0;
uint8_t data = 0, reg_addr;
/* Check for null pointer in the device structure*/
rslt = null_ptr_check(dev);
/* Proceed if null check is fine */
if (rslt == BMI088_OK)
{
reg_addr = BMI088_GYRO_FIFO_STAT_REG;
/* Read Gyro FIFO length*/
rslt |= bmi088_get_gyro_regs(reg_addr, &data, BMI088_ONE, dev);
if (rslt == BMI088_OK)
{
/* Update the fifo length */
*fifo_length = BMI088_GET_BITSLICE(data, BMI088_GYRO_FIFO_COUNTER);
}
}
return rslt;
}
/*!
* @brief This API gets the gyro FIFO overrun status.
*/
uint16_t bmi088_get_gyro_fifo_overrun(uint8_t *fifo_overrun_status, struct bmi088_dev *dev)
{
uint16_t rslt = 0;
uint8_t data = 0, reg_addr;
/* Check for null pointer in the device structure*/
rslt = null_ptr_check(dev);
/* Proceed if null check is fine */
if (rslt == BMI088_OK)
{
reg_addr = BMI088_GYRO_FIFO_STAT_REG;
/* Read Gyro fifo Overrun status */
rslt |= bmi088_get_gyro_regs(reg_addr, &data, BMI088_ONE, dev);
if (rslt == BMI088_OK)
{
/* Update the fifo overrun status */
*fifo_overrun_status = BMI088_GET_BITSLICE(data, BMI088_GYRO_FIFO_OVERRUN);
}
}
return rslt;
}
/*!
* @brief This API gets the fifo tag status which is set in gyro sensor.
*/
uint16_t bmi088_get_gyro_fifo_tag(uint8_t *fifo_tag_status, struct bmi088_dev *dev)
{
uint16_t rslt = 0;
uint8_t data = 0, reg_addr;
/* Check for null pointer in the device structure*/
rslt = null_ptr_check(dev);
/* Proceed if null check is fine */
if (rslt == BMI088_OK)
{
/* Read the fifo config 0 register */
reg_addr = BMI088_GYRO_FIFO_CONFIG_0_REG;
rslt = bmi088_get_gyro_regs(reg_addr, &data, BMI088_ONE, dev);
if (rslt == BMI088_OK)
{
/* Update the fifo tag status */
*fifo_tag_status = BMI088_GET_BITSLICE(data, BMI088_GYRO_FIFO_TAG);
}
}
return rslt;
}
/*!
* @brief This API enables or disable fifo tag in gyro sensor.
*/
uint16_t bmi088_set_gyro_fifo_tag(uint8_t fifo_tag, struct bmi088_dev *dev)
{
uint16_t rslt = 0;
uint8_t data, reg_addr;
/* Check for null pointer in the device structure*/
rslt = null_ptr_check(dev);
/* Proceed if null check is fine */
if (rslt == BMI088_OK)
{
if (fifo_tag <= BMI088_ENABLE)
{
/* Read the fifo config 0 register */
reg_addr = BMI088_GYRO_FIFO_CONFIG_0_REG;
rslt |= bmi088_get_gyro_regs(reg_addr, &data, BMI088_ONE, dev);
/* Write the fifo tag */
data = BMI088_SET_BITSLICE(data, BMI088_GYRO_FIFO_TAG, fifo_tag);
rslt |= bmi088_set_gyro_regs(reg_addr, &data, BMI088_ONE, dev);
}
else
{
rslt = BMI088_E_OUT_OF_RANGE;
}
}
return rslt;
}
/*!
* @brief This API enables or disables the FIFO full interrupt of the gyro sensor.
*/
uint16_t bmi088_set_gyro_fifo_full_int(struct bmi088_int_cfg *int_config, struct bmi088_dev *dev, uint8_t fifo_full_enable)
{
uint16_t rslt = 0;
uint8_t data[2] = { 0, 0 };
uint8_t reg_addr;
/* Check for null pointer in the device structure*/
rslt = null_ptr_check(dev);
/* Proceed if null check is fine */
if (rslt == BMI088_OK)
{
/* Read the Interrupt control register and Interrupt configuration register together */
reg_addr = BMI088_GYRO_INT_CTRL_REG;
rslt |= bmi088_get_gyro_regs(reg_addr, data, BMI088_TWO, dev);
if (rslt == BMI088_OK)
{
data[0] = BMI088_SET_BITSLICE(data[0], BMI088_GYRO_FIFO_EN, fifo_full_enable);
/* Interrupt pin or channel 3 */
if (int_config->gyro_int_channel == BMI088_INT_CHANNEL_3)
{
/* Update data with user configured bmi088_int_cfg structure */
data[1] = BMI088_SET_BITSLICE(data[1], BMI088_GYRO_INT3_LVL, int_config->gyro_int_pin_3_cfg.lvl);
data[1] = BMI088_SET_BITSLICE(data[1], BMI088_GYRO_INT3_OD, int_config->gyro_int_pin_3_cfg.output_mode);
}
/* Interrupt pin or channel 4 */
if (int_config->gyro_int_channel == BMI088_INT_CHANNEL_4)
{
/* Update data with user configured bmi088_int_cfg structure */
data[1] = BMI088_SET_BITSLICE(data[1], BMI088_GYRO_INT4_LVL, int_config->gyro_int_pin_4_cfg.lvl);
data[1] = BMI088_SET_BITSLICE(data[1], BMI088_GYRO_INT4_OD, int_config->gyro_int_pin_4_cfg.output_mode);
}
/* Both Interrupt pins or channels */
if (int_config->gyro_int_channel == BMI088_INT_CHANNEL_BOTH)
{
/* Update data with user configured bmi088_int_cfg structure */
data[1] = BMI088_SET_BITSLICE(data[1], BMI088_GYRO_INT3_LVL, int_config->gyro_int_pin_3_cfg.lvl);
data[1] = BMI088_SET_BITSLICE(data[1], BMI088_GYRO_INT3_OD, int_config->gyro_int_pin_3_cfg.output_mode);
data[1] = BMI088_SET_BITSLICE(data[1], BMI088_GYRO_INT4_LVL, int_config->gyro_int_pin_4_cfg.lvl);
data[1] = BMI088_SET_BITSLICE(data[1], BMI088_GYRO_INT4_OD, int_config->gyro_int_pin_4_cfg.output_mode);
}
/* Write to Interrupt control register and Interrupt configuration register together */
rslt |= bmi088_set_gyro_regs(reg_addr, data, BMI088_TWO, dev);
if (rslt == BMI088_OK)
{
/* Read the Interrupt Map register */
reg_addr = BMI088_GYRO_INT3_INT4_IO_MAP_REG;
rslt |= bmi088_get_gyro_regs(reg_addr, &data[0], BMI088_ONE, dev);
/* Interrupt pin or channel 3 */
if (int_config->gyro_int_channel == BMI088_INT_CHANNEL_3)
{
/* Map Interrupt pin 3 */
data[0] = BMI088_SET_BITSLICE(data[0], BMI088_GYRO_INT1_FIFO, BMI088_ONE);
}
/* Interrupt pin or channel 4 */
if (int_config->gyro_int_channel == BMI088_INT_CHANNEL_4)
{
/* Map Interrupt pin 4 */
data[0] = BMI088_SET_BITSLICE(data[0], BMI088_GYRO_INT2_FIFO, BMI088_ONE);
}
/* Both Interrupt pins or channels */
if (int_config->gyro_int_channel == BMI088_INT_CHANNEL_BOTH)
{
/* Map both Interrupt pins */
data[0] = BMI088_SET_BITSLICE(data[0], BMI088_GYRO_INT1_FIFO, BMI088_ONE);
data[0] = BMI088_SET_BITSLICE(data[0], BMI088_GYRO_INT2_FIFO, BMI088_ONE);
}
/* Write to Interrupt Map register */
rslt |= bmi088_set_gyro_regs(reg_addr, &data[0], BMI088_ONE, dev);
}
}
}
return rslt;
}
/*!
* @brief This API enables or disables the FIFO watermark interrupt of the gyro sensor.
*/
uint16_t bmi088_set_gyro_fifo_wm_int(struct bmi088_int_cfg *int_config, struct bmi088_dev *dev, uint8_t fifo_wm_enable)
{
uint16_t rslt = 0;
uint8_t data, reg_addr;
/* Check for null pointer in the device structure*/
rslt = null_ptr_check(dev);
/* Proceed if null check is fine */
if (rslt == BMI088_OK)
{
reg_addr = BMI088_GYRO_INT3_INT4_IO_CONF_REG;
/* Read interrupt configuration register */
rslt = bmi088_get_gyro_regs(reg_addr, &data, BMI088_ONE, dev);
if (rslt == BMI088_OK)
{
/* Interrupt pin or channel 3 */
if (int_config->gyro_int_channel == BMI088_INT_CHANNEL_3)
{
/* Update data with user configured bmi088_int_cfg structure */
data = BMI088_SET_BITSLICE(data, BMI088_GYRO_INT3_LVL, int_config->gyro_int_pin_3_cfg.lvl);
data = BMI088_SET_BITSLICE(data, BMI088_GYRO_INT3_OD, int_config->gyro_int_pin_3_cfg.output_mode);
}
/* Interrupt pin or channel 4 */
if (int_config->gyro_int_channel == BMI088_INT_CHANNEL_4)
{
/* Update data with user configured bmi088_int_cfg structure */
data = BMI088_SET_BITSLICE(data, BMI088_GYRO_INT4_LVL, int_config->gyro_int_pin_4_cfg.lvl);
data = BMI088_SET_BITSLICE(data, BMI088_GYRO_INT4_OD, int_config->gyro_int_pin_4_cfg.output_mode);
}
/* Both Interrupt pins or channels */
if (int_config->gyro_int_channel == BMI088_INT_CHANNEL_BOTH)
{
/* Update data with user configured bmi088_int_cfg structure */
data = BMI088_SET_BITSLICE(data, BMI088_GYRO_INT3_LVL, int_config->gyro_int_pin_3_cfg.lvl);
data = BMI088_SET_BITSLICE(data, BMI088_GYRO_INT3_OD, int_config->gyro_int_pin_3_cfg.output_mode);
data = BMI088_SET_BITSLICE(data, BMI088_GYRO_INT4_LVL, int_config->gyro_int_pin_4_cfg.lvl);
data = BMI088_SET_BITSLICE(data, BMI088_GYRO_INT4_OD, int_config->gyro_int_pin_4_cfg.output_mode);
}
/* write to interrupt configuration register */
rslt = bmi088_set_gyro_regs(reg_addr, &data, BMI088_ONE, dev);
}
}
/* Read the Interrupt Map register */
reg_addr = BMI088_GYRO_INT3_INT4_IO_MAP_REG;
rslt |= bmi088_get_gyro_regs(reg_addr, &data, BMI088_ONE, dev);
/* Interrupt pin or channel 3 */
if (int_config->gyro_int_channel == BMI088_INT_CHANNEL_3)
{
/* Map Interrupt pin 3 */
data = BMI088_SET_BITSLICE(data, BMI088_GYRO_INT1_FIFO, BMI088_ONE);
}
/* Interrupt pin or channel 4 */
if (int_config->gyro_int_channel == BMI088_INT_CHANNEL_4)
{
/* Map Interrupt pin 4 */
data = BMI088_SET_BITSLICE(data, BMI088_GYRO_INT2_FIFO, BMI088_ONE);
}
/* Both Interrupt pins or channels */
if (int_config->gyro_int_channel == BMI088_INT_CHANNEL_BOTH)
{
/* Map both Interrupt pins */
data = BMI088_SET_BITSLICE(data, BMI088_GYRO_INT1_FIFO, BMI088_ONE);
data = BMI088_SET_BITSLICE(data, BMI088_GYRO_INT2_FIFO, BMI088_ONE);
}
/* Write to Interrupt Map register */
rslt |= bmi088_set_gyro_regs(reg_addr, &data, BMI088_ONE, dev);
/* Read the Interrupt enable register */
reg_addr = BMI088_GYRO_INT_EN_REG;
rslt |= bmi088_get_gyro_regs(reg_addr, &data, BMI088_ONE, dev);
/* Write to Interrupt enable register */
data = BMI088_SET_BITSLICE(data, BMI088_GYRO_INT_EN, fifo_wm_enable);
rslt |= bmi088_set_gyro_regs(reg_addr, &data, BMI088_ONE, dev);
return rslt;
}
/*****************************************************************************/
/* Static function definition */
/*!
* @brief This API is used to validate the device structure pointer for
* null conditions.
*/
static uint16_t null_ptr_check(const struct bmi088_dev *dev)
{
uint16_t rslt;
if ((dev == NULL) || (dev->read == NULL) || (dev->write == NULL) || (dev->delay_ms == NULL))
{
/* Device structure pointer is not valid */
rslt = BMI088_E_NULL_PTR;
}
else
{
/* Device structure is fine */
rslt = BMI088_OK;
}
return rslt;
}
/*!
* @brief This API is used to reset the FIFO related configurations
* in the Accel fifo_frame structure.
*/
static void reset_accel_fifo_data_structure(const struct bmi088_dev *dev)
{
/* Prepare for next accel FIFO read by resetting accel FIFO's
internal data structures*/
dev->accel_fifo->byte_start_idx = 0;
dev->accel_fifo->sensor_time = 0;
dev->accel_fifo->skipped_frame_count = 0;
dev->accel_fifo->dropped_frame_count = 0;
}
/*!
* @brief This API computes the number of bytes of accel FIFO data
* which is to be parsed in header-less mode.
*/
static void get_accel_len_to_parse(uint16_t *start_idx, uint16_t *len, const uint16_t *accel_count, const struct bmi088_dev *dev)
{
uint8_t dummy_byte_spi = 0;
/*Check if this is the first iteration of data unpacking
if yes, then consider dummy byte on SPI*/
if (dev->accel_fifo->byte_start_idx == 0)
{
dummy_byte_spi = dev->dummy_byte;
}
/*Data start index*/
*start_idx = dev->accel_fifo->byte_start_idx + dummy_byte_spi;
if (dev->accel_fifo->fifo_data_enable == BMI088_FIFO_A_ENABLE)
{
/* Len has the number of bytes to loop for */
*len = (uint16_t)(((*accel_count) * BMI088_FIFO_A_LENGTH) + dummy_byte_spi);
}
else
{
/* No sensor is enabled in FIFO,
so there will be no accel data.
Update the data index as complete*/
*start_idx = dev->accel_fifo->length;
}
if ((*len) > dev->accel_fifo->length)
{
/* Handling the case where more data is requested
than available */
*len = dev->accel_fifo->length;
}
}
/*!
* @brief This API checks the accel fifo read data as empty frame, if it
* is empty frame then moves the index to last byte.
*/
static void check_empty_accel_fifo(uint16_t *data_index, const struct bmi088_dev *dev)
{
if ((*data_index + 2) < dev->accel_fifo->length)
{
/* Check if FIFO is empty */
if ((dev->accel_fifo->data[*data_index] == FIFO_MSB_CONFIG_CHECK)
&& (dev->accel_fifo->data[*data_index + BMI088_ONE] == FIFO_LSB_CONFIG_CHECK))
{
/* Update the data index as complete*/
*data_index = dev->accel_fifo->length;
}
}
}
/*!
* @brief This API is used to parse the accelerometer data from the
* FIFO data in header mode.
*/
static void extract_accel_header_mode(struct bmi088_sensor_data *accel_data, uint16_t *accel_length, const struct bmi088_dev *dev)
{
uint8_t frame_header = 0;
uint16_t data_index;
uint16_t accel_index = 0;
uint16_t frame_to_read = *accel_length;
/*Check if this is the first iteration of data unpacking
if yes, then consider dummy byte on SPI*/
if (dev->accel_fifo->byte_start_idx == 0)
{
dev->accel_fifo->byte_start_idx = dev->dummy_byte;
}
for (data_index = dev->accel_fifo->byte_start_idx; data_index < dev->accel_fifo->length;)
{
/* Header byte is stored in the variable frame_header */
frame_header = dev->accel_fifo->data[data_index];
/* Get the frame details from header */
frame_header = frame_header & BMI088_FIFO_TAG_INTR_MASK;
/* Index is moved to next byte where the data is starting */
data_index++;
switch (frame_header)
{
/* Accel frame */
case FIFO_HEAD_A:
{
unpack_accel_frm(accel_data, &data_index, &accel_index, frame_header, dev);
}
break;
/* Sensor time frame */
case FIFO_HEAD_SENSOR_TIME:
{
unpack_sensortime_frame(&data_index, dev);
}
break;
/* Skip frame */
case FIFO_HEAD_SKIP_FRAME:
{
unpack_accel_skipped_frame(&data_index, dev);
}
break;
/* Input config frame */
case FIFO_HEAD_INPUT_CONFIG:
{
move_to_next_accel_frame(&data_index, BMI088_ONE, dev);
}
break;
/* Sample drop frame */
case FIFO_HEAD_SAMPLE_DROP:
{
unpack_accel_dropped_frame(&data_index, dev);
}
break;
/* Over read FIFO data */
case FIFO_HEAD_OVER_READ_MSB:
{
/* Update the data index as complete */
data_index = dev->accel_fifo->length;
}
break;
default:
break;
}
if (frame_to_read == accel_index)
{
/* Number of frames to be read is completed */
break;
}
}
/* Update number of accel data read */
*accel_length = accel_index;
/* Update the accel frame index */
dev->accel_fifo->byte_start_idx = data_index;
}
/*!
* @brief This API is used to parse the accelerometer data from the
* FIFO data in both header mode and header-less mode.
* It updates the idx value which is used to store the index of
* the current data byte which is parsed.
*/
static void unpack_accel_frm(struct bmi088_sensor_data *accel, uint16_t *idx, uint16_t *accel_idx, uint8_t frm, const struct bmi088_dev *dev)
{
uint8_t is_buffer_end_reached = 0;
if ((frm == FIFO_HEAD_A) || (frm == BMI088_FIFO_A_ENABLE))
{
/* Partial read, then skip the data */
if ((*idx + BMI088_FIFO_A_LENGTH) > dev->accel_fifo->length)
{
/* Update the data index as complete */
*idx = dev->accel_fifo->length;
is_buffer_end_reached = 1;
}
if (!is_buffer_end_reached)
{
/* Unpack the data array into the structure instance "accel" */
unpack_accel_data(&accel[*accel_idx], *idx, dev);
/* Move the data index */
*idx = *idx + BMI088_FIFO_A_LENGTH;
(*accel_idx)++;
}
}
}
/*!
* @brief This API is used to parse the accelerometer data from the
* FIFO data and store it in the instance of the structure bmi088_sensor_data.
*/
static void unpack_accel_data(struct bmi088_sensor_data *accel_data, uint16_t data_start_index, const struct bmi088_dev *dev)
{
uint16_t data_lsb;
uint16_t data_msb;
/* Accel raw x data */
data_lsb = dev->accel_fifo->data[data_start_index++];
data_msb = dev->accel_fifo->data[data_start_index++];
accel_data->x = (int16_t)((data_msb << BMI088_EIGHT) | data_lsb);
/* Accel raw y data */
data_lsb = dev->accel_fifo->data[data_start_index++];
data_msb = dev->accel_fifo->data[data_start_index++];
accel_data->y = (int16_t)((data_msb << BMI088_EIGHT) | data_lsb);
/* Accel raw z data */
data_lsb = dev->accel_fifo->data[data_start_index++];
data_msb = dev->accel_fifo->data[data_start_index++];
accel_data->z = (int16_t)((data_msb << BMI088_EIGHT) | data_lsb);
}
/*!
* @brief This API is used to parse and store the sensor time from the
* FIFO data in the structure instance dev.
*/
static void unpack_sensortime_frame(uint16_t *data_index, const struct bmi088_dev *dev)
{
uint32_t sensor_time_byte3 = 0;
uint16_t sensor_time_byte2 = 0;
uint8_t sensor_time_byte1 = 0;
/* Partial read, then move the data index to last data */
if ((*data_index + BMI088_SENSOR_TIME_LENGTH) > dev->accel_fifo->length)
{
/* Update the data index as complete */
*data_index = dev->accel_fifo->length;
}
else
{
sensor_time_byte3 = dev->accel_fifo->data[(*data_index) + BMI088_SENSOR_TIME_MSB_BYTE] << BMI088_SIXTEEN;
sensor_time_byte2 = dev->accel_fifo->data[(*data_index) + BMI088_SENSOR_TIME_XLSB_BYTE] << BMI088_EIGHT;
sensor_time_byte1 = dev->accel_fifo->data[(*data_index) + BMI088_SENSOR_TIME_LSB_BYTE];
/* Sensor time */
dev->accel_fifo->sensor_time = (uint32_t)(sensor_time_byte3 | sensor_time_byte2 | sensor_time_byte1);
*data_index = (*data_index) + BMI088_SENSOR_TIME_LENGTH;
}
}
/*!
* @brief This API is used to parse and store the skipped_frame_count from
* the accelerometer FIFO data in the structure instance dev.
*/
static void unpack_accel_skipped_frame(uint16_t *data_index, const struct bmi088_dev *dev)
{
/* Partial read, then move the data index to last data */
if (*data_index >= dev->accel_fifo->length)
{
/* Update the data index as complete */
*data_index = dev->accel_fifo->length;
}
else
{
dev->accel_fifo->skipped_frame_count = dev->accel_fifo->data[*data_index];
/* Move the data index */
*data_index = (*data_index) + 1;
}
}
/*!
* @brief This API is used to parse and store the dropped_frame_count from
* the accelerometer FIFO data in the structure instance dev.
*/
static void unpack_accel_dropped_frame(uint16_t *data_index, const struct bmi088_dev *dev)
{
uint8_t dropped_frame = 0;
/* Partial read, then move the data index to last data */
if (*data_index >= dev->accel_fifo->length)
{
/*Update the data index as complete*/
*data_index = dev->accel_fifo->length;
}
else
{
/* Extract accel dropped frame count */
dropped_frame = dev->accel_fifo->data[*data_index] & ACCEL_FIFO_DROP;
/* Move the data index and update the dropped frame count */
if (dropped_frame == ACCEL_FIFO_DROP)
{
*data_index = (*data_index) + BMI088_FIFO_A_LENGTH;
dev->accel_fifo->dropped_frame_count = dev->accel_fifo->dropped_frame_count + 1;
}
}
}
/*!
* @brief This API is used to move the data index ahead of the
* current_frame_length parameter when unnecessary FIFO data appears while
* extracting the accel data.
*/
static void move_to_next_accel_frame(uint16_t *data_index, uint8_t current_frame_length, const struct bmi088_dev *dev)
{
/* Partial read, then move the data index to last data */
if ((*data_index + current_frame_length) > dev->accel_fifo->length)
{
/* Update the data index as complete */
*data_index = dev->accel_fifo->length;
}
else
{
/* Move the data index to next frame */
*data_index = *data_index + current_frame_length;
}
}
/*!
* @brief This API is used to reset the gyro FIFO related configurations
* in the fifo_frame structure.
*/
static void reset_gyro_fifo_data_structure(const struct bmi088_dev *dev)
{
/* Prepare for next gyro FIFO read by resetting gyro FIFO's
internal data structures */
dev->gyro_fifo->byte_start_idx = 0;
dev->gyro_fifo->sensor_time = 0;
dev->gyro_fifo->skipped_frame_count = 0;
dev->gyro_fifo->dropped_frame_count = 0;
}
/*!
* @brief This API computes the number of bytes of Gyro FIFO data which is
* to be parsed in header-less mode.
*/
static void get_gyro_len_to_parse(uint16_t *start_idx, uint16_t *len, const uint16_t *gyro_count, const struct bmi088_dev *dev)
{
/* Data start index */
*start_idx = dev->gyro_fifo->byte_start_idx;
if (dev->gyro_fifo->fifo_data_enable == BMI088_GYRO_ALL_INT_DATA)
{
dev->gyro_fifo->frame_length = BMI088_FIFO_G_ALL_DATA_LENGTH;
}
else if (dev->gyro_fifo->fifo_data_enable == BMI088_GYRO_X_DATA)
{
dev->gyro_fifo->frame_length = BMI088_FIFO_G_X_LENGTH;
}
else if (dev->gyro_fifo->fifo_data_enable == BMI088_GYRO_Y_DATA)
{
dev->gyro_fifo->frame_length = BMI088_FIFO_G_Y_LENGTH;
}
else if (dev->gyro_fifo->fifo_data_enable == BMI088_GYRO_Z_DATA)
{
dev->gyro_fifo->frame_length = BMI088_FIFO_G_Z_LENGTH;
}
else
{
/* No sensor is enabled in FIFO,
so there will be no gyro data.
Update the data index as complete */
*start_idx = dev->gyro_fifo->length;
dev->gyro_fifo->frame_length = 0;
}
/* Len has the number of bytes to loop for */
*len = (uint16_t)((*gyro_count) * dev->gyro_fifo->frame_length);
/* Handling the case where more data is requested than available */
if ((*len) > dev->gyro_fifo->length)
{
/* Len is equal to the FIFO length */
*len = dev->gyro_fifo->length;
}
}
/*!
* @brief This API is used to parse the gyroscope data from the
* FIFO data in header-less mode and update the data_index value
* which is used to store the index of the current data byte
* which is parsed.
*/
static uint16_t unpack_gyro_frm(struct bmi088_sensor_data *data, uint16_t *idx, uint16_t *gyro_idx, uint8_t frm,
const struct bmi088_dev *dev)
{
uint16_t rslt = 0;
uint8_t is_buffer_end_reached = 0;
if ((frm == BMI088_GYRO_ALL_INT_DATA) || (frm == BMI088_GYRO_X_DATA)
|| (frm == BMI088_GYRO_Y_DATA)
|| (frm == BMI088_GYRO_Z_DATA))
{
/* Partial read, then skip the data */
if ((*idx + dev->gyro_fifo->frame_length) > dev->gyro_fifo->length)
{
/*update the data index as complete*/
*idx = dev->gyro_fifo->length;
is_buffer_end_reached = 1;
}
if (!is_buffer_end_reached)
{
/* Unpack the data array into Gyro sensor data structure */
unpack_gyro_data(&data[*gyro_idx], *idx, dev);
/* move the data index */
*idx = *idx + dev->gyro_fifo->frame_length;
(*gyro_idx)++;
}
}
return rslt;
}
/*!
* @brief This API is used to parse the gyroscope data from
* the FIFO data and store it in the instance of the structure
* gyro_data.
*/
static void unpack_gyro_data(struct bmi088_sensor_data *gyro_data, uint16_t start_idx, const struct bmi088_dev *dev)
{
uint16_t data_lsb;
uint16_t data_msb;
/* Gyro raw x data */
data_lsb = dev->gyro_fifo->data[start_idx++];
data_msb = dev->gyro_fifo->data[start_idx++];
gyro_data->x = (int16_t)((data_msb << BMI088_EIGHT) | data_lsb);
/* Gyro raw y data */
data_lsb = dev->gyro_fifo->data[start_idx++];
data_msb = dev->gyro_fifo->data[start_idx++];
gyro_data->y = (int16_t)((data_msb << BMI088_EIGHT) | data_lsb);
/* Gyro raw z data */
data_lsb = dev->gyro_fifo->data[start_idx++];
data_msb = dev->gyro_fifo->data[start_idx++];
gyro_data->z = (int16_t)((data_msb << BMI088_EIGHT) | data_lsb);
}
/*!
* @brief This API checks the gyro fifo read data as empty frame, if it
* is empty frame then moves the index to last byte.
*/
static void check_empty_gyro_fifo(uint16_t *data_index, const struct bmi088_dev *dev)
{
if ((*data_index + 2) < dev->gyro_fifo->length)
{
/* Check if FIFO is empty */
if ((dev->gyro_fifo->data[*data_index] == FIFO_MSB_CONFIG_CHECK)
&& (dev->gyro_fifo->data[*data_index + BMI088_ONE] == FIFO_LSB_CONFIG_CHECK))
{
/* Update the data index as complete */
*data_index = dev->gyro_fifo->length;
}
}
}
#endif
/** @}*/