Skip to content

Commit

Permalink
Merge pull request #29 from boschsensortec/Release_BMA400_bma400_v1.5.10
Browse files Browse the repository at this point in the history
Release v1.5.10
  • Loading branch information
eks-99th authored May 10, 2024
2 parents 13086eb + 1b893c3 commit 24dc593
Show file tree
Hide file tree
Showing 17 changed files with 763 additions and 394 deletions.
2 changes: 1 addition & 1 deletion LICENSE
Original file line number Diff line number Diff line change
@@ -1,4 +1,4 @@
Copyright (c) 2020 Bosch Sensortec GmbH. All rights reserved.
Copyright (c) 2024 Bosch Sensortec GmbH. All rights reserved.

BSD-3-Clause

Expand Down
19 changes: 10 additions & 9 deletions README.md
Original file line number Diff line number Diff line change
@@ -1,22 +1,22 @@
# BMA400 Sensor API
# BMA400 SensorAPI

> Bosch Sensortec's BMA400 accelerometer sensor API
> Bosch Sensortec's BMA400 accelerometer SensorAPI
## Sensor Overview
The BMA400 is the first real ultra-low power acceleration sensor that minimizes power consumption without compromising on performance. Featuring 12-bit digital resolution, continuous measurement and a defined selectable bandwidth combined with ultra-low power the BMA400 allows low-noise measurement of accelerations in three perpendicular axes. The BMA400 thus senses tilt, orientation, tab/double tab, and enables plug 'n' play step counting with activity recognition especially suited for wearable devices which need a long-lasting battery lifetime.
The BMA400 is the first real ultra-low power acceleration sensor that minimizes power consumption without compromising performance. Featuring 12-bit digital resolution, continuous measurement, and a defined selectable bandwidth combined with ultra-low power, the BMA400 allows low-noise measurement of accelerations in three perpendicular axes. Therefore, the BMA400 senses tilt, orientation, tab/double tab, and enables Plug and Play step counting with activity recognition especially suited for wearable devices that need a long-lasting battery lifetime.

Due to the continuous measurement principle and defined bandwidth, the BMA400 is the ideal solution for smart home applications such as smart indoor climate systems and smart home security systems.
In the latter, the BMA400 can distinguish between real alarm situations (like broken glass) and false signals coming from random vibrations thereby avoiding false alarms.
In the latter, the BMA400 can distinguish between real alarm situations (like broken glass) and false signals from random vibrations, thereby avoiding false alarms.

#### Applications

- IoT and smart home applications (e.g. indoor climate systems, security systems)
- Activity tracking and step counting in wearable devices (e.g. fitness bands, smart and regular watches, hearables)
- Industrial applications (e.g. predictive maintenance, package tracking)
- IoT and smart home applications (e.g., indoor climate systems, security systems)
- Activity tracking and step counting in wearable devices (e.g., fitness bands, smart and regular watches, hearables)
- Industrial applications (e.g., predictive maintenance, package tracking)
- Power management of consumer end-devices based on motion


#### Important links:
For more information, please refer to:
#### Important Links:

- [BMA400 product page](https://www.bosch-sensortec.com/bst/products/all_products/bma400_1)
- [BMA400 github page](https://github.com/BoschSensortec/BMA400-API)
Expand All @@ -25,3 +25,4 @@ For more information, please refer to:
- [Community support page](https://community.bosch-sensortec.com)

------------

22 changes: 10 additions & 12 deletions bma400.c
Original file line number Diff line number Diff line change
@@ -1,5 +1,5 @@
/**
* Copyright (c) 2020 Bosch Sensortec GmbH. All rights reserved.
* Copyright (c) 2024 Bosch Sensortec GmbH. All rights reserved.
*
* BSD-3-Clause
*
Expand Down Expand Up @@ -31,8 +31,8 @@
* POSSIBILITY OF SUCH DAMAGE.
*
* @file bma400.c
* @date 2020-06-05
* @version v1.5.8
* @date 2024-05-10
* @version v1.5.10
*
*/

Expand Down Expand Up @@ -510,7 +510,7 @@ static int8_t read_fifo(struct bma400_fifo_data *fifo, struct bma400_dev *dev);
* @return Nothing
*/
static void unpack_accel_frame(struct bma400_fifo_data *fifo,
struct bma400_sensor_data *accel_data,
struct bma400_fifo_sensor_data *accel_data,
uint16_t *frame_count,
const struct bma400_dev *dev);

Expand Down Expand Up @@ -544,7 +544,7 @@ static void check_frame_available(const struct bma400_fifo_data *fifo,
* @return Nothing
*/
static void unpack_accel(const struct bma400_fifo_data *fifo,
struct bma400_sensor_data *accel_data,
struct bma400_fifo_sensor_data *accel_data,
uint16_t *data_index,
uint8_t accel_width,
uint8_t frame_header);
Expand Down Expand Up @@ -728,24 +728,22 @@ int8_t bma400_get_regs(uint8_t reg_addr, uint8_t *reg_data, uint32_t len, struct
{
int8_t rslt;
uint16_t index;
uint8_t temp_buff[BMA400_MAX_LEN];

/* Check for null pointer in the device structure */
rslt = null_ptr_check(dev);

/* Proceed if null check is fine */
if ((rslt == BMA400_OK) && (reg_data != NULL))
{
uint32_t temp_len = len + dev->dummy_byte;
uint8_t temp_buff[temp_len];

if (dev->intf != BMA400_I2C_INTF)
{
/* If interface selected is SPI */
reg_addr = reg_addr | BMA400_SPI_RD_MASK;
}

/* Read the data from the reg_addr */
dev->intf_rslt = dev->read(reg_addr, temp_buff, temp_len, dev->intf_ptr);
dev->intf_rslt = dev->read(reg_addr, temp_buff, (len + dev->dummy_byte), dev->intf_ptr);
if (dev->intf_rslt == BMA400_INTF_RET_SUCCESS)
{
for (index = 0; index < len; index++)
Expand Down Expand Up @@ -1394,7 +1392,7 @@ int8_t bma400_get_fifo_data(struct bma400_fifo_data *fifo, struct bma400_dev *de
}

int8_t bma400_extract_accel(struct bma400_fifo_data *fifo,
struct bma400_sensor_data *accel_data,
struct bma400_fifo_sensor_data *accel_data,
uint16_t *frame_count,
const struct bma400_dev *dev)
{
Expand Down Expand Up @@ -3050,7 +3048,7 @@ static int8_t read_fifo(struct bma400_fifo_data *fifo, struct bma400_dev *dev)
}

static void unpack_accel_frame(struct bma400_fifo_data *fifo,
struct bma400_sensor_data *accel_data,
struct bma400_fifo_sensor_data *accel_data,
uint16_t *frame_count,
const struct bma400_dev *dev)
{
Expand Down Expand Up @@ -3302,7 +3300,7 @@ static void check_frame_available(const struct bma400_fifo_data *fifo,
}

static void unpack_accel(const struct bma400_fifo_data *fifo,
struct bma400_sensor_data *accel_data,
struct bma400_fifo_sensor_data *accel_data,
uint16_t *data_index,
uint8_t accel_width,
uint8_t frame_header)
Expand Down
12 changes: 6 additions & 6 deletions bma400.h
Original file line number Diff line number Diff line change
@@ -1,5 +1,5 @@
/**
* Copyright (c) 2020 Bosch Sensortec GmbH. All rights reserved.
* Copyright (c) 2024 Bosch Sensortec GmbH. All rights reserved.
*
* BSD-3-Clause
*
Expand Down Expand Up @@ -31,8 +31,8 @@
* POSSIBILITY OF SUCH DAMAGE.
*
* @file bma400.h
* @date 2020-06-05
* @version v1.5.8
* @date 2024-05-10
* @version v1.5.10
*
*/

Expand Down Expand Up @@ -326,7 +326,7 @@ int8_t bma400_get_fifo_data(struct bma400_fifo_data *fifo, struct bma400_dev *de
* \ingroup bma400ApiFifo
* \page bma400_api_bma400_extract_accel bma400_extract_accel
* \code
* int8_t bma400_extract_accel(struct bma400_fifo_data *fifo, struct bma400_sensor_data *accel_data,
* int8_t bma400_extract_accel(struct bma400_fifo_data *fifo, struct bma400_fifo_sensor_data *accel_data,
* uint16_t *frame_count, const struct bma400_dev *dev);
* \endcode
* @details This API parses and extracts the accelerometer frames, FIFO time
Expand All @@ -339,7 +339,7 @@ int8_t bma400_get_fifo_data(struct bma400_fifo_data *fifo, struct bma400_dev *de
*
* @param[in,out] fifo : Pointer to the FIFO structure.
*
* @param[out] accel_data : Structure instance of bma400_sensor_data where
* @param[out] accel_data : Structure instance of bma400_fifo_sensor_data where
* the accelerometer data from FIFO is extracted
* and stored after calling this API
*
Expand All @@ -355,7 +355,7 @@ int8_t bma400_get_fifo_data(struct bma400_fifo_data *fifo, struct bma400_dev *de
* @retval -ve value -> Error
*/
int8_t bma400_extract_accel(struct bma400_fifo_data *fifo,
struct bma400_sensor_data *accel_data,
struct bma400_fifo_sensor_data *accel_data,
uint16_t *frame_count,
const struct bma400_dev *dev);

Expand Down
26 changes: 22 additions & 4 deletions bma400_defs.h
Original file line number Diff line number Diff line change
@@ -1,5 +1,5 @@
/**
* Copyright (c) 2020 Bosch Sensortec GmbH. All rights reserved.
* Copyright (c) 2024 Bosch Sensortec GmbH. All rights reserved.
*
* BSD-3-Clause
*
Expand Down Expand Up @@ -31,8 +31,8 @@
* POSSIBILITY OF SUCH DAMAGE.
*
* @file bma400_defs.h
* @date 2020-06-05
* @version v1.5.8
* @date 2024-05-10
* @version v1.5.10
*
*/

Expand Down Expand Up @@ -121,6 +121,9 @@
#define BMA400_I2C_ADDRESS_SDO_LOW UINT8_C(0x14)
#define BMA400_I2C_ADDRESS_SDO_HIGH UINT8_C(0x15)

/* Maximum read length */
#define BMA400_MAX_LEN UINT8_C(128)

/* Power mode configurations */
#define BMA400_MODE_NORMAL UINT8_C(0x02)
#define BMA400_MODE_SLEEP UINT8_C(0x00)
Expand Down Expand Up @@ -430,7 +433,7 @@

/* BMA400 FIFO data masks */
#define BMA400_FIFO_HEADER_MASK UINT8_C(0x3E)
#define BMA400_FIFO_BYTES_OVERREAD UINT8_C(25)
#define BMA400_FIFO_BYTES_OVERREAD UINT8_C(100)
#define BMA400_AWIDTH_MASK UINT8_C(0xEF)
#define BMA400_FIFO_DATA_EN_MASK UINT8_C(0x0E)

Expand Down Expand Up @@ -1296,6 +1299,21 @@ struct bma400_sensor_data
uint32_t sensortime;
};

/*
* BMA400 sensor data for FIFO
*/
struct bma400_fifo_sensor_data
{
/* X-axis sensor data */
int16_t x;

/* Y-axis sensor data */
int16_t y;

/* Z-axis sensor data */
int16_t z;
};

/*
* BMA400 interrupt selection
*/
Expand Down
99 changes: 70 additions & 29 deletions examples/accelerometer/accelerometer.c
Original file line number Diff line number Diff line change
@@ -1,28 +1,79 @@
/*
* Copyright (C) 2020 Bosch Sensortec GmbH
/**
* Copyright (c) 2024 Bosch Sensortec GmbH. All rights reserved.
*
* The license is available at root folder
* BSD-3-Clause
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions are met:
*
* 1. Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
*
* 2. 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.
*
* 3. Neither the name of the copyright holder nor the names of its
* 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 THE
* 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.
*
*/

/*!
* @ingroup bma400Examples
* @defgroup bma400ExamplesAccelerometer Accelerometer read
* @brief To read accelerometer xyz data for defined range and ODR
* \include accelerometer.c
*/

#include <stdio.h>
#include "bma400.h"
#include "common.h"

/************************************************************************/
/********* Macros *************/
/************************************************************************/

/* Earth's gravity in m/s^2 */
#define GRAVITY_EARTH (9.80665f)

/* 39.0625us per tick */
#define SENSOR_TICK_TO_S (0.0000390625f)

static float lsb_to_ms2(int16_t accel_data, uint8_t g_range, uint8_t bit_width);
/************************************************************************/
/********* Static APIs *************/
/************************************************************************/

/*!
* @brief This internal API converts raw sensor values(LSB) to meters per seconds square.
*
* @param[in] accel_data : Raw sensor value.
* @param[in] g_range : Accel Range selected (2G, 4G, 8G, 16G).
* @param[in] bit_width : Resolution of the sensor.
*
* @return Accel values in meters per second square.
*
*/
static float lsb_to_ms2(int16_t accel_data, uint8_t g_range, uint8_t bit_width)
{
float accel_ms2;
int16_t half_scale;

half_scale = 1 << (bit_width - 1);
accel_ms2 = (GRAVITY_EARTH * accel_data * g_range) / half_scale;

return accel_ms2;
}

/************************************************************************/
/********* Main Function *************/
/************************************************************************/

int main(int argc, char const *argv[])
{
Expand All @@ -39,15 +90,15 @@ int main(int argc, char const *argv[])
* For I2C : BMA400_I2C_INTF
* For SPI : BMA400_SPI_INTF
*/
rslt = bma400_interface_init(&bma, BMA400_SPI_INTF);
rslt = bma400_interface_init(&bma, BMA400_I2C_INTF);
bma400_check_rslt("bma400_interface_init", rslt);

rslt = bma400_soft_reset(&bma);
bma400_check_rslt("bma400_soft_reset", rslt);

rslt = bma400_init(&bma);
bma400_check_rslt("bma400_init", rslt);

rslt = bma400_soft_reset(&bma);
bma400_check_rslt("bma400_soft_reset", rslt);

/* Select the type of configuration to be modified */
conf.type = BMA400_ACCEL;

Expand Down Expand Up @@ -94,7 +145,8 @@ int main(int argc, char const *argv[])
z = lsb_to_ms2(data.z, 2, 12);
t = (float)data.sensortime * SENSOR_TICK_TO_S;

printf("Gravity-x : %.2f, Gravity-y : %.2f, Gravity-z : %.2f, t(s) : %.4f\r\n", x, y, z, t);
printf("Acc_Raw_X : %d Acc_Raw_Y : %d Acc_Raw_Z : %d", data.x, data.y, data.z);
printf("\tAcc_ms2_X : %.2f, Acc_ms2_Y : %.2f, Acc_ms2_Z : %.2f, t(s) : %.4f\n", x, y, z, t);
n_samples--;
}
}
Expand All @@ -120,7 +172,8 @@ int main(int argc, char const *argv[])
y = lsb_to_ms2(data.y, 2, 12);
z = lsb_to_ms2(data.z, 2, 12);

printf("Gravity-x : %.2f, Gravity-y : %.2f, Gravity-z : %.2f\r\n", x, y, z);
printf("Acc_Raw_X : %d Acc_Raw_Y : %d Acc_Raw_Z : %d", data.x, data.y, data.z);
printf("\tAcc_ms2_X : %.2f, Acc_ms2_Y : %.2f, Acc_ms2_Z : %.2f\n", x, y, z);
n_samples--;
}
}
Expand All @@ -129,15 +182,3 @@ int main(int argc, char const *argv[])

return rslt;
}

static float lsb_to_ms2(int16_t accel_data, uint8_t g_range, uint8_t bit_width)
{
float accel_ms2;
int16_t half_scale;

half_scale = 1 << (bit_width - 1);
accel_ms2 = (GRAVITY_EARTH * accel_data * g_range) / half_scale;

return accel_ms2;

}
Loading

0 comments on commit 24dc593

Please sign in to comment.