diff --git a/Hello_World/Makefile b/Hello_World/Makefile
index 02d4d978a06834b67511ee9796996756000d424c..4f67e2b847a9d1be39957ff39e96a2b33c721846 100644
--- a/Hello_World/Makefile
+++ b/Hello_World/Makefile
@@ -74,6 +74,8 @@ SRCS  += bosch.c
 SRCS  += bhy_support.c bhy_uc_driver.c bhy.c
 SRCS  += MAX77650-Arduino-Library.c
 SRCS  += bme680.h
+SRCS  += bma400.c
+
 # Where to find source files for this test
 VPATH = .
 
@@ -93,6 +95,9 @@ VPATH += ../lib/maxim/MAX77650-Arduino-Library
 IPATH += ../lib/bosch/BME680_driver
 VPATH += ../lib/bosch/BME680_driver
 
+IPATH += ../lib/bosch/BMA400-API
+VPATH += ../lib/bosch/BMA400-API
+
 # Enable assertion checking for development
 PROJ_CFLAGS+=-DMXC_ASSERT_ENABLE
 
diff --git a/lib/bosch/BMA400-API/README.md b/lib/bosch/BMA400-API/README.md
new file mode 100644
index 0000000000000000000000000000000000000000..d05a7ff47cdbdbbe31c2258352f2c4bf881a756f
--- /dev/null
+++ b/lib/bosch/BMA400-API/README.md
@@ -0,0 +1,18 @@
+# BMA400 Sensor API
+
+> This repository contains Bosch Sensortec's BMA400 accelerometer sensor API
+
+## Sensor Overview
+The BMA400 is the first real ultra-low power acceleration sensor 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. Thanks to the continuous measurement principle and always-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, the new acceleration sensor avoids 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)
+- Power management of consumer end-devices based on motion
+
+
+For more information refer product page [Link](https://www.bosch-sensortec.com/bst/products/all_products/bma400_1)
+
+# Copyright (C) 2018 Bosch Sensortec GmbH
\ No newline at end of file
diff --git a/lib/bosch/BMA400-API/bma400.c b/lib/bosch/BMA400-API/bma400.c
new file mode 100644
index 0000000000000000000000000000000000000000..e64e7954b4b7aa3351551223cb786dabe459a34d
--- /dev/null
+++ b/lib/bosch/BMA400-API/bma400.c
@@ -0,0 +1,2909 @@
+/**\mainpage
+ * Copyright (C) 2017 - 2018 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		bma400.c
+ * Date		25 Sep 2018
+ * Version	1.5.0
+ *
+ */
+/*! @file bma400.c
+ * @brief Sensor driver for BMA400 sensor
+ */
+#include "bma400.h"
+/************************** Internal macros *******************************/
+/********************** Static function declarations ************************/
+/*!
+ * @brief This internal API is used to validate the device pointer for
+ * null conditions.
+ *
+ * @param[in] dev : Structure instance of bma400_dev.
+ *
+ * @return Result of API execution status
+ * @retval zero -> Success / +ve value -> Warning / -ve value -> Error
+ */
+static int8_t null_ptr_check(const struct bma400_dev *dev);
+
+/*!
+ * @brief This internal API is used to set the accel configurations in sensor
+ *
+ * @param[in] accel_conf : Structure instance with accel configurations
+ * @param[in] dev             : Structure instance of bma400_dev
+ *
+ * @return Result of API execution status
+ * @retval zero -> Success / +ve value -> Warning / -ve value -> Error
+ */
+static int8_t set_accel_conf(const struct bma400_acc_conf *accel_conf, const struct bma400_dev *dev);
+
+/*!
+ * @brief This API reads accel data along with sensor time
+ *
+ * @param[in] data_sel   : Variable to select the data to be read
+ * @param[in,out] accel  : Structure instance to store the accel data
+ * @param[in] dev        : Structure instance of bma400_dev
+ *
+ * Assignable values for data_sel:
+ *   - BMA400_DATA_ONLY
+ *   - BMA400_DATA_SENSOR_TIME
+ *
+ * @return Result of API execution status
+ * @retval zero -> Success / +ve value -> Warning / -ve value -> Error
+ */
+static int8_t get_accel_data(uint8_t data_sel, struct bma400_sensor_data *accel, const struct bma400_dev *dev);
+
+/*!
+ * @brief This API enables the auto-wakeup feature
+ * of the sensor using a timeout value
+ *
+ * @param[in] wakeup_conf : Structure instance of wakeup configurations
+ * @param[in] dev         : Structure instance of bma400_dev
+ *
+ * @return Result of API execution status
+ * @retval zero -> Success / +ve value -> Warning / -ve value -> Error
+ */
+static int8_t set_autowakeup_timeout(const struct bma400_auto_wakeup_conf *wakeup_conf, const struct bma400_dev *dev);
+
+/*!
+ * @brief This API enables the auto-wakeup feature of the sensor
+ *
+ * @param[in] conf  : Configuration value to enable/disable
+ *                    auto-wakeup interrupt
+ * @param[in] dev   : Structure instance of bma400_dev
+ *
+ * @return Result of API execution status
+ * @retval zero -> Success / +ve value -> Warning / -ve value -> Error
+ */
+static int8_t set_auto_wakeup(uint8_t conf, const struct bma400_dev *dev);
+
+/*!
+ * @brief This API sets the parameters for auto-wakeup feature
+ * of the sensor
+ *
+ * @param[in] wakeup_conf : Structure instance of wakeup configurations
+ * @param[in] dev         : Structure instance of bma400_dev
+ *
+ * @return Result of API execution status
+ * @retval zero -> Success / +ve value -> Warning / -ve value -> Error
+ */
+static int8_t set_autowakeup_interrupt(const struct bma400_wakeup_conf *wakeup_conf, const struct bma400_dev *dev);
+
+/*!
+ * @brief This API sets the sensor to enter low power mode
+ * automatically  based on the configurations
+ *
+ * @param[in] auto_lp_conf : Structure instance of auto-low power settings
+ * @param[in] dev            : Structure instance of bma400_dev
+ *
+ * @return Result of API execution status
+ * @retval zero -> Success / +ve value -> Warning / -ve value -> Error
+ */
+static int8_t set_auto_low_power(const struct bma400_auto_lp_conf *auto_lp_conf, const struct bma400_dev *dev);
+
+/*!
+ * @brief This API sets the tap setting parameters
+ *
+ * @param[in] tap_set : Structure instance of tap configurations
+ * @param[in] dev     : Structure instance of bma400_dev
+ *
+ * @return Result of API execution status
+ * @retval zero -> Success / +ve value -> Warning / -ve value -> Error
+ */
+static int8_t set_tap_conf(const struct bma400_tap_conf *tap_set, const struct bma400_dev *dev);
+
+/*!
+ * @brief This API sets the parameters for activity change detection
+ *
+ * @param[in] act_ch_set : Structure instance of activity change
+ *                         configurations
+ * @param[in] dev        : Structure instance of bma400_dev
+ *
+ * @return Result of API execution status
+ * @retval zero -> Success / +ve value -> Warning / -ve value -> Error
+ */
+static int8_t set_activity_change_conf(const struct bma400_act_ch_conf *act_ch_set, const struct bma400_dev *dev);
+
+/*!
+ * @brief This API sets the parameters for generic interrupt1 configuration
+ *
+ * @param[in] gen_int_set : Structure instance of generic interrupt
+ *                          configurations
+ * @param[in] dev         : Structure instance of bma400_dev
+ *
+ * @return Result of API execution status
+ * @retval zero -> Success / +ve value -> Warning / -ve value -> Error
+ */
+static int8_t set_gen1_int(const struct bma400_gen_int_conf *gen_int_set, const struct bma400_dev *dev);
+
+/*!
+ * @brief This API sets the parameters for generic interrupt2 configuration
+ *
+ * @param[in] gen_int_set : Structure instance of generic interrupt
+ *                          configurations
+ * @param[in] dev         : Structure instance of bma400_dev
+ *
+ * @return Result of API execution status
+ * @retval zero -> Success / +ve value -> Warning / -ve value -> Error
+ */
+static int8_t set_gen2_int(const struct bma400_gen_int_conf *gen_int_set, const struct bma400_dev *dev);
+
+/*!
+ * @brief This API sets the parameters for orientation interrupt
+ *
+ * @param[in] orient_conf : Structure instance of orient interrupt
+ *                          configurations
+ * @param[in] dev         : Structure instance of bma400_dev
+ *
+ * @return Result of API execution status
+ * @retval zero -> Success / +ve value -> Warning / -ve value -> Error
+ */
+static int8_t set_orient_int(const struct bma400_orient_int_conf *orient_conf, const struct bma400_dev *dev);
+
+/*!
+ * @brief This internal API is used to get the accel configurations in sensor
+ *
+ * @param[in,out] accel_conf  : Structure instance of basic
+ *                              accelerometer configuration
+ * @param[in] dev             : Structure instance of bma400_dev
+ *
+ * @return Result of API execution status
+ * @retval zero -> Success / +ve value -> Warning / -ve value -> Error
+ */
+static int8_t get_accel_conf(struct bma400_acc_conf *accel_conf, const struct bma400_dev *dev);
+
+/*!
+ * @brief This API gets the set sensor settings for auto-wakeup timeout feature
+ *
+ * @param[in,out] wakeup_conf : Structure instance of wake-up configurations
+ * @param[in] dev             : Structure instance of bma400_dev
+ *
+ * @return Result of API execution status
+ * @retval zero -> Success / +ve value -> Warning / -ve value -> Error
+ */
+static int8_t get_autowakeup_timeout(struct bma400_auto_wakeup_conf *wakeup_conf, const struct bma400_dev *dev);
+
+/*!
+ * @brief This API gets the set sensor settings for
+ * auto-wakeup interrupt feature
+ *
+ * @param[in,out] wakeup_conf : Structure instance of wake-up configurations
+ * @param[in] dev               : Structure instance of bma400_dev
+ *
+ * @return Result of API execution status
+ * @retval zero -> Success / +ve value -> Warning / -ve value -> Error
+ */
+static int8_t get_autowakeup_interrupt(struct bma400_wakeup_conf *wakeup_conf, const struct bma400_dev *dev);
+
+/*!
+ * @brief This API gets the sensor to get the auto-low
+ * power mode configuration settings
+ *
+ * @param[in,out] auto_lp_conf : Structure instance of low power
+ *                                 configurations
+ * @param[in] dev                : Structure instance of bma400_dev
+ *
+ * @return Result of API execution status
+ * @retval zero -> Success / +ve value -> Warning / -ve value -> Error
+ */
+static int8_t get_auto_low_power(struct bma400_auto_lp_conf *auto_lp_conf, const struct bma400_dev *dev);
+
+/*!
+ * @brief This API sets the tap setting parameters
+ *
+ * @param[in,out] tap_set : Structure instance of tap configurations
+ * @param[in] dev         : Structure instance of bma400_dev
+ *
+ * @return Result of API execution status
+ * @retval zero -> Success / +ve value -> Warning / -ve value -> Error
+ */
+static int8_t get_tap_conf(struct bma400_tap_conf *tap_set, const struct bma400_dev *dev);
+
+/*!
+ * @brief This API gets the parameters for activity change detection
+ *
+ * @param[in,out] act_ch_set : Structure instance of activity
+ *                             change configurations
+ * @param[in] dev            : Structure instance of bma400_dev
+ *
+ * @return Result of API execution status
+ * @retval zero -> Success / +ve value -> Warning / -ve value -> Error
+ */
+static int8_t get_activity_change_conf(struct bma400_act_ch_conf *act_ch_set, const struct bma400_dev *dev);
+
+/*!
+ * @brief This API gets the generic interrupt1 configuration
+ *
+ * @param[in,out] gen_int_set : Structure instance of generic
+ *                               interrupt configurations
+ * @param[in] dev             : Structure instance of bma400_dev
+ *
+ * @return Result of API execution status
+ * @retval zero -> Success / +ve value -> Warning / -ve value -> Error
+ */
+static int8_t get_gen1_int(struct bma400_gen_int_conf *gen_int_set, const struct bma400_dev *dev);
+
+/*!
+ * @brief This API gets the generic interrupt2 configuration
+ *
+ * @param[in,out] gen_int_set : Structure instance of generic
+ *                              interrupt configurations
+ * @param[in] dev             : Structure instance of bma400_dev
+ *
+ * @return Result of API execution status
+ * @retval zero -> Success / +ve value -> Warning / -ve value -> Error
+ */
+static int8_t get_gen2_int(struct bma400_gen_int_conf *gen_int_set, const struct bma400_dev *dev);
+
+/*!
+ * @brief This API gets the parameters for orientation interrupt
+ *
+ * @param[in,out] orient_conf : Structure instance of orient
+ *                              interrupt configurations
+ * @param[in] dev             : Structure instance of bma400_dev
+ *
+ * @return Result of API execution status
+ * @retval zero -> Success / +ve value -> Warning / -ve value -> Error
+ */
+static int8_t get_orient_int(struct bma400_orient_int_conf *orient_conf, const struct bma400_dev *dev);
+
+/*!
+ * @brief This API sets the selected interrupt to be mapped to
+ * the hardware interrupt pin of the sensor
+ *
+ * @param[in,out] data_array  : Data array of interrupt pin configurations
+ * @param[in] int_enable      : Interrupt selected for pin mapping
+ * @param[in] int_map         : Interrupt channel to be mapped
+ *
+ * @return Nothing
+ */
+static void map_int_pin(uint8_t *data_array, uint8_t int_enable, enum bma400_int_chan int_map);
+
+/*!
+ * @brief This API checks whether the interrupt is mapped to the INT pin1
+ * or INT pin2 of the sensor
+ *
+ * @param[in] int_1_map     : Variable to denote whether the interrupt is
+ *                            mapped to INT1 pin or not
+ * @param[in] int_2_map     : Variable to denote whether the interrupt is
+ *                            mapped to INT2 pin or not
+ * @param[in,out] int_map   : Interrupt channel which is mapped
+ *                            INT1/INT2/NONE/BOTH
+ *
+ * @return Nothing
+ */
+static void check_mapped_interrupts(uint8_t int_1_map, uint8_t int_2_map, enum bma400_int_chan *int_map);
+
+/*!
+ * @brief This API gets the selected interrupt and its mapping to
+ * the hardware interrupt pin of the sensor
+ *
+ * @param[in,out] data_array  : Data array of interrupt pin configurations
+ * @param[in] int_enable      : Interrupt selected for pin mapping
+ * @param[out] int_map        : Interrupt channel which is mapped
+ *
+ * @return Nothing
+ */
+static void get_int_pin_map(const uint8_t *data_array, uint8_t int_enable, enum bma400_int_chan *int_map);
+
+/*!
+ * @brief This API is used to set the interrupt pin configurations
+ *
+ * @param[in] int_conf     : Interrupt pin configuration
+ * @param[in] dev          : Structure instance of bma400_dev
+ *
+ * @return Result of API execution status
+ * @retval zero -> Success / +ve value -> Warning / -ve value -> Error
+ */
+static int8_t set_int_pin_conf(struct bma400_int_pin_conf int_conf, const struct bma400_dev *dev);
+
+/*!
+ * @brief This API is used to set the interrupt pin configurations
+ *
+ * @param[in,out] int_conf     : Interrupt pin configuration
+ * @param[in] dev              : Structure instance of bma400_dev
+ *
+ * @return Result of API execution status
+ * @retval zero -> Success / +ve value -> Warning / -ve value -> Error
+ */
+static int8_t get_int_pin_conf(struct bma400_int_pin_conf *int_conf, const struct bma400_dev *dev);
+
+/*!
+ * @brief This API is used to set the FIFO configurations
+ *
+ * @param[in,out] fifo_conf       : Structure instance containing the FIFO
+ *                                  configuration set in the sensor
+ * @param[in] dev                 : Structure instance of bma400_dev
+ *
+ * @return Result of API execution status
+ * @retval zero -> Success / +ve value -> Warning / -ve value -> Error
+ */
+static int8_t set_fifo_conf(const struct bma400_fifo_conf *fifo_conf, const struct bma400_dev *dev);
+
+/*!
+ * @brief This API is used to get the FIFO configurations
+ *
+ * @param[in,out] fifo_conf       : Structure instance containing the FIFO
+ *                                  configuration set in the sensor
+ * @param[in] dev                 : Structure instance of bma400_dev
+ *
+ * @return Result of API execution status
+ * @retval zero -> Success / +ve value -> Warning / -ve value -> Error
+ */
+static int8_t get_fifo_conf(struct bma400_fifo_conf *fifo_conf, const struct bma400_dev *dev);
+
+/*!
+ * @brief This API is used to get the number of bytes filled in FIFO
+ *
+ * @param[in,out] fifo_byte_cnt   : Number of bytes in the FIFO buffer
+ *                                  actually filled by the sensor
+ * @param[in] dev                 : Structure instance of bma400_dev
+ *
+ * @return Result of API execution status
+ * @retval zero -> Success / +ve value -> Warning / -ve value -> Error
+ */
+static int8_t get_fifo_length(uint16_t *fifo_byte_cnt, const struct bma400_dev *dev);
+
+/*!
+ * @brief This API is used to read the FIFO of BMA400
+ *
+ * @param[in,out] fifo : Pointer to the fifo structure.
+ *
+ * @param[in] dev      : Structure instance of bma400_dev
+ *
+ * @return Result of API execution status
+ * @retval zero -> Success / +ve value -> Warning / -ve value -> Error
+ */
+static int8_t read_fifo(struct bma400_fifo_data *fifo, const struct bma400_dev *dev);
+
+/*!
+ * @brief This API is used to unpack the accelerometer frames from the FIFO
+ *
+ * @param[in,out] fifo            : Pointer to the fifo structure.
+ * @param[in,out] accel_data      : Structure instance to store the accel data
+ * @param[in,out] frame_count     : Number of frames requested by user as input
+ *                                  Number of frames actually parsed as output
+ * @param[in] dev                 : Structure instance of bma400_dev
+ *
+ * @return Nothing
+ */
+static void unpack_accel_frame(struct bma400_fifo_data *fifo,
+			       struct bma400_sensor_data *accel_data,
+			       uint16_t *frame_count,
+			       const struct bma400_dev *dev);
+
+/*!
+ * @brief This API is used to check for a frame availability in FIFO
+ *
+ * @param[in,out] fifo            : Pointer to the fifo structure.
+ * @param[in,out] frame_available : Variable to denote availability of a frame
+ * @param[in] accel_width         : Variable to denote 12/8 bit accel data
+ * @param[in] data_en             : Data enabled in FIFO
+ * @param[in,out] data_index      : Index of the currently parsed FIFO data
+ *
+ * @return Nothing
+ */
+static void check_frame_available(struct bma400_fifo_data *fifo,
+				  uint8_t *frame_available,
+				  uint8_t accel_width,
+				  uint8_t data_en,
+				  uint16_t *data_index);
+
+/*!
+ * @brief This API is used to unpack the accelerometer xyz data from the FIFO
+ * and store it in the user defined buffer
+ *
+ * @param[in,out] fifo         : Pointer to the fifo structure.
+ * @param[in,out] accel_data   : Structure instance to store the accel data
+ * @param[in,out] data_index   : Index of the currently parsed FIFO data
+ * @param[in] accel_width      : Variable to denote 12/8 bit accel data
+ * @param[in] frame_header     : Variable to get the data enabled
+ *
+ * @return Nothing
+ */
+static void unpack_accel(struct bma400_fifo_data *fifo,
+			 struct bma400_sensor_data *accel_data,
+			 uint16_t *data_index,
+			 uint8_t accel_width,
+			 uint8_t frame_header);
+
+/*!
+ * @brief This API is used to parse and store the sensor time from the
+ * FIFO data in the structure instance dev
+ *
+ * @param[in,out] fifo         : Pointer to the fifo structure.
+ * @param[in,out] data_index   : Index of the FIFO data which has sensor time
+ *
+ * @return Nothing
+ */
+static void unpack_sensortime_frame(struct bma400_fifo_data *fifo, uint16_t *data_index);
+
+/*!
+ * @brief This API validates the self test results
+ *
+ * @param[in] accel_pos	: Structure pointer to store accel data
+ *                        for positive excitation
+ * @param[in] accel_neg	: Structure pointer to store accel data
+ *                        for negative excitation
+ *
+ * @return Result of API execution status
+ * @retval zero -> Success  / -ve value -> Error / +ve value -> Self test fail
+ */
+static int8_t validate_accel_self_test(const struct bma400_sensor_data *accel_pos,
+				       const struct bma400_sensor_data *accel_neg);
+
+/*!
+ * @brief This API performs self test with positive excitation
+ *
+ * @param[in] accel_pos	: Structure pointer to store accel data
+ *                        for positive excitation
+ * @param[in] dev	: structure instance of bma400_dev
+ *
+ * @return Result of API execution status
+ * @retval zero -> Success  / -ve value -> Error
+ */
+static int8_t positive_excited_accel(struct bma400_sensor_data *accel_pos, const struct bma400_dev *dev);
+
+/*!
+ * @brief This API performs self test with negative excitation
+ *
+ * @param[in] accel_neg	: Structure pointer to store accel data
+ *                        for negative excitation
+ * @param[in] dev	: structure instance of bma400_dev
+ *
+ * @return Result of API execution status
+ * @retval zero -> Success  / -ve value -> Error
+ */
+static int8_t negative_excited_accel(struct bma400_sensor_data *accel_neg, const struct bma400_dev *dev);
+
+/*!
+ * @brief This API performs the pre-requisites needed to perform the self test
+ *
+ * @param[in] dev	: structure instance of bma400_dev
+ *
+ * @return Result of API execution status
+ * @retval zero -> Success  / -ve value -> Error
+ */
+static int8_t enable_self_test(const struct bma400_dev *dev);
+
+/********************** Global function definitions ************************/
+/*!
+ *  @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 updates the trim parameters of the sensor.
+ */
+int8_t bma400_init(struct bma400_dev *dev)
+{
+	int8_t rslt;
+	uint8_t chip_id = 0;
+
+	/* Check for null pointer in the device structure*/
+	rslt = null_ptr_check(dev);
+	/* Proceed if null check is fine */
+	if (rslt == BMA400_OK) {
+		/* Initial power-up time */
+		dev->delay_ms(5);
+		/* Assigning dummy byte value */
+		if (dev->intf == BMA400_SPI_INTF) {
+			/* Dummy Byte availability */
+			dev->dummy_byte = 1;
+			/* Dummy read of Chip-ID in SPI mode */
+			rslt = bma400_get_regs(BMA400_CHIP_ID_ADDR, &chip_id, 1, dev);
+		} else {
+			dev->dummy_byte = 0;
+		}
+		if (rslt == BMA400_OK) {
+			/* Chip ID of the sensor is read */
+			rslt = bma400_get_regs(BMA400_CHIP_ID_ADDR, &chip_id, 1, dev);
+			/* Proceed if everything is fine until now */
+			if (rslt == BMA400_OK) {
+				/* Check for chip id validity */
+				if (chip_id == BMA400_CHIP_ID) {
+					/* Store the chip ID in dev structure */
+					dev->chip_id = chip_id;
+				} else {
+					rslt = BMA400_E_DEV_NOT_FOUND;
+				}
+			}
+		}
+	}
+	return rslt;
+}
+/*!
+ * @brief This API writes the given data to the register address
+ * of the sensor.
+ */
+int8_t bma400_set_regs(uint8_t reg_addr, uint8_t *reg_data, uint8_t len, const struct bma400_dev *dev)
+{
+	int8_t rslt;
+	uint8_t count;
+
+	/* 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)) {
+		/* Write the data to the reg_addr */
+		/* SPI write requires to set The MSB of reg_addr as 0
+		   but in default the MSB is always 0 */
+		if (len == 1) {
+			rslt = dev->write(dev->intf_ptr, dev->dev_id, reg_addr, reg_data, len);
+			if (rslt != BMA400_OK) {
+				/* Failure case */
+				rslt = BMA400_E_COM_FAIL;
+			}
+		}
+		/* Burst write is not allowed thus we split burst case write
+		 * into single byte writes Thus user can write multiple bytes
+		 * with ease */
+		if (len > 1) {
+			for (count = 0; count < len; count++) {
+				rslt = dev->write(dev->intf_ptr, dev->dev_id, reg_addr, &reg_data[count], 1);
+				reg_addr++;
+			}
+		}
+	} else {
+		rslt = BMA400_E_NULL_PTR;
+	}
+	return rslt;
+}
+/*!
+ * @brief This API reads the data from the given register address of the sensor.
+ */
+int8_t bma400_get_regs(uint8_t reg_addr, uint8_t *reg_data, uint8_t len, const struct bma400_dev *dev)
+{
+	int8_t rslt;
+	uint16_t index;
+	uint16_t temp_len = len + dev->dummy_byte;
+	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 == BMA400_OK) && (reg_data != NULL)) {
+		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 */
+		rslt = dev->read(dev->intf_ptr, dev->dev_id, reg_addr, temp_buff, temp_len);
+		if (rslt == BMA400_OK) {
+			for (index = 0; index < len; index++) {
+				/* Parse the data read and store in "reg_data"
+				 * buffer so that the dummy byte is removed
+				 * and user will get only valid data
+				 */
+				reg_data[index] = temp_buff[index + dev->dummy_byte];
+			}
+		}
+		if (rslt != BMA400_OK) {
+			/* Failure case */
+			rslt = BMA400_E_COM_FAIL;
+		}
+	} else {
+		rslt = BMA400_E_NULL_PTR;
+	}
+	return rslt;
+}
+/*!
+ * @brief This API is used to perform soft-reset of the sensor
+ * where all the registers are reset to their default values.
+ */
+int8_t bma400_soft_reset(const struct bma400_dev *dev)
+{
+	int8_t rslt;
+	uint8_t data = BMA400_SOFT_RESET_CMD;
+
+	/* Null-pointer check */
+	rslt = null_ptr_check(dev);
+	if (rslt == BMA400_OK) {
+		/* Reset the device */
+		rslt = bma400_set_regs(BMA400_COMMAND_REG_ADDR, &data, 1, dev);
+		dev->delay_ms(BMA400_SOFT_RESET_DELAY_MS);
+		if ((rslt == BMA400_OK) && (dev->intf == BMA400_SPI_INTF)) {
+			/* Dummy read of 0x7F register to enable SPI Interface
+			 * if SPI is used
+			 */
+			rslt = bma400_get_regs(0x7F, &data, 1, dev);
+		}
+	}
+	return rslt;
+}
+/*!
+ * @brief This API is used to set the power mode of the sensor.
+ */
+int8_t bma400_set_power_mode(uint8_t power_mode, const struct bma400_dev *dev)
+{
+	int8_t rslt;
+	uint8_t reg_data = 0;
+
+	rslt = null_ptr_check(dev);
+
+	if (rslt == BMA400_OK) {
+		rslt = bma400_get_regs(BMA400_ACCEL_CONFIG_0_ADDR, &reg_data, 1, dev);
+	}
+
+	if (rslt == BMA400_OK) {
+		reg_data = BMA400_SET_BITS_POS_0(reg_data, BMA400_POWER_MODE, power_mode);
+		/* Set the power mode of sensor */
+		rslt = bma400_set_regs(BMA400_ACCEL_CONFIG_0_ADDR, &reg_data, 1, dev);
+		if (power_mode == BMA400_LOW_POWER_MODE) {
+			/* A delay of 1/ODR is required to switch power modes
+			 * Low power mode has 25Hz frequency and hence it needs
+			 * 40ms delay to enter low power mode */
+			dev->delay_ms(40);
+		} else {
+			dev->delay_ms(10); /* TBC */
+		}
+	}
+
+	return rslt;
+}
+/*!
+ * @brief This API is used to get the power mode of the sensor.
+ */
+int8_t bma400_get_power_mode(uint8_t *power_mode, const struct bma400_dev *dev)
+{
+	int8_t rslt;
+	uint8_t reg_data;
+
+	/* Check for null pointer in the device structure*/
+	rslt = null_ptr_check(dev);
+	/* Proceed if null check is fine */
+	if (rslt == BMA400_OK) {
+		rslt = bma400_get_regs(BMA400_STATUS_ADDR, &reg_data, 1, dev);
+		*power_mode = BMA400_GET_BITS(reg_data, BMA400_POWER_MODE_STATUS);
+	}
+	return rslt;
+}
+/*!
+ * @brief This API is used to get the accel data along with the sensor-time
+ */
+int8_t bma400_get_accel_data(uint8_t data_sel, struct bma400_sensor_data *accel, const struct bma400_dev *dev)
+{
+	int8_t rslt;
+
+	/* Check for null pointer in the device structure*/
+	rslt = null_ptr_check(dev);
+	/* Proceed if null check is fine */
+	if ((rslt == BMA400_OK) || (accel != NULL)) {
+		/* Read and store the accel data */
+		rslt = get_accel_data(data_sel, accel, dev);
+	} else {
+		rslt = BMA400_E_NULL_PTR;
+	}
+	return rslt;
+}
+/*!
+ * @brief This API is used to set the sensor settings like sensor
+ * configurations and interrupt configurations
+ */
+int8_t bma400_set_sensor_conf(const struct bma400_sensor_conf *conf, uint16_t n_sett, const struct bma400_dev *dev)
+{
+	int8_t rslt;
+	uint16_t idx = 0;
+	uint8_t data_array[3] = { 0 };
+
+	/* Check for null pointer in the device structure*/
+	rslt = null_ptr_check(dev);
+	/* Proceed if null check is fine */
+	if (rslt == BMA400_OK) {
+		/* Read the interrupt pin mapping configurations */
+		rslt = bma400_get_regs(BMA400_INT_MAP_ADDR, data_array, 3, dev);
+		if (rslt == BMA400_OK) {
+			for (idx = 0; idx < n_sett; idx++) {
+				switch (conf[idx].type) {
+				case BMA400_ACCEL:
+					/* Setting Accel configurations */
+					rslt = set_accel_conf(&conf[idx].param.accel, dev);
+					if (rslt == BMA400_OK) {
+						/* Int pin mapping settings */
+						map_int_pin(data_array, BMA400_DATA_READY_INT_MAP,
+							    conf[idx].param.accel.int_chan);
+					}
+					break;
+				case BMA400_TAP_INT:
+					/* Setting TAP configurations */
+					rslt = set_tap_conf(&conf[idx].param.tap, dev);
+					if (rslt == BMA400_OK) {
+						/* Int pin mapping settings */
+						map_int_pin(data_array, BMA400_TAP_INT_MAP,
+							    conf[idx].param.tap.int_chan);
+					}
+					break;
+				case BMA400_ACTIVITY_CHANGE_INT:
+					/* Setting activity change config */
+					rslt = set_activity_change_conf(&conf[idx].param.act_ch, dev);
+					if (rslt == BMA400_OK) {
+						/* Int pin mapping settings */
+						map_int_pin(data_array, BMA400_ACT_CH_INT_MAP,
+							    conf[idx].param.act_ch.int_chan);
+					}
+					break;
+				case BMA400_GEN1_INT:
+					/* Setting Generic int 1 config */
+					rslt = set_gen1_int(&conf[idx].param.gen_int, dev);
+					if (rslt == BMA400_OK) {
+						/* Int pin mapping settings */
+						map_int_pin(data_array, BMA400_GEN1_INT_MAP,
+							    conf[idx].param.gen_int.int_chan);
+					}
+					break;
+				case BMA400_GEN2_INT:
+					/* Setting Generic int 2 config */
+					rslt = set_gen2_int(&conf[idx].param.gen_int, dev);
+					if (rslt == BMA400_OK) {
+						/* Int pin mapping settings */
+						map_int_pin(data_array, BMA400_GEN2_INT_MAP,
+							    conf[idx].param.gen_int.int_chan);
+					}
+					break;
+				case BMA400_ORIENT_CHANGE_INT:
+					/* Setting orient int config */
+					rslt = set_orient_int(&conf[idx].param.orient, dev);
+					if (rslt == BMA400_OK) {
+						/* Int pin mapping settings */
+						map_int_pin(data_array, BMA400_ORIENT_CH_INT_MAP,
+							    conf[idx].param.orient.int_chan);
+					}
+					break;
+				case BMA400_STEP_COUNTER_INT:
+					/* Int pin mapping settings */
+					map_int_pin(data_array, BMA400_STEP_INT_MAP, conf[idx].param.step_cnt.int_chan);
+					break;
+				}
+			}
+			if (rslt == BMA400_OK) {
+				/* Set the interrupt pin mapping configurations */
+				rslt = bma400_set_regs(BMA400_INT_MAP_ADDR, data_array, 3, dev);
+			}
+		}
+	}
+	return rslt;
+}
+/*!
+ * @brief This API is used to get the sensor settings like sensor
+ * configurations and interrupt configurations and store
+ * them in the corresponding structure instance
+ */
+int8_t bma400_get_sensor_conf(struct bma400_sensor_conf *conf, uint16_t n_sett, const struct bma400_dev *dev)
+{
+	int8_t rslt = BMA400_OK;
+	uint16_t idx = 0;
+	uint8_t data_array[3] = { 0 };
+
+	if (conf == NULL) {
+		rslt = BMA400_E_NULL_PTR;
+	}
+
+	if (rslt == BMA400_OK) {
+		/* Read the interrupt pin mapping configurations */
+		rslt = bma400_get_regs(BMA400_INT_MAP_ADDR, data_array, 3, dev);
+	}
+
+	for (idx = 0; (idx < n_sett) && (rslt == BMA400_OK); idx++) {
+		switch (conf[idx].type) {
+		case BMA400_ACCEL:
+			/* Accel configuration settings */
+			rslt = get_accel_conf(&conf[idx].param.accel, dev);
+			if (rslt == BMA400_OK) {
+				/* Get the INT pin mapping */
+				get_int_pin_map(data_array, BMA400_DATA_READY_INT_MAP, &conf[idx].param.accel.int_chan);
+			}
+			break;
+		case BMA400_TAP_INT:
+			/* TAP configuration settings */
+			rslt = get_tap_conf(&conf[idx].param.tap, dev);
+			if (rslt == BMA400_OK) {
+				/* Get the INT pin mapping */
+				get_int_pin_map(data_array, BMA400_TAP_INT_MAP, &conf[idx].param.tap.int_chan);
+			}
+			break;
+		case BMA400_ACTIVITY_CHANGE_INT:
+			/* Activity change configurations */
+			rslt = get_activity_change_conf(&conf[idx].param.act_ch, dev);
+			if (rslt == BMA400_OK) {
+				/* Get the INT pin mapping */
+				get_int_pin_map(data_array, BMA400_ACT_CH_INT_MAP, &conf[idx].param.act_ch.int_chan);
+			}
+			break;
+		case BMA400_GEN1_INT:
+			/* Generic int1 configurations */
+			rslt = get_gen1_int(&conf[idx].param.gen_int, dev);
+			if (rslt == BMA400_OK) {
+				/* Get the INT pin mapping */
+				get_int_pin_map(data_array, BMA400_GEN1_INT_MAP, &conf[idx].param.gen_int.int_chan);
+			}
+			break;
+		case BMA400_GEN2_INT:
+			/* Generic int2 configurations */
+			rslt = get_gen2_int(&conf[idx].param.gen_int, dev);
+			if (rslt == BMA400_OK) {
+				/* Get the INT pin mapping */
+				get_int_pin_map(data_array, BMA400_GEN2_INT_MAP, &conf[idx].param.gen_int.int_chan);
+			}
+			break;
+		case BMA400_ORIENT_CHANGE_INT:
+			/* Orient int configurations */
+			rslt = get_orient_int(&conf[idx].param.orient, dev);
+			if (rslt == BMA400_OK) {
+				/* Get the INT pin mapping */
+				get_int_pin_map(data_array, BMA400_ORIENT_CH_INT_MAP, &conf[idx].param.orient.int_chan);
+			}
+			break;
+		case BMA400_STEP_COUNTER_INT:
+			/* Get int pin mapping settings */
+			get_int_pin_map(data_array, BMA400_STEP_INT_MAP, &conf[idx].param.step_cnt.int_chan);
+			break;
+		default:
+			rslt = BMA400_E_INVALID_CONFIG;
+		}
+	}
+
+	return rslt;
+}
+/*!
+ * @brief This API is used to set the device specific settings
+ */
+int8_t bma400_set_device_conf(const struct bma400_device_conf *conf, uint8_t n_sett, const struct bma400_dev *dev)
+{
+	int8_t rslt = BMA400_OK;
+	uint16_t idx = 0;
+	uint8_t data_array[3] = { 0 };
+
+	if (conf == NULL) {
+		rslt = BMA400_E_NULL_PTR;
+	}
+
+	if (rslt == BMA400_OK) {
+		/* Read the interrupt pin mapping configurations */
+		rslt = bma400_get_regs(BMA400_INT_MAP_ADDR, data_array, 3, dev);
+	}
+
+	for (idx = 0; (idx < n_sett) && (rslt == BMA400_OK); idx++) {
+		switch (conf[idx].type) {
+		case BMA400_AUTOWAKEUP_TIMEOUT:
+			rslt = set_autowakeup_timeout(&conf[idx].param.auto_wakeup, dev);
+			break;
+		case BMA400_AUTOWAKEUP_INT:
+			rslt = set_autowakeup_interrupt(&conf[idx].param.wakeup, dev);
+			if (rslt == BMA400_OK) {
+				/* Interrupt pin mapping */
+				map_int_pin(data_array, BMA400_WAKEUP_INT_MAP, conf[idx].param.wakeup.int_chan);
+			}
+			break;
+		case BMA400_AUTO_LOW_POWER:
+			rslt = set_auto_low_power(&conf[idx].param.auto_lp, dev);
+			break;
+		case BMA400_INT_PIN_CONF:
+			rslt = set_int_pin_conf(conf[idx].param.int_conf, dev);
+			break;
+		case BMA400_INT_OVERRUN_CONF:
+			/* Interrupt pin mapping */
+			map_int_pin(data_array, BMA400_INT_OVERRUN_MAP, conf[idx].param.overrun_int.int_chan);
+			break;
+		case BMA400_FIFO_CONF:
+			rslt = set_fifo_conf(&conf[idx].param.fifo_conf, dev);
+			if (rslt == BMA400_OK) {
+				/* Interrupt pin mapping */
+				map_int_pin(data_array, BMA400_FIFO_WM_INT_MAP,
+					    conf[idx].param.fifo_conf.fifo_wm_channel);
+				map_int_pin(data_array, BMA400_FIFO_FULL_INT_MAP,
+					    conf[idx].param.fifo_conf.fifo_full_channel);
+			}
+			break;
+		default:
+			rslt = BMA400_E_INVALID_CONFIG;
+		}
+	}
+
+	if (rslt == BMA400_OK) {
+		/* Set the interrupt pin mapping configurations */
+		rslt = bma400_set_regs(BMA400_INT_MAP_ADDR, data_array, 3, dev);
+	}
+
+	return rslt;
+}
+/*!
+ * @brief This API is used to get the device specific settings and store
+ * them in the corresponding structure instance
+ */
+int8_t bma400_get_device_conf(struct bma400_device_conf *conf, uint8_t n_sett, const struct bma400_dev *dev)
+{
+	int8_t rslt;
+	uint16_t idx = 0;
+	uint8_t data_array[3] = { 0 };
+
+	/* Check for null pointer in the device structure*/
+	rslt = null_ptr_check(dev);
+	/* Proceed if null check is fine */
+	if (rslt == BMA400_OK) {
+		/* Read the interrupt pin mapping configurations */
+		rslt = bma400_get_regs(BMA400_INT_MAP_ADDR, data_array, 3, dev);
+		if (rslt == BMA400_OK) {
+			for (idx = 0; idx < n_sett; idx++) {
+				switch (conf[idx].type) {
+				case BMA400_AUTOWAKEUP_TIMEOUT:
+					rslt = get_autowakeup_timeout(&conf[idx].param.auto_wakeup, dev);
+					break;
+				case BMA400_AUTOWAKEUP_INT:
+					rslt = get_autowakeup_interrupt(&conf[idx].param.wakeup, dev);
+					if (rslt == BMA400_OK) {
+						/* Get the INT pin mapping */
+						get_int_pin_map(data_array, BMA400_WAKEUP_INT_MAP,
+								&conf[idx].param.wakeup.int_chan);
+					}
+					break;
+				case BMA400_AUTO_LOW_POWER:
+					rslt = get_auto_low_power(&conf[idx].param.auto_lp, dev);
+					break;
+				case BMA400_INT_PIN_CONF:
+					rslt = get_int_pin_conf(&conf[idx].param.int_conf, dev);
+					break;
+				case BMA400_INT_OVERRUN_CONF:
+					get_int_pin_map(data_array, BMA400_INT_OVERRUN_MAP,
+							&conf[idx].param.overrun_int.int_chan);
+					break;
+				case BMA400_FIFO_CONF:
+					rslt = get_fifo_conf(&conf[idx].param.fifo_conf, dev);
+					if (rslt == BMA400_OK) {
+						get_int_pin_map(data_array,
+								BMA400_FIFO_FULL_INT_MAP,
+								&conf[idx].param.fifo_conf.fifo_full_channel);
+						get_int_pin_map(data_array, BMA400_FIFO_WM_INT_MAP,
+								&conf[idx].param.fifo_conf.fifo_wm_channel);
+					}
+					break;
+				}
+			}
+		}
+	}
+	return rslt;
+}
+/*!
+ * @brief This API is used to get the status of all the interrupts
+ * whether they are asserted or not
+ */
+int8_t bma400_get_interrupt_status(uint16_t *int_status, const struct bma400_dev *dev)
+{
+	int8_t rslt;
+	uint8_t reg_data[3];
+
+	/* Check for null pointer in the device structure*/
+	rslt = null_ptr_check(dev);
+	/* Proceed if null check is fine */
+	if (rslt == BMA400_OK) {
+		/* Read the interrupt status registers */
+		rslt = bma400_get_regs(BMA400_INT_STAT0_ADDR, reg_data, 3, dev);
+		reg_data[1] = BMA400_SET_BITS(reg_data[1], BMA400_INT_STATUS, reg_data[2]);
+		/* Concatenate the interrupt status to the output */
+		*int_status = ((uint16_t)reg_data[1] << 8) | reg_data[0];
+	}
+	return rslt;
+}
+/*!
+ * @brief This API is used to set the step counter's configuration
+ * parameters from the registers 0x59 to 0x71
+ */
+int8_t bma400_set_step_counter_param(uint8_t *sccr_conf, const struct bma400_dev *dev)
+{
+	int8_t rslt;
+
+	/* Check for null pointer in the device structure*/
+	rslt = null_ptr_check(dev);
+	/* Proceed if null check is fine */
+	if (rslt == BMA400_OK) {
+		/* Set the step counter parameters in the sensor */
+		rslt = bma400_set_regs(0x59, sccr_conf, 25, dev);
+	}
+	return rslt;
+}
+/*!
+ * @brief This API is used to get the step counter output in form
+ * of number of steps in the step_count value
+ */
+int8_t bma400_get_steps_counted(uint32_t *step_count, uint8_t *activity_data, const struct bma400_dev *dev)
+{
+	int8_t rslt;
+	uint8_t data_arrray[4];
+
+	/* Check for null pointer in the device structure*/
+	rslt = null_ptr_check(dev);
+	/* Proceed if null check is fine */
+	if (rslt == BMA400_OK) {
+		rslt = bma400_get_regs(BMA400_STEP_CNT_0_ADDR, data_arrray, 4, dev);
+		*step_count = ((uint32_t)data_arrray[2] << 16) | ((uint16_t)data_arrray[1] << 8) | data_arrray[0];
+		*activity_data = data_arrray[3];
+	}
+	return rslt;
+}
+/*!
+ * @brief This API is used to get the temperature data output
+ */
+int8_t bma400_get_temperature_data(int16_t *temperature_data, const struct bma400_dev *dev)
+{
+	int8_t rslt;
+	uint8_t reg_data;
+
+	/* Check for null pointer in the device structure*/
+	rslt = null_ptr_check(dev);
+	/* Proceed if null check is fine */
+	if (rslt == BMA400_OK) {
+		rslt = bma400_get_regs(BMA400_TEMP_DATA_ADDR, &reg_data, 1, dev);
+		/* Temperature data calculations */
+		*temperature_data = (((int16_t)((int8_t)reg_data)) - 2) * 5 + 250;
+	}
+	return rslt;
+}
+/*!
+ * @brief This API is used to get the enable/disable
+ * status of the various interrupts
+ */
+int8_t bma400_get_interrupts_enabled(struct bma400_int_enable *int_select, uint8_t n_sett, const struct bma400_dev *dev)
+{
+	int8_t rslt;
+	uint8_t idx = 0;
+	uint8_t reg_data[2];
+	uint8_t wkup_int;
+
+	/* Check for null pointer in the device structure */
+	rslt = null_ptr_check(dev);
+	/* Proceed if null check is fine */
+	if (rslt == BMA400_OK) {
+		rslt = bma400_get_regs(BMA400_INT_CONF_0_ADDR, reg_data, 2, dev);
+		if (rslt == BMA400_OK) {
+			for (idx = 0; idx < n_sett; idx++) {
+				/* Read the enable/disable of interrupts
+				 * based on user selection */
+				switch (int_select[idx].type) {
+				case BMA400_DRDY_INT_EN:
+					int_select[idx].conf = BMA400_GET_BITS(reg_data[0], BMA400_EN_DRDY);
+					break;
+				case BMA400_FIFO_WM_INT_EN:
+					int_select[idx].conf = BMA400_GET_BITS(reg_data[0], BMA400_EN_FIFO_WM);
+					break;
+				case BMA400_FIFO_FULL_INT_EN:
+					int_select[idx].conf = BMA400_GET_BITS(reg_data[0], BMA400_EN_FIFO_FULL);
+					break;
+				case BMA400_GEN2_INT_EN:
+					int_select[idx].conf = BMA400_GET_BITS(reg_data[0], BMA400_EN_GEN2);
+					break;
+				case BMA400_GEN1_INT_EN:
+					int_select[idx].conf = BMA400_GET_BITS(reg_data[0], BMA400_EN_GEN1);
+					break;
+				case BMA400_ORIENT_CHANGE_INT_EN:
+					int_select[idx].conf = BMA400_GET_BITS(reg_data[0], BMA400_EN_ORIENT_CH);
+					break;
+				case BMA400_LATCH_INT_EN:
+					int_select[idx].conf = BMA400_GET_BITS(reg_data[1], BMA400_EN_LATCH);
+					break;
+				case BMA400_ACTIVITY_CHANGE_INT_EN:
+					int_select[idx].conf = BMA400_GET_BITS(reg_data[1], BMA400_EN_ACTCH);
+					break;
+				case BMA400_DOUBLE_TAP_INT_EN:
+					int_select[idx].conf = BMA400_GET_BITS(reg_data[1], BMA400_EN_D_TAP);
+					break;
+				case BMA400_SINGLE_TAP_INT_EN:
+					int_select[idx].conf = BMA400_GET_BITS(reg_data[1], BMA400_EN_S_TAP);
+					break;
+				case BMA400_STEP_COUNTER_INT_EN:
+					int_select[idx].conf = BMA400_GET_BITS_POS_0(reg_data[1], BMA400_EN_STEP_INT);
+					break;
+				case BMA400_AUTO_WAKEUP_EN:
+					rslt = bma400_get_regs(BMA400_AUTOWAKEUP_1_ADDR, &wkup_int, 1, dev);
+					if (rslt == BMA400_OK) {
+						/* Auto-Wakeup int status */
+						int_select[idx].conf = BMA400_GET_BITS(wkup_int,
+										       BMA400_WAKEUP_INTERRUPT);
+					}
+					break;
+				default:
+					rslt = BMA400_E_INVALID_CONFIG;
+					break;
+				}
+			}
+		}
+	}
+	return rslt;
+}
+/*!
+ * @brief This API is used to enable the various interrupts
+ */
+int8_t bma400_enable_interrupt(const struct bma400_int_enable *int_select, uint8_t n_sett, const struct bma400_dev *dev)
+{
+	int8_t rslt;
+	uint8_t conf, idx = 0;
+	uint8_t reg_data[2];
+
+	/* Check for null pointer in the device structure */
+	rslt = null_ptr_check(dev);
+	/* Proceed if null check is fine */
+	if (rslt == BMA400_OK) {
+		rslt = bma400_get_regs(BMA400_INT_CONF_0_ADDR, reg_data, 2, dev);
+		if (rslt == BMA400_OK) {
+			for (idx = 0; idx < n_sett; idx++) {
+				conf = int_select[idx].conf;
+				/* Enable the interrupt based on user selection */
+				switch (int_select[idx].type) {
+				case BMA400_DRDY_INT_EN:
+					reg_data[0] = BMA400_SET_BITS(reg_data[0], BMA400_EN_DRDY, conf);
+					break;
+				case BMA400_FIFO_WM_INT_EN:
+					reg_data[0] = BMA400_SET_BITS(reg_data[0], BMA400_EN_FIFO_WM, conf);
+					break;
+				case BMA400_FIFO_FULL_INT_EN:
+					reg_data[0] = BMA400_SET_BITS(reg_data[0], BMA400_EN_FIFO_FULL, conf);
+					break;
+				case BMA400_GEN2_INT_EN:
+					reg_data[0] = BMA400_SET_BITS(reg_data[0], BMA400_EN_GEN2, conf);
+					break;
+				case BMA400_GEN1_INT_EN:
+					reg_data[0] = BMA400_SET_BITS(reg_data[0], BMA400_EN_GEN1, conf);
+					break;
+				case BMA400_ORIENT_CHANGE_INT_EN:
+					reg_data[0] = BMA400_SET_BITS(reg_data[0], BMA400_EN_ORIENT_CH, conf);
+					break;
+				case BMA400_LATCH_INT_EN:
+					reg_data[1] = BMA400_SET_BITS(reg_data[1], BMA400_EN_LATCH, conf);
+					break;
+				case BMA400_ACTIVITY_CHANGE_INT_EN:
+					reg_data[1] = BMA400_SET_BITS(reg_data[1], BMA400_EN_ACTCH, conf);
+					break;
+				case BMA400_DOUBLE_TAP_INT_EN:
+					reg_data[1] = BMA400_SET_BITS(reg_data[1], BMA400_EN_D_TAP, conf);
+					break;
+				case BMA400_SINGLE_TAP_INT_EN:
+					reg_data[1] = BMA400_SET_BITS(reg_data[1], BMA400_EN_S_TAP, conf);
+					break;
+				case BMA400_STEP_COUNTER_INT_EN:
+					reg_data[1] = BMA400_SET_BITS_POS_0(reg_data[1], BMA400_EN_STEP_INT, conf);
+					break;
+				case BMA400_AUTO_WAKEUP_EN:
+					rslt = set_auto_wakeup(conf, dev);
+					break;
+				default:
+					rslt = BMA400_E_INVALID_CONFIG;
+					break;
+				}
+			}
+			if (rslt == BMA400_OK) {
+				/* Set the configurations in the sensor */
+				rslt = bma400_set_regs(BMA400_INT_CONF_0_ADDR, reg_data, 2, dev);
+			}
+		}
+	}
+	return rslt;
+}
+/*!
+ * @brief This API reads the FIFO data from the sensor
+ */
+int8_t bma400_get_fifo_data(struct bma400_fifo_data *fifo, const struct bma400_dev *dev)
+{
+	int8_t rslt;
+	uint8_t data;
+	uint16_t fifo_byte_cnt = 0;
+	uint16_t user_fifo_len = 0;
+
+	/* Check for null pointer in the device structure */
+	rslt = null_ptr_check(dev);
+	/* Proceed if null check is fine */
+	if (rslt == BMA400_OK) {
+		/* Resetting the FIFO data byte index */
+		fifo->accel_byte_start_idx = 0;
+		/* Reading the FIFO length */
+		rslt = get_fifo_length(&fifo_byte_cnt, dev);
+		if (rslt == BMA400_OK) {
+			/* Get the FIFO configurations
+			 * from the sensor */
+			rslt = bma400_get_regs(BMA400_FIFO_CONFIG_0_ADDR, &data, 1, dev);
+			if (rslt == BMA400_OK) {
+				/* Get the data from FIFO_CONFIG0 register */
+				fifo->fifo_8_bit_en = BMA400_GET_BITS(data, BMA400_FIFO_8_BIT_EN);
+				fifo->fifo_data_enable = BMA400_GET_BITS(data, BMA400_FIFO_AXES_EN);
+				fifo->fifo_time_enable = BMA400_GET_BITS(data, BMA400_FIFO_TIME_EN);
+				fifo->fifo_sensor_time = 0;
+				user_fifo_len = fifo->length;
+				if (fifo->length > fifo_byte_cnt) {
+					/* Handling case where user requests
+					 * more data than available in FIFO */
+					fifo->length = fifo_byte_cnt;
+				}
+				/* Reading extra bytes as per the macro
+				 * "BMA400_FIFO_BYTES_OVERREAD"
+				 * when FIFO time is enabled */
+				if ((fifo->fifo_time_enable == BMA400_ENABLE) &&
+				    (fifo_byte_cnt + BMA400_FIFO_BYTES_OVERREAD <= user_fifo_len)) {
+					/* Handling sensor time availability*/
+					fifo->length = fifo->length + BMA400_FIFO_BYTES_OVERREAD;
+				}
+				/* Read the FIFO data */
+				rslt = read_fifo(fifo, dev);
+			}
+		}
+	}
+	return rslt;
+}
+/*!
+ * @brief This API parses and extracts the accelerometer frames, FIFO time
+ * and control frames from FIFO data read by the "bma400_get_fifo_data" API
+ * and stores it in the "accel_data" structure instance.
+ */
+int8_t bma400_extract_accel(struct bma400_fifo_data *fifo,
+			    struct bma400_sensor_data *accel_data,
+			    uint16_t *frame_count,
+			    const struct bma400_dev *dev)
+{
+	int8_t rslt;
+
+	/* Check for null pointer in the device structure */
+	rslt = null_ptr_check(dev);
+	/* Proceed if null check is fine */
+	if (rslt == BMA400_OK) {
+		/* Parse the FIFO data */
+		unpack_accel_frame(fifo, accel_data, frame_count, dev);
+	}
+	return rslt;
+}
+/*!
+ *  @brief This API writes fifo_flush command to command register.This
+ *  action clears all data in the FIFO
+ */
+int8_t bma400_set_fifo_flush(const struct bma400_dev *dev)
+{
+	int8_t rslt;
+	uint8_t data = BMA400_FIFO_FLUSH_CMD;
+
+	/* Check for null pointer in the device structure */
+	rslt = null_ptr_check(dev);
+	/* Proceed if null check is fine */
+	if (rslt == BMA400_OK) {
+		/* FIFO flush command is set */
+		rslt = bma400_set_regs(BMA400_COMMAND_REG_ADDR, &data, 1, dev);
+	}
+	return rslt;
+}
+/*!
+ * @brief This is used to perform self test of accelerometer in BMA400
+ */
+int8_t bma400_perform_self_test(const struct bma400_dev *dev)
+{
+	int8_t rslt;
+	int8_t self_test_rslt = 0;
+	struct bma400_sensor_data accel_pos, accel_neg;
+
+	/* Check for null pointer in the device structure */
+	rslt = null_ptr_check(dev);
+	/* Proceed if null check is fine */
+	if (rslt == BMA400_OK) {
+		/* pre-requisites for self test*/
+		rslt = enable_self_test(dev);
+		if (rslt == BMA400_OK) {
+			rslt = positive_excited_accel(&accel_pos, dev);
+			if (rslt == BMA400_OK) {
+				rslt = negative_excited_accel(&accel_neg, dev);
+				if (rslt == BMA400_OK) {
+					/* Validate the self test result */
+					rslt = validate_accel_self_test(&accel_pos, &accel_neg);
+				}
+			}
+		}
+	}
+	/* Check to ensure bus error does not occur */
+	if (rslt >= BMA400_OK) {
+		/* Store the status of self test result */
+		self_test_rslt = rslt;
+		/* Perform soft reset */
+		rslt = bma400_soft_reset(dev);
+	}
+	/* Check to ensure bus operations are success */
+	if (rslt == BMA400_OK) {
+		/* Restore self_test_rslt as return value */
+		rslt = self_test_rslt;
+	}
+	return rslt;
+}
+/****************************************************************************/
+/**\name	INTERNAL APIs                                               */
+/*!
+ * @brief This internal API is used to validate the device structure pointer for
+ * null conditions.
+ */
+static int8_t null_ptr_check(const struct bma400_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 = BMA400_E_NULL_PTR;
+	} else {
+		/* Device structure is fine */
+		rslt = BMA400_OK;
+	}
+	return rslt;
+}
+
+/*!
+ * @brief This internal API is used to set the accel configurations in sensor
+ */
+static int8_t set_accel_conf(const struct bma400_acc_conf *accel_conf, const struct bma400_dev *dev)
+{
+	int8_t rslt;
+	uint8_t data_array[3] = { 0, 0, 0xE0 };
+
+	/* Update the accel configurations from the user structure
+	 * accel_conf */
+	rslt = bma400_get_regs(BMA400_ACCEL_CONFIG_0_ADDR, data_array, 3, dev);
+	if (rslt == BMA400_OK) {
+		data_array[0] = BMA400_SET_BITS(data_array[0], BMA400_FILT_1_BW, accel_conf->filt1_bw);
+		data_array[0] = BMA400_SET_BITS(data_array[0], BMA400_OSR_LP, accel_conf->osr_lp);
+		data_array[1] = BMA400_SET_BITS(data_array[1], BMA400_ACCEL_RANGE, accel_conf->range);
+		data_array[1] = BMA400_SET_BITS(data_array[1], BMA400_OSR, accel_conf->osr);
+		data_array[1] = BMA400_SET_BITS_POS_0(data_array[1], BMA400_ACCEL_ODR, accel_conf->odr);
+		data_array[2] = BMA400_SET_BITS(data_array[2], BMA400_DATA_FILTER, accel_conf->data_src);
+		/* Set the accel configurations in the sensor */
+		rslt = bma400_set_regs(BMA400_ACCEL_CONFIG_0_ADDR, data_array, 3, dev);
+	}
+	return rslt;
+}
+/*!
+ * @brief This internal API is used to set the accel configurations in sensor
+ */
+static int8_t get_accel_conf(struct bma400_acc_conf *accel_conf, const struct bma400_dev *dev)
+{
+	int8_t rslt;
+	uint8_t data_array[3];
+
+	rslt = bma400_get_regs(BMA400_ACCEL_CONFIG_0_ADDR, data_array, 3, dev);
+	if (rslt == BMA400_OK) {
+		accel_conf->filt1_bw = BMA400_GET_BITS(data_array[0], BMA400_FILT_1_BW);
+		accel_conf->osr_lp = BMA400_GET_BITS(data_array[0], BMA400_OSR_LP);
+		accel_conf->range = BMA400_GET_BITS(data_array[1], BMA400_ACCEL_RANGE);
+		accel_conf->osr = BMA400_GET_BITS(data_array[1], BMA400_OSR);
+		accel_conf->odr = BMA400_GET_BITS_POS_0(data_array[1], BMA400_ACCEL_ODR);
+		accel_conf->data_src = BMA400_GET_BITS(data_array[2], BMA400_DATA_FILTER);
+	}
+	return rslt;
+}
+/*!
+ * @brief This API reads accel data along with sensor time
+ */
+static int8_t get_accel_data(uint8_t data_sel, struct bma400_sensor_data *accel, const struct bma400_dev *dev)
+{
+	int8_t rslt;
+	uint8_t data_array[9] = { 0 };
+	uint16_t lsb;
+	uint8_t msb;
+	uint8_t time_0;
+	uint16_t time_1;
+	uint32_t time_2;
+
+	if (data_sel == BMA400_DATA_ONLY) {
+		/* Read the sensor data registers only */
+		rslt = bma400_get_regs(BMA400_ACCEL_DATA_ADDR, data_array, 6, dev);
+	} else if (data_sel == BMA400_DATA_SENSOR_TIME) {
+		/* Read the sensor data along with sensor time */
+		rslt = bma400_get_regs(BMA400_ACCEL_DATA_ADDR, data_array, 9, dev);
+	} else {
+		/* Invalid use of "data_sel" */
+		rslt = BMA400_E_INVALID_CONFIG;
+	}
+	if (rslt == BMA400_OK) {
+		lsb = data_array[0];
+		msb = data_array[1];
+		/* accel X axis data */
+		accel->x = (int16_t)(((uint16_t)msb * 256) + lsb);
+		if (accel->x > 2047) {
+			/* Computing accel data negative value */
+			accel->x = accel->x - 4096;
+		}
+		lsb = data_array[2];
+		msb = data_array[3];
+		/* accel Y axis data */
+		accel->y = (int16_t)(((uint16_t)msb * 256) | lsb);
+		if (accel->y > 2047) {
+			/* Computing accel data negative value */
+			accel->y = accel->y - 4096;
+		}
+		lsb = data_array[4];
+		msb = data_array[5];
+		/* accel Z axis data */
+		accel->z = (int16_t)(((uint16_t)msb * 256) | lsb);
+		if (accel->z > 2047) {
+			/* Computing accel data negative value */
+			accel->z = accel->z - 4096;
+		}
+		if (data_sel == BMA400_DATA_ONLY) {
+			/* Update sensortime as 0 */
+			accel->sensortime = 0;
+		}
+		if (data_sel == BMA400_DATA_SENSOR_TIME) {
+			/* Sensor-time data*/
+			time_0 = data_array[6];
+			time_1 = ((uint16_t)data_array[7] << 8);
+			time_2 = ((uint32_t)data_array[8] << 16);
+			accel->sensortime = (uint32_t)(time_2 + time_1 + time_0);
+		}
+	}
+	return rslt;
+}
+/*!
+ * @brief This API enables the auto-wakeup feature
+ * of the sensor using a timeout value
+ */
+static int8_t set_autowakeup_timeout(const struct bma400_auto_wakeup_conf *wakeup_conf, const struct bma400_dev *dev)
+{
+	int8_t rslt;
+	uint8_t data_array[2];
+	uint8_t lsb;
+	uint8_t msb;
+
+	rslt = bma400_get_regs(BMA400_AUTOWAKEUP_1_ADDR, &data_array[1], 1, dev);
+	if (rslt == BMA400_OK) {
+		data_array[1] = BMA400_SET_BITS(data_array[1], BMA400_WAKEUP_TIMEOUT, wakeup_conf->wakeup_timeout);
+		/* LSB of timeout threshold */
+		lsb = BMA400_GET_BITS_POS_0(wakeup_conf->timeout_thres, BMA400_WAKEUP_THRES_LSB);
+		/* MSB of timeout threshold */
+		msb = BMA400_GET_BITS(wakeup_conf->timeout_thres, BMA400_WAKEUP_THRES_MSB);
+		/* Set the value in the data_array */
+		data_array[0] = msb;
+		data_array[1] = BMA400_SET_BITS(data_array[1], BMA400_WAKEUP_TIMEOUT_THRES, lsb);
+		rslt = bma400_set_regs(BMA400_AUTOWAKEUP_0_ADDR, data_array, 2, dev);
+	}
+	return rslt;
+}
+/*!
+ * @brief This API gets the set sensor settings for auto-wakeup timeout feature
+ */
+static int8_t get_autowakeup_timeout(struct bma400_auto_wakeup_conf *wakeup_conf, const struct bma400_dev *dev)
+{
+	int8_t rslt;
+	uint8_t data_array[2];
+	uint8_t lsb;
+	uint8_t msb;
+
+	rslt = bma400_get_regs(BMA400_AUTOWAKEUP_0_ADDR, data_array, 2, dev);
+	if (rslt == BMA400_OK) {
+		wakeup_conf->wakeup_timeout = BMA400_GET_BITS(data_array[1], BMA400_WAKEUP_TIMEOUT);
+		msb = data_array[0];
+		lsb = BMA400_GET_BITS(data_array[1], BMA400_WAKEUP_TIMEOUT_THRES);
+		/* Store the timeout value in the wakeup structure */
+		wakeup_conf->timeout_thres = msb << 4 | lsb;
+	}
+	return rslt;
+}
+/*!
+ * @brief This API enables the auto-wakeup feature of the sensor
+ */
+static int8_t set_auto_wakeup(uint8_t conf, const struct bma400_dev *dev)
+{
+	int8_t rslt;
+	uint8_t reg_data;
+
+	rslt = bma400_get_regs(BMA400_AUTOWAKEUP_1_ADDR, &reg_data, 1, dev);
+	if (rslt == BMA400_OK) {
+		reg_data = BMA400_SET_BITS(reg_data, BMA400_WAKEUP_INTERRUPT, conf);
+		/* Enabling the Auto wakeup interrupt */
+		rslt = bma400_set_regs(BMA400_AUTOWAKEUP_1_ADDR, &reg_data, 1, dev);
+	}
+	return rslt;
+}
+/*!
+ * @brief This API sets the parameters for auto-wakeup feature
+ * of the sensor
+ */
+static int8_t set_autowakeup_interrupt(const struct bma400_wakeup_conf *wakeup_conf, const struct bma400_dev *dev)
+{
+	int8_t rslt;
+	uint8_t data_array[5] = { 0 };
+
+	/* Set the wakeup reference update */
+	data_array[0] = BMA400_SET_BITS_POS_0(data_array[0], BMA400_WKUP_REF_UPDATE, wakeup_conf->wakeup_ref_update);
+	/* Set the number of samples for interrupt condition evaluation */
+	data_array[0] = BMA400_SET_BITS(data_array[0], BMA400_SAMPLE_COUNT, wakeup_conf->sample_count);
+	/* Enable low power wake-up interrupt for X,Y,Z axes*/
+	data_array[0] = BMA400_SET_BITS(data_array[0], BMA400_WAKEUP_EN_AXES, wakeup_conf->wakeup_axes_en);
+	/* Set interrupt threshold configuration  */
+	data_array[1] = wakeup_conf->int_wkup_threshold;
+	/* Set the reference acceleration x-axis for the wake-up interrupt */
+	data_array[2] = wakeup_conf->int_wkup_ref_x;
+	/* Set the reference acceleration y-axis for the wake-up interrupt */
+	data_array[3] = wakeup_conf->int_wkup_ref_y;
+	/* Set the reference acceleration z-axis for the wake-up interrupt */
+	data_array[4] = wakeup_conf->int_wkup_ref_z;
+	/* Set the wakeup interrupt configurations in the sensor */
+	rslt = bma400_set_regs(BMA400_WAKEUP_INT_CONF_0_ADDR, data_array, 5, dev);
+	return rslt;
+}
+/*!
+ * @brief This API gets the set sensor settings for
+ * auto-wakeup interrupt feature
+ */
+static int8_t get_autowakeup_interrupt(struct bma400_wakeup_conf *wakeup_conf, const struct bma400_dev *dev)
+{
+	int8_t rslt;
+	uint8_t data_array[5];
+
+	rslt = bma400_get_regs(BMA400_WAKEUP_INT_CONF_0_ADDR, data_array, 5, dev);
+	if (rslt == BMA400_OK) {
+		/* get the wakeup reference update */
+		wakeup_conf->wakeup_ref_update = BMA400_GET_BITS_POS_0(data_array[0], BMA400_WKUP_REF_UPDATE);
+		/* Get the number of samples for interrupt condition evaluation */
+		wakeup_conf->sample_count = BMA400_GET_BITS(data_array[0], BMA400_SAMPLE_COUNT);
+		/* Get the axes enabled */
+		wakeup_conf->wakeup_axes_en = BMA400_GET_BITS(data_array[0], BMA400_WAKEUP_EN_AXES);
+		/* Get interrupt threshold configuration  */
+		wakeup_conf->int_wkup_threshold = data_array[1];
+		/* Get the reference acceleration x-axis for the wake-up interrupt */
+		wakeup_conf->int_wkup_ref_x = data_array[2];
+		/* Get the reference acceleration y-axis for the wake-up interrupt */
+		wakeup_conf->int_wkup_ref_y = data_array[3];
+		/* Get the reference acceleration z-axis for the wake-up interrupt */
+		wakeup_conf->int_wkup_ref_z = data_array[4];
+	}
+	return rslt;
+}
+/*!
+ * @brief This API sets the sensor to enter low power mode
+ * automatically  based on the configurations
+ */
+static int8_t set_auto_low_power(const struct bma400_auto_lp_conf *auto_lp_conf, const struct bma400_dev *dev)
+{
+	int8_t rslt;
+	uint8_t reg_data;
+	uint8_t timeout_msb;
+	uint8_t timeout_lsb;
+
+	rslt = bma400_get_regs(BMA400_AUTO_LOW_POW_1_ADDR, &reg_data, 1, dev);
+	if (rslt == BMA400_OK) {
+		reg_data = BMA400_SET_BITS_POS_0(reg_data, BMA400_AUTO_LOW_POW, auto_lp_conf->auto_low_power_trigger);
+		/* If auto Low power timeout threshold is enabled */
+		if (auto_lp_conf->auto_low_power_trigger & 0x0C) {
+			rslt = bma400_get_regs(BMA400_AUTO_LOW_POW_0_ADDR, &timeout_msb, 1, dev);
+			if (rslt == BMA400_OK) {
+				/* Compute the timeout threshold MSB value */
+				timeout_msb = BMA400_GET_BITS(auto_lp_conf->auto_lp_timeout_threshold,
+							      BMA400_AUTO_LP_THRES);
+				/* Compute the timeout threshold LSB value */
+				timeout_lsb = BMA400_GET_BITS_POS_0(auto_lp_conf->auto_lp_timeout_threshold,
+								    BMA400_AUTO_LP_THRES_LSB);
+				reg_data = BMA400_SET_BITS(reg_data, BMA400_AUTO_LP_TIMEOUT_LSB, timeout_lsb);
+				/* Set the timeout threshold MSB value */
+				rslt = bma400_set_regs(BMA400_AUTO_LOW_POW_0_ADDR, &timeout_msb, 1, dev);
+			}
+		}
+		if (rslt == BMA400_OK) {
+			/* Set the Auto low power configurations */
+			rslt = bma400_set_regs(BMA400_AUTO_LOW_POW_1_ADDR, &reg_data, 1, dev);
+		}
+	}
+	return rslt;
+}
+/*!
+ * @brief This API gets the sensor to get the auto-low
+ * power mode configuration settings
+ */
+static int8_t get_auto_low_power(struct bma400_auto_lp_conf *auto_lp_conf, const struct bma400_dev *dev)
+{
+	int8_t rslt;
+	uint8_t data_array[2];
+	uint8_t timeout_msb;
+	uint8_t timeout_lsb;
+
+	rslt = bma400_get_regs(BMA400_AUTO_LOW_POW_0_ADDR, data_array, 2, dev);
+	if (rslt == BMA400_OK) {
+		/* Get the auto low power trigger */
+		auto_lp_conf->auto_low_power_trigger = BMA400_GET_BITS_POS_0(data_array[1], BMA400_AUTO_LOW_POW);
+		timeout_msb = data_array[0];
+		timeout_lsb = BMA400_GET_BITS(data_array[1], BMA400_AUTO_LP_TIMEOUT_LSB);
+		/* Get the auto low power timeout threshold */
+		auto_lp_conf->auto_lp_timeout_threshold = timeout_msb << 4 | timeout_lsb;
+	}
+	return rslt;
+}
+/*!
+ * @brief This API sets the tap setting parameters
+ */
+static int8_t set_tap_conf(const struct bma400_tap_conf *tap_set, const struct bma400_dev *dev)
+{
+	int8_t rslt;
+	uint8_t reg_data[2] = { 0, 0 };
+
+	rslt = bma400_get_regs(BMA400_TAP_CONFIG_ADDR, reg_data, 2, dev);
+
+	if (rslt == BMA400_OK) {
+		/* Set the axis to sense for tap */
+		reg_data[0] = BMA400_SET_BITS(reg_data[0], BMA400_TAP_AXES_EN, tap_set->axes_sel);
+		/* Set the threshold for tap sensing */
+		reg_data[0] = BMA400_SET_BITS_POS_0(reg_data[0], BMA400_TAP_SENSITIVITY, tap_set->sensitivity);
+		/* Set the Quiet_dt setting */
+		reg_data[1] = BMA400_SET_BITS(reg_data[1], BMA400_TAP_QUIET_DT, tap_set->quiet_dt);
+		/* Set the Quiet setting */
+		reg_data[1] = BMA400_SET_BITS(reg_data[1], BMA400_TAP_QUIET, tap_set->quiet);
+		/* Set the tics_th setting */
+		reg_data[1] = BMA400_SET_BITS_POS_0(reg_data[1], BMA400_TAP_TICS_TH, tap_set->tics_th);
+		/* Set the TAP configuration in the sensor*/
+		rslt = bma400_set_regs(BMA400_TAP_CONFIG_ADDR, reg_data, 2, dev);
+	}
+
+	return rslt;
+}
+/*!
+ * @brief This API gets the tap setting parameters
+ */
+static int8_t get_tap_conf(struct bma400_tap_conf *tap_set, const struct bma400_dev *dev)
+{
+	int8_t rslt;
+	uint8_t reg_data[2];
+
+	rslt = bma400_get_regs(BMA400_TAP_CONFIG_ADDR, reg_data, 2, dev);
+	if (rslt == BMA400_OK) {
+		/* Get the axis enabled for tap sensing */
+		tap_set->axes_sel = BMA400_GET_BITS(reg_data[0], BMA400_TAP_AXES_EN);
+		/* Get the threshold for tap sensing */
+		tap_set->sensitivity = BMA400_GET_BITS_POS_0(reg_data[0], BMA400_TAP_SENSITIVITY);
+		/* Get the Quiet_dt setting */
+		tap_set->quiet_dt = BMA400_GET_BITS(reg_data[1], BMA400_TAP_QUIET_DT);
+		/* Get the Quiet setting */
+		tap_set->quiet = BMA400_GET_BITS(reg_data[1], BMA400_TAP_QUIET);
+		/* Get the tics_th setting */
+		tap_set->tics_th = BMA400_GET_BITS_POS_0(reg_data[1], BMA400_TAP_TICS_TH);
+	}
+	return rslt;
+}
+/*!
+ * @brief This API sets the parameters for activity change detection
+ */
+static int8_t set_activity_change_conf(const struct bma400_act_ch_conf *act_ch_set, const struct bma400_dev *dev)
+{
+	int8_t rslt;
+	uint8_t data_array[2] = { 0 };
+
+	/* Set the activity change threshold */
+	data_array[0] = act_ch_set->act_ch_thres;
+	/* Set the axis to sense for activity change */
+	data_array[1] = BMA400_SET_BITS(data_array[1], BMA400_ACT_CH_AXES_EN, act_ch_set->axes_sel);
+	/* Set the data source for activity change */
+	data_array[1] = BMA400_SET_BITS(data_array[1], BMA400_ACT_CH_DATA_SRC, act_ch_set->data_source);
+	/* Set the Number of sample points(NPTS)
+	 * for sensing activity change */
+	data_array[1] = BMA400_SET_BITS_POS_0(data_array[1], BMA400_ACT_CH_NPTS, act_ch_set->act_ch_ntps);
+	/* Set the Activity change configuration in the sensor*/
+	rslt = bma400_set_regs(BMA400_ACT_CH_CONFIG_0_ADDR, data_array, 2, dev);
+	return rslt;
+}
+/*!
+ * @brief This API gets the parameters for activity change detection
+ */
+static int8_t get_activity_change_conf(struct bma400_act_ch_conf *act_ch_set, const struct bma400_dev *dev)
+{
+	int8_t rslt;
+	uint8_t data_array[2];
+
+	rslt = bma400_get_regs(BMA400_ACT_CH_CONFIG_0_ADDR, data_array, 2, dev);
+	if (rslt == BMA400_OK) {
+		/* Get the activity change threshold */
+		act_ch_set->act_ch_thres = data_array[0];
+		/* Get the axis enabled for activity change detection */
+		act_ch_set->axes_sel = BMA400_GET_BITS(data_array[1], BMA400_ACT_CH_AXES_EN);
+		/* Get the data source for activity change */
+		act_ch_set->data_source = BMA400_GET_BITS(data_array[1], BMA400_ACT_CH_DATA_SRC);
+		/* Get the Number of sample points(NPTS)
+		 * for sensing activity change */
+		act_ch_set->act_ch_ntps = BMA400_GET_BITS_POS_0(data_array[1], BMA400_ACT_CH_NPTS);
+	}
+	return rslt;
+}
+/*!
+ * @brief This API sets the parameters for generic interrupt1 configuration
+ */
+static int8_t set_gen1_int(const struct bma400_gen_int_conf *gen_int_set, const struct bma400_dev *dev)
+{
+	int8_t rslt;
+	uint8_t data_array[11] = { 0 };
+
+	/* Set the axes to sense for interrupt */
+	data_array[0] = BMA400_SET_BITS(data_array[0], BMA400_INT_AXES_EN, gen_int_set->axes_sel);
+	/* Set the data source for interrupt */
+	data_array[0] = BMA400_SET_BITS(data_array[0], BMA400_INT_DATA_SRC, gen_int_set->data_src);
+	/* Set the reference update mode */
+	data_array[0] = BMA400_SET_BITS(data_array[0], BMA400_INT_REFU, gen_int_set->ref_update);
+	/* Set the hysteresis for interrupt calculation */
+	data_array[0] = BMA400_SET_BITS_POS_0(data_array[0], BMA400_INT_HYST, gen_int_set->hysteresis);
+	/* Set the criterion to generate interrupt on either
+	 * ACTIVITY OR INACTIVITY */
+	data_array[1] = BMA400_SET_BITS(data_array[1], BMA400_GEN_INT_CRITERION, gen_int_set->criterion_sel);
+	/* Set the interrupt axes logic (AND/OR) for the
+	 * enabled axes to generate interrupt */
+	data_array[1] = BMA400_SET_BITS_POS_0(data_array[1], BMA400_GEN_INT_COMB, gen_int_set->evaluate_axes);
+	/* Set the interrupt threshold */
+	data_array[2] = gen_int_set->gen_int_thres;
+	/* Set the MSB of gen int dur */
+	data_array[3] = BMA400_GET_MSB(gen_int_set->gen_int_dur);
+	/* Set the LSB of gen int dur */
+	data_array[4] = BMA400_GET_LSB(gen_int_set->gen_int_dur);
+	/* Handling case of manual reference update */
+	if (gen_int_set->ref_update == BMA400_MANUAL_UPDATE) {
+		/* Set the LSB of reference x threshold */
+		data_array[5] = BMA400_GET_LSB(gen_int_set->int_thres_ref_x);
+		/* Set the MSB of reference x threshold */
+		data_array[6] = BMA400_GET_MSB(gen_int_set->int_thres_ref_x);
+		/* Set the LSB of reference y threshold */
+		data_array[7] = BMA400_GET_LSB(gen_int_set->int_thres_ref_y);
+		/* Set the MSB of reference y threshold */
+		data_array[8] = BMA400_GET_MSB(gen_int_set->int_thres_ref_y);
+		/* Set the LSB of reference z threshold */
+		data_array[9] = BMA400_GET_LSB(gen_int_set->int_thres_ref_z);
+		/* Set the MSB of reference z threshold */
+		data_array[10] = BMA400_GET_MSB(gen_int_set->int_thres_ref_z);
+		/* Set the GEN1 INT configuration in the sensor */
+		rslt = bma400_set_regs(BMA400_GEN1_INT_CONFIG_ADDR, data_array, 11, dev);
+	} else {
+		/* Set the GEN1 INT configuration in the sensor */
+		rslt = bma400_set_regs(BMA400_GEN1_INT_CONFIG_ADDR, data_array, 5, dev);
+	}
+	return rslt;
+}
+/*!
+ * @brief This API gets the generic interrupt1 configuration
+ */
+static int8_t get_gen1_int(struct bma400_gen_int_conf *gen_int_set, const struct bma400_dev *dev)
+{
+	int8_t rslt;
+	uint8_t data_array[11];
+
+	rslt = bma400_get_regs(BMA400_GEN1_INT_CONFIG_ADDR, data_array, 11, dev);
+	if (rslt == BMA400_OK) {
+		/* Get the axes to sense for interrupt */
+		gen_int_set->axes_sel = BMA400_GET_BITS(data_array[0], BMA400_INT_AXES_EN);
+		/* Get the data source for interrupt */
+		gen_int_set->data_src = BMA400_GET_BITS(data_array[0], BMA400_INT_DATA_SRC);
+		/* Get the reference update mode */
+		gen_int_set->ref_update = BMA400_GET_BITS(data_array[0], BMA400_INT_REFU);
+		/* Get the hysteresis for interrupt calculation */
+		gen_int_set->hysteresis = BMA400_GET_BITS_POS_0(data_array[0], BMA400_INT_HYST);
+		/* Get the interrupt axes logic (AND/OR) to generate interrupt */
+		gen_int_set->evaluate_axes = BMA400_GET_BITS_POS_0(data_array[1], BMA400_GEN_INT_COMB);
+		/* Get the criterion to generate interrupt ACTIVITY/INACTIVITY */
+		gen_int_set->criterion_sel = BMA400_GET_BITS(data_array[1], BMA400_GEN_INT_CRITERION);
+		/* Get the interrupt threshold */
+		gen_int_set->gen_int_thres = data_array[2];
+		/* Get the interrupt duration */
+		gen_int_set->gen_int_dur = ((uint16_t)data_array[3] << 8) | data_array[4];
+		/* Get the interrupt threshold */
+		data_array[6] = data_array[6] & 0x0F;
+		gen_int_set->int_thres_ref_x = ((uint16_t)data_array[6] << 8) | data_array[5];
+		data_array[8] = data_array[8] & 0x0F;
+		gen_int_set->int_thres_ref_y = ((uint16_t)data_array[8] << 8) | data_array[7];
+		data_array[10] = data_array[10] & 0x0F;
+		gen_int_set->int_thres_ref_z = ((uint16_t)data_array[10] << 8) | data_array[9];
+	}
+	return rslt;
+}
+/*!
+ * @brief This API sets the parameters for generic interrupt2 configuration
+ */
+static int8_t set_gen2_int(const struct bma400_gen_int_conf *gen_int_set, const struct bma400_dev *dev)
+{
+	int8_t rslt;
+	uint8_t data_array[11] = { 0 };
+
+	/* Set the axes to sense for interrupt */
+	data_array[0] = BMA400_SET_BITS(data_array[0], BMA400_INT_AXES_EN, gen_int_set->axes_sel);
+	/* Set the data source for interrupt */
+	data_array[0] = BMA400_SET_BITS(data_array[0], BMA400_INT_DATA_SRC, gen_int_set->data_src);
+	/* Set the reference update mode */
+	data_array[0] = BMA400_SET_BITS(data_array[0], BMA400_INT_REFU, gen_int_set->ref_update);
+	/* Set the hysteresis for interrupt calculation */
+	data_array[0] = BMA400_SET_BITS_POS_0(data_array[0], BMA400_INT_HYST, gen_int_set->hysteresis);
+	/* Set the criterion to generate interrupt on either
+	 * ACTIVITY OR INACTIVITY */
+	data_array[1] = BMA400_SET_BITS(data_array[1], BMA400_GEN_INT_CRITERION, gen_int_set->criterion_sel);
+	/* Set the interrupt axes logic (AND/OR) for the
+	 * enabled axes to generate interrupt */
+	data_array[1] = BMA400_SET_BITS_POS_0(data_array[1], BMA400_GEN_INT_COMB, gen_int_set->evaluate_axes);
+	/* Set the interrupt threshold */
+	data_array[2] = gen_int_set->gen_int_thres;
+	/* Set the MSB of gen int dur */
+	data_array[3] = BMA400_GET_MSB(gen_int_set->gen_int_dur);
+	/* Set the LSB of gen int dur */
+	data_array[4] = BMA400_GET_LSB(gen_int_set->gen_int_dur);
+	/* Handling case of manual reference update */
+	if (gen_int_set->ref_update == BMA400_MANUAL_UPDATE) {
+		/* Set the LSB of reference x threshold */
+		data_array[5] = BMA400_GET_LSB(gen_int_set->int_thres_ref_x);
+		/* Set the MSB of reference x threshold */
+		data_array[6] = BMA400_GET_MSB(gen_int_set->int_thres_ref_x);
+		/* Set the LSB of reference y threshold */
+		data_array[7] = BMA400_GET_LSB(gen_int_set->int_thres_ref_y);
+		/* Set the MSB of reference y threshold */
+		data_array[8] = BMA400_GET_MSB(gen_int_set->int_thres_ref_y);
+		/* Set the LSB of reference z threshold */
+		data_array[9] = BMA400_GET_LSB(gen_int_set->int_thres_ref_z);
+		/* Set the MSB of reference z threshold */
+		data_array[10] = BMA400_GET_MSB(gen_int_set->int_thres_ref_z);
+		/* Set the GEN2 INT configuration in the sensor */
+		rslt = bma400_set_regs(BMA400_GEN2_INT_CONFIG_ADDR, data_array, 11, dev);
+	} else {
+		/* Set the GEN2 INT configuration in the sensor */
+		rslt = bma400_set_regs(BMA400_GEN2_INT_CONFIG_ADDR, data_array, 5, dev);
+	}
+	return rslt;
+}
+/*!
+ * @brief This API gets the generic interrupt2 configuration
+ */
+static int8_t get_gen2_int(struct bma400_gen_int_conf *gen_int_set, const struct bma400_dev *dev)
+{
+	int8_t rslt;
+	uint8_t data_array[11];
+
+	rslt = bma400_get_regs(BMA400_GEN2_INT_CONFIG_ADDR, data_array, 11, dev);
+	if (rslt == BMA400_OK) {
+		/* Get the axes to sense for interrupt */
+		gen_int_set->axes_sel = BMA400_GET_BITS(data_array[0], BMA400_INT_AXES_EN);
+		/* Get the data source for interrupt */
+		gen_int_set->data_src = BMA400_GET_BITS(data_array[0], BMA400_INT_DATA_SRC);
+		/* Get the reference update mode */
+		gen_int_set->ref_update = BMA400_GET_BITS(data_array[0], BMA400_INT_REFU);
+		/* Get the hysteresis for interrupt calculation */
+		gen_int_set->hysteresis = BMA400_GET_BITS_POS_0(data_array[0], BMA400_INT_HYST);
+		/* Get the interrupt axes logic (AND/OR) to generate interrupt */
+		gen_int_set->evaluate_axes = BMA400_GET_BITS_POS_0(data_array[1], BMA400_GEN_INT_COMB);
+		/* Get the criterion to generate interrupt ACTIVITY/INACTIVITY */
+		gen_int_set->criterion_sel = BMA400_GET_BITS(data_array[1], BMA400_GEN_INT_CRITERION);
+		/* Get the interrupt threshold */
+		gen_int_set->gen_int_thres = data_array[2];
+		/* Get the interrupt duration */
+		gen_int_set->gen_int_dur = ((uint16_t)data_array[3] << 8) | data_array[4];
+		/* Get the interrupt threshold */
+		data_array[6] = data_array[6] & 0x0F;
+		gen_int_set->int_thres_ref_x = ((uint16_t)data_array[6] << 8) | data_array[5];
+		data_array[8] = data_array[8] & 0x0F;
+		gen_int_set->int_thres_ref_y = ((uint16_t)data_array[8] << 8) | data_array[7];
+		data_array[10] = data_array[10] & 0x0F;
+		gen_int_set->int_thres_ref_z = ((uint16_t)data_array[10] << 8) | data_array[9];
+	}
+	return rslt;
+}
+/*!
+ * @brief This API sets the parameters for orientation interrupt
+ */
+static int8_t set_orient_int(const struct bma400_orient_int_conf *orient_conf, const struct bma400_dev *dev)
+{
+	int8_t rslt;
+	uint8_t data_array[10] = { 0 };
+
+	/* Set the axes to sense for interrupt */
+	data_array[0] = BMA400_SET_BITS(data_array[0], BMA400_INT_AXES_EN, orient_conf->axes_sel);
+	/* Set the data source for interrupt */
+	data_array[0] = BMA400_SET_BITS(data_array[0], BMA400_INT_DATA_SRC, orient_conf->data_src);
+	/* Set the reference update mode */
+	data_array[0] = BMA400_SET_BITS(data_array[0], BMA400_INT_REFU, orient_conf->ref_update);
+	/* Set the stability_mode for interrupt calculation */
+	data_array[0] = BMA400_SET_BITS_POS_0(data_array[0], BMA400_STABILITY_MODE, orient_conf->stability_mode);
+	/* Set the threshold for interrupt calculation */
+	data_array[1] = orient_conf->orient_thres;
+	/* Set the stability threshold */
+	data_array[2] = orient_conf->stability_thres;
+	/* Set the interrupt duration */
+	data_array[3] = orient_conf->orient_int_dur;
+	/* Handling case of manual reference update */
+	if (orient_conf->ref_update == BMA400_MANUAL_UPDATE) {
+		/* Set the LSB of reference x threshold */
+		data_array[4] = BMA400_GET_LSB(orient_conf->orient_ref_x);
+		/* Set the MSB of reference x threshold */
+		data_array[5] = BMA400_GET_MSB(orient_conf->orient_ref_x);
+		/* Set the MSB of reference x threshold */
+		data_array[6] = BMA400_GET_LSB(orient_conf->orient_ref_y);
+		/* Set the LSB of reference y threshold */
+		data_array[7] = BMA400_GET_MSB(orient_conf->orient_ref_y);
+		/* Set the MSB of reference y threshold */
+		data_array[8] = BMA400_GET_LSB(orient_conf->orient_ref_z);
+		/* Set the LSB of reference z threshold */
+		data_array[9] = BMA400_GET_MSB(orient_conf->orient_ref_z);
+		/* Set the orient configurations in the sensor */
+		rslt = bma400_set_regs(BMA400_ORIENTCH_INT_CONFIG_ADDR, data_array, 10, dev);
+	} else {
+		/* Set the orient configurations in the sensor excluding
+		 * reference values of x,y,z */
+		rslt = bma400_set_regs(BMA400_ORIENTCH_INT_CONFIG_ADDR, data_array, 4, dev);
+	}
+	return rslt;
+}
+/*!
+ * @brief This API gets the parameters for orientation interrupt
+ */
+static int8_t get_orient_int(struct bma400_orient_int_conf *orient_conf, const struct bma400_dev *dev)
+{
+	int8_t rslt;
+	uint8_t data_array[10];
+
+	rslt = bma400_get_regs(BMA400_ORIENTCH_INT_CONFIG_ADDR, data_array, 10, dev);
+	if (rslt == BMA400_OK) {
+		/* Get the axes to sense for interrupt */
+		orient_conf->axes_sel = BMA400_GET_BITS(data_array[0], BMA400_INT_AXES_EN);
+		/* Get the data source for interrupt */
+		orient_conf->data_src = BMA400_GET_BITS(data_array[0], BMA400_INT_DATA_SRC);
+		/* Get the reference update mode */
+		orient_conf->ref_update = BMA400_GET_BITS(data_array[0], BMA400_INT_REFU);
+		/* Get the stability_mode for interrupt calculation */
+		orient_conf->stability_mode = BMA400_GET_BITS_POS_0(data_array[0], BMA400_STABILITY_MODE);
+		/* Get the threshold for interrupt calculation */
+		orient_conf->orient_thres = data_array[1];
+		/* Get the stability threshold */
+		orient_conf->stability_thres = data_array[2];
+		/* Get the interrupt duration */
+		orient_conf->orient_int_dur = data_array[3];
+		/* Get the interrupt reference values */
+		data_array[5] = data_array[5] & 0x0F;
+		orient_conf->orient_ref_x = ((uint16_t)data_array[5] << 8) | data_array[4];
+		data_array[5] = data_array[7] & 0x0F;
+		orient_conf->orient_ref_y = ((uint16_t)data_array[7] << 8) | data_array[6];
+		data_array[5] = data_array[9] & 0x0F;
+		orient_conf->orient_ref_z = ((uint16_t)data_array[9] << 8) | data_array[8];
+	}
+	return rslt;
+}
+/*!
+ * @brief This API sets the selected interrupt to be mapped to
+ * the hardware interrupt pin of the sensor
+ */
+static void map_int_pin(uint8_t *data_array, uint8_t int_enable, enum bma400_int_chan int_map)
+{
+	switch (int_enable) {
+	case BMA400_DATA_READY_INT_MAP:
+		if (int_map == BMA400_INT_CHANNEL_1) {
+			/* Mapping interrupt to INT pin 1*/
+			data_array[0] = BMA400_SET_BITS(data_array[0], BMA400_EN_DRDY, BMA400_ENABLE);
+		}
+		if (int_map == BMA400_INT_CHANNEL_2) {
+			/* Mapping interrupt to INT pin 2*/
+			data_array[1] = BMA400_SET_BITS(data_array[1], BMA400_EN_DRDY, BMA400_ENABLE);
+		}
+		if (int_map == BMA400_UNMAP_INT_PIN) {
+			data_array[0] = BMA400_SET_BIT_VAL_0(data_array[0], BMA400_EN_DRDY);
+			data_array[1] = BMA400_SET_BIT_VAL_0(data_array[1], BMA400_EN_DRDY);
+		}
+		if (int_map == BMA400_MAP_BOTH_INT_PINS) {
+			data_array[0] = BMA400_SET_BITS(data_array[0], BMA400_EN_DRDY, BMA400_ENABLE);
+			data_array[1] = BMA400_SET_BITS(data_array[1], BMA400_EN_DRDY, BMA400_ENABLE);
+		}
+		break;
+	case BMA400_FIFO_WM_INT_MAP:
+		if (int_map == BMA400_INT_CHANNEL_1) {
+			/* Mapping interrupt to INT pin 1*/
+			data_array[0] = BMA400_SET_BITS(data_array[0], BMA400_EN_FIFO_WM, BMA400_ENABLE);
+		}
+		if (int_map == BMA400_INT_CHANNEL_2) {
+			/* Mapping interrupt to INT pin 2*/
+			data_array[1] = BMA400_SET_BITS(data_array[1], BMA400_EN_FIFO_WM, BMA400_ENABLE);
+		}
+		if (int_map == BMA400_UNMAP_INT_PIN) {
+			data_array[0] = BMA400_SET_BIT_VAL_0(data_array[0], BMA400_EN_FIFO_WM);
+			data_array[1] = BMA400_SET_BIT_VAL_0(data_array[1], BMA400_EN_FIFO_WM);
+		}
+		if (int_map == BMA400_MAP_BOTH_INT_PINS) {
+			data_array[0] = BMA400_SET_BITS(data_array[0], BMA400_EN_FIFO_WM, BMA400_ENABLE);
+			data_array[1] = BMA400_SET_BITS(data_array[1], BMA400_EN_FIFO_WM, BMA400_ENABLE);
+		}
+		break;
+	case BMA400_FIFO_FULL_INT_MAP:
+		if (int_map == BMA400_INT_CHANNEL_1) {
+			/* Mapping interrupt to INT pin 1 */
+			data_array[0] = BMA400_SET_BITS(data_array[0], BMA400_EN_FIFO_FULL, BMA400_ENABLE);
+		}
+		if (int_map == BMA400_INT_CHANNEL_2) {
+			/* Mapping interrupt to INT pin 2 */
+			data_array[1] = BMA400_SET_BITS(data_array[1], BMA400_EN_FIFO_FULL, BMA400_ENABLE);
+		}
+		if (int_map == BMA400_UNMAP_INT_PIN) {
+			data_array[0] = BMA400_SET_BIT_VAL_0(data_array[0], BMA400_EN_FIFO_FULL);
+			data_array[1] = BMA400_SET_BIT_VAL_0(data_array[1], BMA400_EN_FIFO_FULL);
+		}
+		if (int_map == BMA400_MAP_BOTH_INT_PINS) {
+			data_array[0] = BMA400_SET_BITS(data_array[0], BMA400_EN_FIFO_FULL, BMA400_ENABLE);
+			data_array[1] = BMA400_SET_BITS(data_array[1], BMA400_EN_FIFO_FULL, BMA400_ENABLE);
+		}
+		break;
+	case BMA400_INT_OVERRUN_MAP:
+		if (int_map == BMA400_INT_CHANNEL_1) {
+			/* Mapping interrupt to INT pin 1 */
+			data_array[0] = BMA400_SET_BITS(data_array[0], BMA400_EN_INT_OVERRUN, BMA400_ENABLE);
+		}
+		if (int_map == BMA400_INT_CHANNEL_2) {
+			/* Mapping interrupt to INT pin 2 */
+			data_array[1] = BMA400_SET_BITS(data_array[1], BMA400_EN_INT_OVERRUN, BMA400_ENABLE);
+		}
+		if (int_map == BMA400_UNMAP_INT_PIN) {
+			data_array[0] = BMA400_SET_BIT_VAL_0(data_array[0], BMA400_EN_INT_OVERRUN);
+			data_array[1] = BMA400_SET_BIT_VAL_0(data_array[1], BMA400_EN_INT_OVERRUN);
+		}
+		if (int_map == BMA400_MAP_BOTH_INT_PINS) {
+			data_array[0] = BMA400_SET_BITS(data_array[0], BMA400_EN_INT_OVERRUN, BMA400_ENABLE);
+			data_array[1] = BMA400_SET_BITS(data_array[1], BMA400_EN_INT_OVERRUN, BMA400_ENABLE);
+		}
+		break;
+	case BMA400_GEN2_INT_MAP:
+		if (int_map == BMA400_INT_CHANNEL_1) {
+			/* Mapping interrupt to INT pin 1 */
+			data_array[0] = BMA400_SET_BITS(data_array[0], BMA400_EN_GEN2, BMA400_ENABLE);
+		}
+		if (int_map == BMA400_INT_CHANNEL_2) {
+			/* Mapping interrupt to INT pin 2 */
+			data_array[1] = BMA400_SET_BITS(data_array[1], BMA400_EN_GEN2, BMA400_ENABLE);
+		}
+		if (int_map == BMA400_UNMAP_INT_PIN) {
+			data_array[0] = BMA400_SET_BIT_VAL_0(data_array[0], BMA400_EN_GEN2);
+			data_array[1] = BMA400_SET_BIT_VAL_0(data_array[1], BMA400_EN_GEN2);
+		}
+		if (int_map == BMA400_MAP_BOTH_INT_PINS) {
+			data_array[0] = BMA400_SET_BITS(data_array[0], BMA400_EN_GEN2, BMA400_ENABLE);
+			data_array[1] = BMA400_SET_BITS(data_array[1], BMA400_EN_GEN2, BMA400_ENABLE);
+		}
+		break;
+	case BMA400_GEN1_INT_MAP:
+		if (int_map == BMA400_INT_CHANNEL_1) {
+			/* Mapping interrupt to INT pin 1 */
+			data_array[0] = BMA400_SET_BITS(data_array[0], BMA400_EN_GEN1, BMA400_ENABLE);
+		}
+		if (int_map == BMA400_INT_CHANNEL_2) {
+			/* Mapping interrupt to INT pin 2 */
+			data_array[1] = BMA400_SET_BITS(data_array[1], BMA400_EN_GEN1, BMA400_ENABLE);
+		}
+		if (int_map == BMA400_UNMAP_INT_PIN) {
+			data_array[0] = BMA400_SET_BIT_VAL_0(data_array[0], BMA400_EN_GEN1);
+			data_array[1] = BMA400_SET_BIT_VAL_0(data_array[1], BMA400_EN_GEN1);
+		}
+		if (int_map == BMA400_MAP_BOTH_INT_PINS) {
+			data_array[0] = BMA400_SET_BITS(data_array[0], BMA400_EN_GEN1, BMA400_ENABLE);
+			data_array[1] = BMA400_SET_BITS(data_array[1], BMA400_EN_GEN1, BMA400_ENABLE);
+		}
+		break;
+	case BMA400_ORIENT_CH_INT_MAP:
+		if (int_map == BMA400_INT_CHANNEL_1) {
+			/* Mapping interrupt to INT pin 1 */
+			data_array[0] = BMA400_SET_BITS(data_array[0], BMA400_EN_ORIENT_CH, BMA400_ENABLE);
+		}
+		if (int_map == BMA400_INT_CHANNEL_2) {
+			/* Mapping interrupt to INT pin 2 */
+			data_array[1] = BMA400_SET_BITS(data_array[1], BMA400_EN_ORIENT_CH, BMA400_ENABLE);
+		}
+		if (int_map == BMA400_UNMAP_INT_PIN) {
+			data_array[0] = BMA400_SET_BIT_VAL_0(data_array[0], BMA400_EN_ORIENT_CH);
+			data_array[1] = BMA400_SET_BIT_VAL_0(data_array[1], BMA400_EN_ORIENT_CH);
+		}
+		if (int_map == BMA400_MAP_BOTH_INT_PINS) {
+			data_array[0] = BMA400_SET_BITS(data_array[0], BMA400_EN_ORIENT_CH, BMA400_ENABLE);
+			data_array[1] = BMA400_SET_BITS(data_array[1], BMA400_EN_ORIENT_CH, BMA400_ENABLE);
+		}
+		break;
+	case BMA400_WAKEUP_INT_MAP:
+		if (int_map == BMA400_INT_CHANNEL_1) {
+			/* Mapping interrupt to INT pin 1 */
+			data_array[0] = BMA400_SET_BITS_POS_0(data_array[0], BMA400_EN_WAKEUP_INT, BMA400_ENABLE);
+		}
+		if (int_map == BMA400_INT_CHANNEL_2) {
+			/* Mapping interrupt to INT pin 2 */
+			data_array[1] = BMA400_SET_BITS_POS_0(data_array[1], BMA400_EN_WAKEUP_INT, BMA400_ENABLE);
+		}
+		if (int_map == BMA400_UNMAP_INT_PIN) {
+			data_array[0] = BMA400_SET_BIT_VAL_0(data_array[0], BMA400_EN_WAKEUP_INT);
+			data_array[1] = BMA400_SET_BIT_VAL_0(data_array[1], BMA400_EN_WAKEUP_INT);
+		}
+		if (int_map == BMA400_MAP_BOTH_INT_PINS) {
+			data_array[0] = BMA400_SET_BITS_POS_0(data_array[0], BMA400_EN_WAKEUP_INT, BMA400_ENABLE);
+			data_array[1] = BMA400_SET_BITS_POS_0(data_array[1], BMA400_EN_WAKEUP_INT, BMA400_ENABLE);
+		}
+		break;
+	case BMA400_ACT_CH_INT_MAP:
+		if (int_map == BMA400_INT_CHANNEL_1) {
+			/* Mapping interrupt to INT pin 1 */
+			data_array[2] = BMA400_SET_BITS(data_array[2], BMA400_ACTCH_MAP_INT1, BMA400_ENABLE);
+		}
+		if (int_map == BMA400_INT_CHANNEL_2) {
+			/* Mapping interrupt to INT pin 2 */
+			data_array[2] = BMA400_SET_BITS(data_array[2], BMA400_ACTCH_MAP_INT2, BMA400_ENABLE);
+		}
+		if (int_map == BMA400_UNMAP_INT_PIN) {
+			data_array[2] = BMA400_SET_BIT_VAL_0(data_array[2], BMA400_ACTCH_MAP_INT1);
+			data_array[2] = BMA400_SET_BIT_VAL_0(data_array[2], BMA400_ACTCH_MAP_INT2);
+		}
+		if (int_map == BMA400_MAP_BOTH_INT_PINS) {
+			data_array[2] = BMA400_SET_BITS(data_array[2], BMA400_ACTCH_MAP_INT1, BMA400_ENABLE);
+			data_array[2] = BMA400_SET_BITS(data_array[2], BMA400_ACTCH_MAP_INT2, BMA400_ENABLE);
+		}
+		break;
+	case BMA400_TAP_INT_MAP:
+		if (int_map == BMA400_INT_CHANNEL_1) {
+			/* Mapping interrupt to INT pin 1 */
+			data_array[2] = BMA400_SET_BITS(data_array[2], BMA400_TAP_MAP_INT1, BMA400_ENABLE);
+		}
+		if (int_map == BMA400_INT_CHANNEL_2) {
+			/* Mapping interrupt to INT pin 2 */
+			data_array[2] = BMA400_SET_BITS(data_array[2], BMA400_TAP_MAP_INT2, BMA400_ENABLE);
+		}
+		if (int_map == BMA400_UNMAP_INT_PIN) {
+			data_array[2] = BMA400_SET_BIT_VAL_0(data_array[2], BMA400_TAP_MAP_INT1);
+			data_array[2] = BMA400_SET_BIT_VAL_0(data_array[2], BMA400_TAP_MAP_INT2);
+		}
+		if (int_map == BMA400_MAP_BOTH_INT_PINS) {
+			data_array[2] = BMA400_SET_BITS(data_array[2], BMA400_TAP_MAP_INT1, BMA400_ENABLE);
+			data_array[2] = BMA400_SET_BITS(data_array[2], BMA400_TAP_MAP_INT2, BMA400_ENABLE);
+		}
+		break;
+	case BMA400_STEP_INT_MAP:
+		if (int_map == BMA400_INT_CHANNEL_1) {
+			/* Mapping interrupt to INT pin 1 */
+			data_array[2] = BMA400_SET_BITS_POS_0(data_array[2], BMA400_EN_STEP_INT, BMA400_ENABLE);
+		}
+		if (int_map == BMA400_INT_CHANNEL_2) {
+			/* Mapping interrupt to INT pin 2 */
+			data_array[2] = BMA400_SET_BITS(data_array[2], BMA400_STEP_MAP_INT2, BMA400_ENABLE);
+		}
+		if (int_map == BMA400_UNMAP_INT_PIN) {
+			data_array[2] = BMA400_SET_BIT_VAL_0(data_array[2], BMA400_EN_STEP_INT);
+			data_array[2] = BMA400_SET_BIT_VAL_0(data_array[2], BMA400_STEP_MAP_INT2);
+		}
+		if (int_map == BMA400_MAP_BOTH_INT_PINS) {
+			data_array[2] = BMA400_SET_BITS_POS_0(data_array[2], BMA400_EN_STEP_INT, BMA400_ENABLE);
+			data_array[2] = BMA400_SET_BITS(data_array[2], BMA400_STEP_MAP_INT2, BMA400_ENABLE);
+		}
+		break;
+	default:
+		break;
+	}
+}
+/*!
+ * @brief This API checks whether the interrupt is mapped to the INT pin1
+ * or INT pin2 of the sensor
+ */
+static void check_mapped_interrupts(uint8_t int_1_map, uint8_t int_2_map, enum bma400_int_chan *int_map)
+{
+	if ((int_1_map == BMA400_ENABLE) && (int_2_map == BMA400_DISABLE)) {
+		/* INT 1 mapped INT 2 not mapped */
+		*int_map = BMA400_INT_CHANNEL_1;
+	}
+	if ((int_1_map == BMA400_DISABLE) && (int_2_map == BMA400_ENABLE)) {
+		/* INT 1 not mapped INT 2 mapped */
+		*int_map = BMA400_INT_CHANNEL_2;
+	}
+	if ((int_1_map == BMA400_ENABLE) && (int_2_map == BMA400_ENABLE)) {
+		/* INT 1 ,INT 2 both mapped */
+		*int_map = BMA400_MAP_BOTH_INT_PINS;
+	}
+	if ((int_1_map == BMA400_DISABLE) && (int_2_map == BMA400_DISABLE)) {
+		/* INT 1 ,INT 2 not mapped */
+		*int_map = BMA400_UNMAP_INT_PIN;
+	}
+}
+/*!
+ * @brief This API gets the selected interrupt and its mapping to
+ * the hardware interrupt pin of the sensor
+ */
+static void get_int_pin_map(const uint8_t *data_array, uint8_t int_enable, enum bma400_int_chan *int_map)
+{
+	uint8_t int_1_map;
+	uint8_t int_2_map;
+
+	switch (int_enable) {
+	case BMA400_DATA_READY_INT_MAP:
+		/* Interrupt 1 pin mapping status */
+		int_1_map = BMA400_GET_BITS(data_array[0], BMA400_EN_DRDY);
+		/* Interrupt 2 pin mapping status */
+		int_2_map = BMA400_GET_BITS(data_array[1], BMA400_EN_DRDY);
+		/* Check the mapped interrupt pins */
+		check_mapped_interrupts(int_1_map, int_2_map, int_map);
+		break;
+	case BMA400_FIFO_WM_INT_MAP:
+		/* Interrupt 1 pin mapping status */
+		int_1_map = BMA400_GET_BITS(data_array[0], BMA400_EN_FIFO_WM);
+		/* Interrupt 2 pin mapping status */
+		int_2_map = BMA400_GET_BITS(data_array[1], BMA400_EN_FIFO_WM);
+		/* Check the mapped interrupt pins */
+		check_mapped_interrupts(int_1_map, int_2_map, int_map);
+		break;
+	case BMA400_FIFO_FULL_INT_MAP:
+		/* Interrupt 1 pin mapping status */
+		int_1_map = BMA400_GET_BITS(data_array[0], BMA400_EN_FIFO_FULL);
+		/* Interrupt 2 pin mapping status */
+		int_2_map = BMA400_GET_BITS(data_array[1], BMA400_EN_FIFO_FULL);
+		/* Check the mapped interrupt pins */
+		check_mapped_interrupts(int_1_map, int_2_map, int_map);
+		break;
+	case BMA400_GEN2_INT_MAP:
+		/* Interrupt 1 pin mapping status */
+		int_1_map = BMA400_GET_BITS(data_array[0], BMA400_EN_GEN2);
+		/* Interrupt 2 pin mapping status */
+		int_2_map = BMA400_GET_BITS(data_array[1], BMA400_EN_GEN2);
+		/* Check the mapped interrupt pins */
+		check_mapped_interrupts(int_1_map, int_2_map, int_map);
+		break;
+	case BMA400_GEN1_INT_MAP:
+		/* Interrupt 1 pin mapping status */
+		int_1_map = BMA400_GET_BITS(data_array[0], BMA400_EN_GEN1);
+		/* Interrupt 2 pin mapping status */
+		int_2_map = BMA400_GET_BITS(data_array[1], BMA400_EN_GEN1);
+		/* Check the mapped interrupt pins */
+		check_mapped_interrupts(int_1_map, int_2_map, int_map);
+		break;
+	case BMA400_ORIENT_CH_INT_MAP:
+		/* Interrupt 1 pin mapping status */
+		int_1_map = BMA400_GET_BITS(data_array[0], BMA400_EN_ORIENT_CH);
+		/* Interrupt 2 pin mapping status */
+		int_2_map = BMA400_GET_BITS(data_array[1], BMA400_EN_ORIENT_CH);
+		/* Check the mapped interrupt pins */
+		check_mapped_interrupts(int_1_map, int_2_map, int_map);
+		break;
+	case BMA400_WAKEUP_INT_MAP:
+		/* Interrupt 1 pin mapping status */
+		int_1_map = BMA400_GET_BITS_POS_0(data_array[0], BMA400_EN_WAKEUP_INT);
+		/* Interrupt 2 pin mapping status */
+		int_2_map = BMA400_GET_BITS_POS_0(data_array[1], BMA400_EN_WAKEUP_INT);
+		/* Check the mapped interrupt pins */
+		check_mapped_interrupts(int_1_map, int_2_map, int_map);
+		break;
+	case BMA400_ACT_CH_INT_MAP:
+		/* Interrupt 1 pin mapping status */
+		int_1_map = BMA400_GET_BITS(data_array[2], BMA400_ACTCH_MAP_INT1);
+		/* Interrupt 2 pin mapping status */
+		int_2_map = BMA400_GET_BITS(data_array[2], BMA400_ACTCH_MAP_INT2);
+		/* Check the mapped interrupt pins */
+		check_mapped_interrupts(int_1_map, int_2_map, int_map);
+		break;
+	case BMA400_TAP_INT_MAP:
+		/* Interrupt 1 pin mapping status */
+		int_1_map = BMA400_GET_BITS(data_array[2], BMA400_TAP_MAP_INT1);
+		/* Interrupt 2 pin mapping status */
+		int_2_map = BMA400_GET_BITS(data_array[2], BMA400_TAP_MAP_INT2);
+		/* Check the mapped interrupt pins */
+		check_mapped_interrupts(int_1_map, int_2_map, int_map);
+		break;
+	case BMA400_STEP_INT_MAP:
+		/* Interrupt 1 pin mapping status */
+		int_1_map = BMA400_GET_BITS_POS_0(data_array[2], BMA400_EN_STEP_INT);
+		/* Interrupt 2 pin mapping status */
+		int_2_map = BMA400_GET_BITS(data_array[2], BMA400_STEP_MAP_INT2);
+		/* Check the mapped interrupt pins */
+		check_mapped_interrupts(int_1_map, int_2_map, int_map);
+		break;
+	case BMA400_INT_OVERRUN_MAP:
+		/* Interrupt 1 pin mapping status */
+		int_1_map = BMA400_GET_BITS(data_array[0], BMA400_EN_INT_OVERRUN);
+		/* Interrupt 2 pin mapping status */
+		int_2_map = BMA400_GET_BITS(data_array[1], BMA400_EN_INT_OVERRUN);
+		/* Check the mapped interrupt pins */
+		check_mapped_interrupts(int_1_map, int_2_map, int_map);
+		break;
+	default:
+		break;
+	}
+}
+/*!
+ * @brief This API is used to set the interrupt pin configurations
+ */
+static int8_t set_int_pin_conf(struct bma400_int_pin_conf int_conf, const struct bma400_dev *dev)
+{
+	int8_t rslt;
+	uint8_t reg_data;
+
+	rslt = bma400_get_regs(BMA400_INT_12_IO_CTRL_ADDR, &reg_data, 1, dev);
+	if (rslt == BMA400_OK) {
+		if (int_conf.int_chan == BMA400_INT_CHANNEL_1) {
+			/* Setting interrupt pin configurations */
+			reg_data = BMA400_SET_BITS(reg_data, BMA400_INT_PIN1_CONF, int_conf.pin_conf);
+		}
+		if (int_conf.int_chan == BMA400_INT_CHANNEL_2) {
+			/* Setting interrupt pin configurations */
+			reg_data = BMA400_SET_BITS(reg_data, BMA400_INT_PIN2_CONF, int_conf.pin_conf);
+		}
+		/* Set the configurations in the sensor */
+		rslt = bma400_set_regs(BMA400_INT_12_IO_CTRL_ADDR, &reg_data, 1, dev);
+	}
+	return rslt;
+}
+/*!
+ * @brief This API is used to get the interrupt pin configurations
+ */
+static int8_t get_int_pin_conf(struct bma400_int_pin_conf *int_conf, const struct bma400_dev *dev)
+{
+	int8_t rslt;
+	uint8_t reg_data;
+
+	rslt = bma400_get_regs(BMA400_INT_12_IO_CTRL_ADDR, &reg_data, 1, dev);
+	if (rslt == BMA400_OK) {
+		if (int_conf->int_chan == BMA400_INT_CHANNEL_1) {
+			/* reading Interrupt pin configurations */
+			int_conf->pin_conf = BMA400_GET_BITS(reg_data, BMA400_INT_PIN1_CONF);
+		}
+		if (int_conf->int_chan == BMA400_INT_CHANNEL_2) {
+			/* Setting interrupt pin configurations */
+			int_conf->pin_conf = BMA400_GET_BITS(reg_data, BMA400_INT_PIN2_CONF);
+		}
+	}
+	return rslt;
+}
+/*!
+ * @brief This API is used to get the FIFO configurations
+ */
+static int8_t get_fifo_conf(struct bma400_fifo_conf *fifo_conf, const struct bma400_dev *dev)
+{
+	int8_t rslt;
+	uint8_t data_array[3];
+
+	/* Check for null pointer in the device structure */
+	rslt = null_ptr_check(dev);
+	/* Proceed if null check is fine */
+	if (rslt == BMA400_OK) {
+		/* Get the FIFO configurations and water-mark
+		 * values from the sensor */
+		rslt = bma400_get_regs(BMA400_FIFO_CONFIG_0_ADDR, data_array, 3, dev);
+		if (rslt == BMA400_OK) {
+			/* Get the data of FIFO_CONFIG0 register */
+			fifo_conf->conf_regs = data_array[0];
+			/* Get the MSB of FIFO water-mark  */
+			data_array[2] = BMA400_GET_BITS_POS_0(data_array[2], BMA400_FIFO_BYTES_CNT);
+			/* FIFO water-mark value is stored */
+			fifo_conf->fifo_watermark = ((uint16_t)data_array[2] << 8) | ((uint16_t)data_array[1]);
+		}
+	}
+	return rslt;
+}
+/*!
+ * @brief This API is used to set the FIFO configurations
+ */
+static int8_t set_fifo_conf(const struct bma400_fifo_conf *fifo_conf, const struct bma400_dev *dev)
+{
+	int8_t rslt;
+	uint8_t data_array[3];
+	uint8_t sens_data[3];
+
+	/* Check for null pointer in the device structure */
+	rslt = null_ptr_check(dev);
+	/* Proceed if null check is fine */
+	if (rslt == BMA400_OK) {
+		/* Get the FIFO configurations and water-mark
+		 * values from the sensor */
+		rslt = bma400_get_regs(BMA400_FIFO_CONFIG_0_ADDR, sens_data, 3, dev);
+		if (rslt == BMA400_OK) {
+			/* FIFO configurations */
+			data_array[0] = fifo_conf->conf_regs;
+			if (fifo_conf->conf_status == BMA400_DISABLE) {
+				/* Disable the selected interrupt status */
+				data_array[0] = sens_data[0] & (~data_array[0]);
+			}
+			/* FIFO water-mark values */
+			data_array[1] = BMA400_GET_LSB(fifo_conf->fifo_watermark);
+			data_array[2] = BMA400_GET_MSB(fifo_conf->fifo_watermark);
+			data_array[2] = BMA400_GET_BITS_POS_0(data_array[2], BMA400_FIFO_BYTES_CNT);
+			if ((data_array[1] == sens_data[1]) && (data_array[2] == sens_data[2])) {
+				/* Set the FIFO configurations in the
+				 * sensor excluding the watermark value */
+				rslt = bma400_set_regs(BMA400_FIFO_CONFIG_0_ADDR, data_array, 1, dev);
+			} else {
+				/* Set the FIFO configurations in the sensor*/
+				rslt = bma400_set_regs(BMA400_FIFO_CONFIG_0_ADDR, data_array, 3, dev);
+			}
+		}
+	}
+	return rslt;
+}
+/*!
+ *  @brief This API is used to get the number of bytes filled in FIFO
+ */
+static int8_t get_fifo_length(uint16_t *fifo_byte_cnt, const struct bma400_dev *dev)
+{
+	int8_t rslt;
+	uint8_t data_array[2] = { 0 };
+
+	rslt = bma400_get_regs(BMA400_FIFO_LENGTH_ADDR, data_array, 2, dev);
+	if (rslt == BMA400_OK) {
+		data_array[1] = BMA400_GET_BITS_POS_0(data_array[1], BMA400_FIFO_BYTES_CNT);
+		/* Available data in FIFO is stored in fifo_byte_cnt*/
+		*fifo_byte_cnt = ((uint16_t)data_array[1] << 8) | ((uint16_t)data_array[0]);
+	}
+	return rslt;
+}
+/*!
+ *  @brief This API is used to read the FIFO of BMA400
+ */
+static int8_t read_fifo(struct bma400_fifo_data *fifo, const struct bma400_dev *dev)
+{
+	int8_t rslt;
+	uint8_t reg_data;
+	uint8_t fifo_addr = BMA400_FIFO_DATA_ADDR;
+
+	if (dev->intf == BMA400_SPI_INTF) {
+		/* SPI mask is added */
+		fifo_addr = fifo_addr | BMA400_SPI_RD_MASK;
+	}
+	/* Read the FIFO enable bit */
+	rslt = bma400_get_regs(BMA400_FIFO_READ_EN_ADDR, &reg_data, 1, dev);
+	if (rslt == BMA400_OK) {
+		/* FIFO read disable bit */
+		if (reg_data == 0) {
+			/* Read FIFO Buffer since FIFO read is enabled */
+			rslt = dev->read(dev->intf_ptr, dev->dev_id, fifo_addr, fifo->data, fifo->length);
+			if (rslt != 0) {
+				rslt = BMA400_E_COM_FAIL;
+			}
+		} else {
+			/* Enable FIFO reading */
+			reg_data = 0;
+			rslt = bma400_set_regs(BMA400_FIFO_READ_EN_ADDR, &reg_data, 1, dev);
+			if (rslt == BMA400_OK) {
+				/* Delay to enable the FIFO */
+				dev->delay_ms(1);
+				/* Read FIFO Buffer since FIFO read is enabled*/
+				rslt = dev->read(dev->intf_ptr, dev->dev_id, fifo_addr, fifo->data, fifo->length);
+				if (rslt == BMA400_OK) {
+					/* Disable FIFO reading */
+					reg_data = 1;
+					rslt = bma400_set_regs(BMA400_FIFO_READ_EN_ADDR, &reg_data, 1, dev);
+				}
+			}
+		}
+	}
+	return rslt;
+}
+/*!
+ *  @brief This API is used to unpack the accelerometer frames from the FIFO
+ */
+static void unpack_accel_frame(struct bma400_fifo_data *fifo,
+			       struct bma400_sensor_data *accel_data,
+			       uint16_t *frame_count,
+			       const struct bma400_dev *dev)
+{
+	/* Frame header information is stored */
+	uint8_t frame_header = 0;
+	/* Accel data width is stored */
+	uint8_t accel_width;
+	/* Data index of the parsed byte from FIFO */
+	uint16_t data_index;
+	/* Number of accel frames parsed */
+	uint16_t accel_index = 0;
+	/* Variable to check frame availability */
+	uint8_t frame_available = BMA400_ENABLE;
+
+	/* Check if this is the first iteration of data unpacking
+	 * if yes, then consider dummy byte on SPI */
+	if (fifo->accel_byte_start_idx == 0) {
+		/* Dummy byte included */
+		fifo->accel_byte_start_idx = dev->dummy_byte;
+	}
+	for (data_index = fifo->accel_byte_start_idx; data_index < fifo->length;) {
+		/*Header byte is stored in the variable frame_header*/
+		frame_header = fifo->data[data_index];
+		/* Store the Accel 8 bit or 12 bit mode */
+		accel_width = BMA400_GET_BITS(frame_header, BMA400_FIFO_8_BIT_EN);
+		/* Exclude the 8/12 bit mode data from frame header */
+		frame_header = frame_header & BMA400_AWIDTH_MASK;
+		/*Index is moved to next byte where the data is starting*/
+		data_index++;
+		switch (frame_header) {
+		case BMA400_FIFO_XYZ_ENABLE:
+			check_frame_available(fifo, &frame_available, accel_width, BMA400_FIFO_XYZ_ENABLE, &data_index);
+			if (frame_available != BMA400_DISABLE) {
+				/* Extract and store accel xyz data */
+				unpack_accel(fifo, &accel_data[accel_index], &data_index, accel_width, frame_header);
+				accel_index++;
+			}
+			break;
+		case BMA400_FIFO_X_ENABLE:
+			check_frame_available(fifo, &frame_available, accel_width, BMA400_FIFO_X_ENABLE, &data_index);
+			if (frame_available != BMA400_DISABLE) {
+				/* Extract and store accel x data */
+				unpack_accel(fifo, &accel_data[accel_index], &data_index, accel_width, frame_header);
+				accel_index++;
+			}
+			break;
+		case BMA400_FIFO_Y_ENABLE:
+			check_frame_available(fifo, &frame_available, accel_width, BMA400_FIFO_Y_ENABLE, &data_index);
+			if (frame_available != BMA400_DISABLE) {
+				/* Extract and store accel y data */
+				unpack_accel(fifo, &accel_data[accel_index], &data_index, accel_width, frame_header);
+				accel_index++;
+			}
+			break;
+		case BMA400_FIFO_Z_ENABLE:
+			check_frame_available(fifo, &frame_available, accel_width, BMA400_FIFO_Z_ENABLE, &data_index);
+			if (frame_available != BMA400_DISABLE) {
+				/* Extract and store accel z data */
+				unpack_accel(fifo, &accel_data[accel_index], &data_index, accel_width, frame_header);
+				accel_index++;
+			}
+			break;
+		case BMA400_FIFO_XY_ENABLE:
+			check_frame_available(fifo, &frame_available, accel_width, BMA400_FIFO_XY_ENABLE, &data_index);
+			if (frame_available != BMA400_DISABLE) {
+				/* Extract and store accel xy data */
+				unpack_accel(fifo, &accel_data[accel_index], &data_index, accel_width, frame_header);
+				accel_index++;
+			}
+			break;
+		case BMA400_FIFO_YZ_ENABLE:
+			check_frame_available(fifo, &frame_available, accel_width, BMA400_FIFO_YZ_ENABLE, &data_index);
+			if (frame_available != BMA400_DISABLE) {
+				/* Extract and store accel yz data */
+				unpack_accel(fifo, &accel_data[accel_index], &data_index, accel_width, frame_header);
+				accel_index++;
+			}
+			break;
+		case BMA400_FIFO_XZ_ENABLE:
+			check_frame_available(fifo, &frame_available, accel_width, BMA400_FIFO_YZ_ENABLE, &data_index);
+			if (frame_available != BMA400_DISABLE) {
+				/* Extract and store accel xz data */
+				unpack_accel(fifo, &accel_data[accel_index], &data_index, accel_width, frame_header);
+				accel_index++;
+			}
+			break;
+		case BMA400_FIFO_SENSOR_TIME:
+			check_frame_available(fifo, &frame_available, accel_width, BMA400_FIFO_SENSOR_TIME, &data_index);
+			if (frame_available != BMA400_DISABLE) {
+				/* Unpack and store the sensor time data */
+				unpack_sensortime_frame(fifo, &data_index);
+			}
+			break;
+		case BMA400_FIFO_EMPTY_FRAME:
+			/* Update the data index as complete */
+			data_index = fifo->length;
+			break;
+		case BMA400_FIFO_CONTROL_FRAME:
+			check_frame_available(fifo, &frame_available, accel_width, BMA400_FIFO_CONTROL_FRAME,
+					      &data_index);
+			if (frame_available != BMA400_DISABLE) {
+				/* Store the configuration change data from FIFO */
+				fifo->conf_change = fifo->data[data_index++];
+			}
+			break;
+		default:
+			/* Update the data index as complete */
+			data_index = fifo->length;
+			break;
+		}
+		if (*frame_count == accel_index) {
+			/* Frames read completely*/
+			break;
+		}
+	}
+	/* Update the data index */
+	fifo->accel_byte_start_idx = data_index;
+	/* Update number of accel frame index */
+	*frame_count = accel_index;
+}
+/*!
+ *  @brief This API is used to check for a frame availability in FIFO
+ */
+static void check_frame_available(struct bma400_fifo_data *fifo,
+				  uint8_t *frame_available,
+				  uint8_t accel_width,
+				  uint8_t data_en,
+				  uint16_t *data_index)
+{
+	switch (data_en) {
+	case BMA400_FIFO_XYZ_ENABLE:
+		/* Handling case of 12 bit/ 8 bit data available in FIFO */
+		if (accel_width == BMA400_12_BIT_FIFO_DATA) {
+			if ((*data_index + 6) > fifo->length) {
+				/* Partial frame available */
+				*data_index = fifo->length;
+				*frame_available = BMA400_DISABLE;
+			}
+		} else {
+			if ((*data_index + 3) > fifo->length) {
+				/* Partial frame available */
+				*data_index = fifo->length;
+				*frame_available = BMA400_DISABLE;
+			}
+		}
+		break;
+	case BMA400_FIFO_X_ENABLE:
+	case BMA400_FIFO_Y_ENABLE:
+	case BMA400_FIFO_Z_ENABLE:
+		/* Handling case of 12 bit/ 8 bit data available in FIFO */
+		if (accel_width == BMA400_12_BIT_FIFO_DATA) {
+			if ((*data_index + 2) > fifo->length) {
+				/* Partial frame available */
+				*data_index = fifo->length;
+				*frame_available = BMA400_DISABLE;
+			}
+		} else {
+			if ((*data_index + 1) > fifo->length) {
+				/* Partial frame available */
+				*data_index = fifo->length;
+				*frame_available = BMA400_DISABLE;
+			}
+		}
+		break;
+	case BMA400_FIFO_XY_ENABLE:
+	case BMA400_FIFO_YZ_ENABLE:
+	case BMA400_FIFO_XZ_ENABLE:
+		/* Handling case of 12 bit/ 8 bit data available in FIFO */
+		if (accel_width == BMA400_12_BIT_FIFO_DATA) {
+			if ((*data_index + 4) > fifo->length) {
+				/* Partial frame available */
+				*data_index = fifo->length;
+				*frame_available = BMA400_DISABLE;
+			}
+		} else {
+			if ((*data_index + 2) > fifo->length) {
+				/* Partial frame available */
+				*data_index = fifo->length;
+				*frame_available = BMA400_DISABLE;
+			}
+		}
+		break;
+	case BMA400_FIFO_SENSOR_TIME:
+		if ((*data_index + 3) > fifo->length) {
+			/* Partial frame available */
+			*data_index = fifo->length;
+			*frame_available = BMA400_DISABLE;
+		}
+		break;
+	case BMA400_FIFO_CONTROL_FRAME:
+		if ((*data_index + 1) > fifo->length) {
+			/* Partial frame available */
+			*data_index = fifo->length;
+			*frame_available = BMA400_DISABLE;
+		}
+		break;
+	default:
+		break;
+	}
+}
+/*!
+ *  @brief This API is used to unpack the accelerometer xyz data from the FIFO
+ *  and store it in the user defined buffer
+ */
+static void unpack_accel(struct bma400_fifo_data *fifo,
+			 struct bma400_sensor_data *accel_data,
+			 uint16_t *data_index,
+			 uint8_t accel_width,
+			 uint8_t frame_header)
+{
+	uint8_t data_lsb;
+	uint8_t data_msb;
+
+	/* Header information of enabled axes */
+	frame_header = frame_header & BMA400_FIFO_DATA_EN_MASK;
+	if (accel_width == BMA400_12_BIT_FIFO_DATA) {
+		if (frame_header & BMA400_FIFO_X_ENABLE) {
+			/* Accel x data */
+			data_lsb = fifo->data[(*data_index)++];
+			data_msb = fifo->data[(*data_index)++];
+			accel_data->x = (int16_t)(((uint16_t)(data_msb << 4)) | data_lsb);
+			if (accel_data->x > 2047) {
+				/* Computing accel x data negative value */
+				accel_data->x = accel_data->x - 4096;
+			}
+		} else {
+			/* Accel x not available */
+			accel_data->x = 0;
+		}
+		if (frame_header & BMA400_FIFO_Y_ENABLE) {
+			/* Accel y data */
+			data_lsb = fifo->data[(*data_index)++];
+			data_msb = fifo->data[(*data_index)++];
+			accel_data->y = (int16_t)(((uint16_t)(data_msb << 4)) | data_lsb);
+			if (accel_data->y > 2047) {
+				/* Computing accel y data negative value */
+				accel_data->y = accel_data->y - 4096;
+			}
+		} else {
+			/* Accel y not available */
+			accel_data->y = 0;
+		}
+		if (frame_header & BMA400_FIFO_Z_ENABLE) {
+			/* Accel z data */
+			data_lsb = fifo->data[(*data_index)++];
+			data_msb = fifo->data[(*data_index)++];
+			accel_data->z = (int16_t)(((uint16_t)(data_msb << 4)) | data_lsb);
+			if (accel_data->z > 2047) {
+				/* Computing accel z data negative value */
+				accel_data->z = accel_data->z - 4096;
+			}
+		} else {
+			/* Accel z not available */
+			accel_data->z = 0;
+		}
+	} else {
+		if (frame_header & BMA400_FIFO_X_ENABLE) {
+			/* Accel x data */
+			data_msb = fifo->data[(*data_index)++];
+			accel_data->x = (int16_t)((uint16_t)(data_msb << 4));
+			if (accel_data->x > 2047) {
+				/* Computing accel x data negative value */
+				accel_data->x = accel_data->x - 4096;
+			}
+		} else {
+			/* Accel x not available */
+			accel_data->x = 0;
+		}
+		if (frame_header & BMA400_FIFO_Y_ENABLE) {
+			/* Accel y data */
+			data_msb = fifo->data[(*data_index)++];
+			accel_data->y = (int16_t)((uint16_t)(data_msb << 4));
+			if (accel_data->y > 2047) {
+				/* Computing accel y data negative value */
+				accel_data->y = accel_data->y - 4096;
+			}
+		} else {
+			/* Accel y not available */
+			accel_data->y = 0;
+		}
+		if (frame_header & BMA400_FIFO_Z_ENABLE) {
+			/* Accel z data */
+			data_msb = fifo->data[(*data_index)++];
+			accel_data->z = (int16_t)((uint16_t)(data_msb << 4));
+			if (accel_data->z > 2047) {
+				/* Computing accel z data negative value */
+				accel_data->z = accel_data->z - 4096;
+			}
+		} else {
+			/* Accel z not available */
+			accel_data->z = 0;
+		}
+	}
+}
+/*!
+ *  @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(struct bma400_fifo_data *fifo, uint16_t *data_index)
+{
+	uint32_t time_msb;
+	uint16_t time_lsb;
+	uint8_t time_xlsb;
+
+	time_msb = fifo->data[(*data_index) + 2] << 16;
+	time_lsb = fifo->data[(*data_index) + 1] << 8;
+	time_xlsb = fifo->data[(*data_index)];
+	/* Sensor time */
+	fifo->fifo_sensor_time = (uint32_t)(time_msb | time_lsb | time_xlsb);
+	*data_index = (*data_index) + 3;
+}
+/*!
+ * @brief This API validates the self test results
+ */
+static int8_t validate_accel_self_test(const struct bma400_sensor_data *accel_pos,
+				       const struct bma400_sensor_data *accel_neg)
+{
+	int8_t rslt;
+
+	/* Validate the results of self test
+	 * Self test value of x,y axes should be 800mg
+	 * and z axes should be 400 mg */
+	if (((accel_pos->x - accel_neg->x) > 205) && ((accel_pos->y - accel_neg->y) > 205) &&
+	    ((accel_pos->z - accel_neg->z) > 103)) {
+		/* Self test pass condition */
+		rslt = BMA400_OK;
+	} else {
+		/* Self test failed */
+		rslt = BMA400_W_SELF_TEST_FAIL;
+	}
+	return rslt;
+}
+/*!
+ * @brief This API performs self test with positive excitation
+ */
+static int8_t positive_excited_accel(struct bma400_sensor_data *accel_pos, const struct bma400_dev *dev)
+{
+	int8_t rslt;
+	uint8_t reg_data = BMA400_ENABLE_POSITIVE_SELF_TEST;
+
+	/* Enable positive excitation for all 3 axes */
+	rslt = bma400_set_regs(BMA400_SELF_TEST_ADDR, &reg_data, 1, dev);
+	if (rslt == BMA400_OK) {
+		/* Read accel data after 50ms delay */
+		dev->delay_ms(BMA400_SELF_TEST_DATA_READ_MS);
+		rslt = bma400_get_accel_data(BMA400_DATA_ONLY, accel_pos, dev);
+	}
+	return rslt;
+}
+/*!
+ * @brief This API performs self test with negative excitation
+ */
+static int8_t negative_excited_accel(struct bma400_sensor_data *accel_neg, const struct bma400_dev *dev)
+{
+	int8_t rslt;
+	uint8_t reg_data = BMA400_ENABLE_NEGATIVE_SELF_TEST;
+
+	/* Enable negative excitation for all 3 axes */
+	rslt = bma400_set_regs(BMA400_SELF_TEST_ADDR, &reg_data, 1, dev);
+	if (rslt == BMA400_OK) {
+		/* Read accel data after 50ms delay */
+		dev->delay_ms(BMA400_SELF_TEST_DATA_READ_MS);
+		rslt = bma400_get_accel_data(BMA400_DATA_ONLY, accel_neg, dev);
+		if (rslt == BMA400_OK) {
+			/* Disable self test */
+			reg_data = BMA400_DISABLE_SELF_TEST;
+			rslt = bma400_set_regs(BMA400_SELF_TEST_ADDR, &reg_data, 1, dev);
+		}
+	}
+	return rslt;
+}
+/*!
+ * @brief This API performs the pre-requisites needed to perform the self test
+ */
+static int8_t enable_self_test(const struct bma400_dev *dev)
+{
+	int8_t rslt;
+	/* Accelerometer setting structure */
+	struct bma400_sensor_conf accel_setting;
+
+	/* Select the type of configuration to be modified */
+	accel_setting.type = BMA400_ACCEL;
+	/* Get the accel configurations which are set in the sensor */
+	rslt = bma400_get_sensor_conf(&accel_setting, 1, dev);
+	if (rslt == BMA400_OK) {
+		/* Modify to the desired configurations */
+		accel_setting.param.accel.odr = BMA400_ODR_100HZ;
+		accel_setting.param.accel.range = BMA400_8G_RANGE;
+		accel_setting.param.accel.osr = BMA400_ACCEL_OSR_SETTING_3;
+		accel_setting.param.accel.data_src = BMA400_DATA_SRC_ACCEL_FILT_1;
+		/* Set the desired configurations in the sensor */
+		rslt = bma400_set_sensor_conf(&accel_setting, 1, dev);
+		if (rslt == BMA400_OK) {
+			/* self test enabling delay */
+			dev->delay_ms(BMA400_SELF_TEST_DELAY_MS);
+		}
+
+		if (rslt == BMA400_OK) {
+			rslt = bma400_set_power_mode(BMA400_NORMAL_MODE, dev);
+		}
+	}
+	return rslt;
+}
diff --git a/lib/bosch/BMA400-API/bma400.h b/lib/bosch/BMA400-API/bma400.h
new file mode 100644
index 0000000000000000000000000000000000000000..821969b504a6485492f04830bc53abb0e9ddfb57
--- /dev/null
+++ b/lib/bosch/BMA400-API/bma400.h
@@ -0,0 +1,454 @@
+/**
+ * Copyright (C) 2017 - 2018 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       bma400.h
+ * @date       25 Sep 2018
+ * @version    1.5.0
+ * @brief
+ *
+ */
+/*! @file bma400.h */
+/*!
+ * @defgroup BMA400 SENSOR API
+ * @{
+ */
+
+#ifndef BMA400_H__
+#define BMA400_H__
+/*! CPP guard */
+#ifdef __cplusplus
+extern "C" {
+#endif
+/*********************************************************************/
+/* header files */
+
+#include "bma400_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 bma400_dev
+ *
+ * @return Result of API execution status
+ * @retval zero -> Success / +ve value -> Warning / -ve value -> Error
+ */
+int8_t bma400_init(struct bma400_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 bma400_dev.
+ *
+ * @return Result of API execution status
+ * @retval zero -> Success / +ve value -> Warning / -ve value -> Error
+ */
+int8_t bma400_set_regs(uint8_t reg_addr, uint8_t *reg_data, uint8_t len, const struct bma400_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 bma400_dev.
+ *
+ * @note For most of the registers auto address increment applies, with the
+ * exception of a few special registers, which trap the address. For e.g.,
+ * Register address - 0x14(BMA400_FIFO_DATA_ADDR)
+ *
+ * @return Result of API execution status
+ * @retval zero -> Success / +ve value -> Warning / -ve value -> Error
+ */
+int8_t bma400_get_regs(uint8_t reg_addr, uint8_t *reg_data, uint8_t len, const struct bma400_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 bma400_dev.
+ *
+ * @return Result of API execution status
+ * @retval zero -> Success / +ve value -> Warning / -ve value -> Error
+ */
+int8_t bma400_soft_reset(const struct bma400_dev *dev);
+
+/*!
+ * @brief This API is used to set the power mode of the sensor.
+ *
+ * @param[in] power_mode  : Macro to select power mode of the sensor.
+ * @param[in] dev         : Structure instance of bma400_dev.
+ *
+ * Possible value for power_mode :
+ *   - BMA400_NORMAL_MODE
+ *   - BMA400_SLEEP_MODE
+ *   - BMA400_LOW_POWER_MODE
+ *
+ * @return Result of API execution status
+ * @retval zero -> Success / +ve value -> Warning / -ve value -> Error
+ */
+int8_t bma400_set_power_mode(uint8_t power_mode, const struct bma400_dev *dev);
+
+/*!
+ * @brief This API is used to get the power mode of the sensor
+ *
+ * @param[out] power_mode  : power mode of the sensor.
+ * @param[in] dev          : Structure instance of bma400_dev.
+ *
+ * * Possible value for power_mode :
+ *   - BMA400_NORMAL_MODE
+ *   - BMA400_SLEEP_MODE
+ *   - BMA400_LOW_POWER_MODE
+ *
+ * @return Result of API execution status
+ * @retval zero -> Success / +ve value -> Warning / -ve value -> Error
+ */
+int8_t bma400_get_power_mode(uint8_t *power_mode, const struct bma400_dev *dev);
+
+/*!
+ * @brief This API is used to get the accel data along with the sensor-time
+ *
+ * @param[in] data_sel     : Variable to select sensor data only
+ *                           or data along with sensortime
+ * @param[in,out] accel    : Structure instance to store data
+ * @param[in] dev          : Structure instance of bma400_dev
+ *
+ * Assignable macros for "data_sel" :
+ *   - BMA400_DATA_ONLY
+ *   - BMA400_DATA_SENSOR_TIME
+ *
+ * @note : The Accel data value are in LSB based on the range selected
+ *
+ * @return Result of API execution status
+ * @retval zero -> Success / +ve value -> Warning / -ve value -> Error
+ */
+int8_t bma400_get_accel_data(uint8_t data_sel, struct bma400_sensor_data *accel, const struct bma400_dev *dev);
+
+/*!
+ * @brief This API is used to set the sensor settings like sensor
+ * configurations and interrupt configurations like
+ *    - Accelerometer configurations (Like ODR,OSR,range...)
+ *    - Tap configurations
+ *    - Activity change configurations
+ *    - Gen1/Gen2 configurations
+ *    - Orient change configurations
+ *    - Step counter configurations
+ *
+ * @param[in] conf         : Structure instance of the configuration structure
+ * @param[in] n_sett       : Number of settings to be set
+ * @param[in] dev          : Structure instance of bma400_dev
+ *
+ * @note : Fill in the value of the required configurations in the conf structure
+ * (Examples are mentioned in the readme.md) before calling this API
+ *
+ * @return Result of API execution status
+ * @retval zero -> Success / +ve value -> Warning / -ve value -> Error
+ */
+int8_t bma400_set_sensor_conf(const struct bma400_sensor_conf *conf, uint16_t n_sett, const struct bma400_dev *dev);
+
+/*!
+ * @brief This API is used to get the sensor settings like sensor
+ * configurations and interrupt configurations and store
+ * them in the corresponding structure instance
+ *
+ * @param[in] conf         : Structure instance of the configuration structure
+ * @param[in] n_sett       : Number of settings to be obtained
+ * @param[in] dev          : Structure instance of bma400_dev.
+ *
+ * @note : Call the API and the settings structure will be updated with the
+ * sensor settings
+ *
+ * @return Result of API execution status
+ * @retval zero -> Success / +ve value -> Warning / -ve value -> Error
+ */
+int8_t bma400_get_sensor_conf(struct bma400_sensor_conf *conf, uint16_t n_sett, const struct bma400_dev *dev);
+
+/*!
+ * @brief This API is used to set the device specific settings like
+ *  - BMA400_AUTOWAKEUP_TIMEOUT
+ *  - BMA400_AUTOWAKEUP_INT
+ *  - BMA400_AUTO_LOW_POWER
+ *  - BMA400_INT_PIN_CONF
+ *  - BMA400_INT_OVERRUN_CONF
+ *  - BMA400_FIFO_CONF
+ *
+ * @param[in] conf         : Structure instance of the configuration structure.
+ * @param[in] n_sett       : Number of settings to be set
+ * @param[in] dev          : Structure instance of bma400_dev.
+ *
+ * @note : Fill in the value of the required configurations in the conf structure
+ * (Examples are mentioned in the readme.md) before calling this API
+ *
+ * @return Result of API execution status
+ * @retval zero -> Success / +ve value -> Warning / -ve value -> Error
+ */
+int8_t bma400_set_device_conf(const struct bma400_device_conf *conf, uint8_t n_sett, const struct bma400_dev *dev);
+
+/*!
+ * @brief This API is used to get the device specific settings and store
+ * them in the corresponding structure instance
+ *
+ * @param[in] conf         : Structure instance of the configuration structure
+ * @param[in] n_sett       : Number of settings to be obtained
+ * @param[in] dev          : Structure instance of bma400_dev.
+ *
+ * @note : Call the API and the settings structure will be updated with the
+ * sensor settings
+ *
+ * @return Result of API execution status
+ * @retval zero -> Success / +ve value -> Warning / -ve value -> Error
+ */
+int8_t bma400_get_device_conf(struct bma400_device_conf *conf, uint8_t n_sett, const struct bma400_dev *dev);
+
+/*!
+ * @brief This API is used to get the status of all the interrupts
+ * whether they are asserted or not
+ *
+ * @param[in] int_status   : Interrupt status of sensor
+ * @param[in] dev          : Structure instance of bma400_dev.
+ *
+ * @note : Interrupt status of the sensor determines which all
+ * interrupts are asserted at any instant of time
+ *
+ * Interrupt status macros :
+ *  - BMA400_WAKEUP_INT_ASSERTED
+ *  - BMA400_ORIENT_CH_INT_ASSERTED
+ *  - BMA400_GEN1_INT_ASSERTED
+ *  - BMA400_GEN2_INT_ASSERTED
+ *  - BMA400_FIFO_FULL_INT_ASSERTED
+ *  - BMA400_FIFO_WM_INT_ASSERTED
+ *  - BMA400_DRDY_INT_ASSERTED
+ *  - BMA400_INT_OVERRUN_ASSERTED
+ *  - BMA400_STEP_INT_ASSERTED
+ *  - BMA400_S_TAP_INT_ASSERTED
+ *  - BMA400_D_TAP_INT_ASSERTED
+ *  - BMA400_ACT_CH_X_ASSERTED
+ *  - BMA400_ACT_CH_Y_ASSERTED
+ *  - BMA400_ACT_CH_Z_ASSERTED
+ *
+ * @note : Call the API and then use the above macros to
+ * check whether the interrupt is asserted or not
+ *
+ * if (int_status & BMA400_FIFO_FULL_INT_ASSERTED) {
+ *     printf("\n FIFO FULL INT ASSERTED");
+ * }
+ *
+ * @return Result of API execution status
+ * @retval zero -> Success / +ve value -> Warning / -ve value -> Error
+ */
+int8_t bma400_get_interrupt_status(uint16_t *int_status, const struct bma400_dev *dev);
+
+/*!
+ * @brief This API is used to get the enable/disable
+ * status of the various interrupts
+ *
+ * @param[in] int_select   : Structure to select specific interrupts
+ * @param[in] n_sett       : Number of interrupt settings enabled / disabled
+ * @param[in] dev          : Structure instance of bma400_dev.
+ *
+ * @note : Select the needed interrupt type for which the status of it whether
+ * it is enabled/disabled is to be known in the int_select->int_sel, and the
+ * output is stored in int_select->conf either as BMA400_ENABLE/BMA400_DISABLE
+ *
+ * @return Result of API execution status
+ * @retval zero -> Success / +ve value -> Warning / -ve value -> Error
+ */
+int8_t bma400_get_interrupts_enabled(struct bma400_int_enable *int_select, uint8_t n_sett, const struct bma400_dev *dev);
+
+/*!
+ * @brief This API is used to enable the various interrupts
+ *
+ * @param[in] int_select   : Structure to enable specific interrupts
+ * @param[in] n_sett       : Number of interrupt settings enabled / disabled
+ * @param[in] dev          : Structure instance of bma400_dev.
+ *
+ * @note : Multiple interrupt can be enabled/disabled by
+ *    struct interrupt_enable int_select[2];
+ *
+ *    int_select[0].int_sel = BMA400_FIFO_FULL_INT_EN;
+ *    int_select[0].conf = BMA400_ENABLE;
+ *
+ *    int_select[1].int_sel = BMA400_FIFO_WM_INT_EN;
+ *    int_select[1].conf = BMA400_ENABLE;
+ *
+ *    rslt = bma400_enable_interrupt(&int_select, 2, dev);
+ *
+ * @return Result of API execution status
+ * @retval zero -> Success / +ve value -> Warning / -ve value -> Error
+ */
+int8_t bma400_enable_interrupt(const struct bma400_int_enable *int_select, uint8_t n_sett, const struct bma400_dev *dev);
+
+/*!
+ * @brief This API is used to get the step counter output in form
+ * of number of steps in the step_count value
+ *
+ * @param[out] step_count      : Number of step counts
+ * @param[out] activity_data   : Activity data WALK/STILL/RUN
+ * @param[in] dev              : Structure instance of bma400_dev.
+ *
+ *  activity_data   |  Status
+ * -----------------|------------------
+ *  0x00            | BMA400_STILL_ACT
+ *  0x01            | BMA400_WALK_ACT
+ *  0x02            | BMA400_RUN_ACT
+ *
+ * @return Result of API execution status
+ * @retval zero -> Success / +ve value -> Warning / -ve value -> Error
+ */
+int8_t bma400_get_steps_counted(uint32_t *step_count, uint8_t *activity_data, const struct bma400_dev *dev);
+
+/*!
+ * @brief This API is used to get the temperature data output
+ *
+ * @note Temperature data output must be divided by a factor of 10
+ * Consider temperature_data = 195 ,
+ * Then the actual temperature is 19.5 degree Celsius
+ *
+ * @param[in,out] temperature_data   : Temperature data
+ * @param[in] dev                    : Structure instance of bma400_dev.
+ *
+ * @return Result of API execution status
+ * @retval zero -> Success / +ve value -> Warning / -ve value -> Error
+ */
+int8_t bma400_get_temperature_data(int16_t *temperature_data, const struct bma400_dev *dev);
+
+/*!
+ *  @brief This API writes fifo_flush command to command register.
+ *  This action clears all data in the FIFO
+ *
+ *  @param[in] dev           : Structure instance of bma400_dev.
+ *
+ * @return Result of API execution status
+ * @retval zero -> Success / +ve value -> Warning / -ve value -> Error
+ */
+int8_t bma400_set_fifo_flush(const struct bma400_dev *dev);
+
+/*!
+ * @brief This API reads the FIFO data from the sensor
+ *
+ * @note User has to allocate the FIFO buffer along with
+ * corresponding fifo read 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
+ * fifo->length , It will be updated by the number of bytes actually
+ * read from FIFO after calling this API
+ *
+ * @param[in,out] fifo      : Pointer to the fifo structure.
+ *
+ * @param[in,out] dev       : Structure instance of bma400_dev.
+ *
+ * @return Result of API execution status
+ * @retval zero -> Success / +ve value -> Warning / -ve value -> Error
+ */
+int8_t bma400_get_fifo_data(struct bma400_fifo_data *fifo, const struct bma400_dev *dev);
+
+/*!
+ * @brief This API parses and extracts the accelerometer frames, FIFO time
+ * and control frames from FIFO data read by the "bma400_get_fifo_data" API
+ * and stores it in the "accel_data" structure instance.
+ *
+ * @note The bma400_extract_accel API should be called only after
+ * reading the FIFO data by calling the bma400_get_fifo_data() API
+ * Please refer the readme.md for usage.
+ *
+ * @param[in,out] fifo        : Pointer to the fifo structure.
+ *
+ * @param[out] accel_data     : Structure instance of bma400_sensor_data where
+ *                              the accelerometer data from FIFO is extracted
+ *                              and stored after calling this API
+ *
+ * @param[in,out] frame_count : Number of valid accelerometer frames requested
+ *                              by user is given as input and it is updated by
+ *                              the actual frames parsed from the FIFO
+ *
+ * @param[in] dev             : Structure instance of bma400_dev.
+ *
+ * @return Result of API execution status
+ * @retval zero -> Success / +ve value -> Warning / -ve value -> Error
+ */
+int8_t bma400_extract_accel(struct bma400_fifo_data *fifo,
+			    struct bma400_sensor_data *accel_data,
+			    uint16_t *frame_count,
+			    const struct bma400_dev *dev);
+
+/*!
+ * @brief This is used to perform self test of accelerometer in BMA400
+ *
+ * @param[in] dev    : Structure instance of bma400_dev.
+ *
+ * @note The return value of this API gives us the result of self test.
+ *
+ * @note Performing self test does soft reset of the sensor, User can
+ * set the desired settings after performing the self test.
+ *
+ * @return Result of API execution status
+ * @retval zero -> Success  / -ve value -> Error / +ve value -> Self-test fail
+ *
+ *   Return value                  |   Result of self test
+ * --------------------------------|---------------------------------
+ *  BMA400_OK                      |  Self test success
+ *  BMA400_W_SELF_TEST_FAIL        |  self test fail
+ */
+int8_t bma400_perform_self_test(const struct bma400_dev *dev);
+
+/*!
+ * @brief This API is used to set the step counter's configuration
+ * parameters from the registers 0x59 to 0x71
+ */
+int8_t bma400_set_step_counter_param(uint8_t *sccr_conf, const struct bma400_dev *dev);
+
+#ifdef __cplusplus
+}
+#endif  /* End of CPP guard */
+
+#endif  /* BMA400_H__ */
+/** @}*/
diff --git a/lib/bosch/BMA400-API/bma400_defs.h b/lib/bosch/BMA400-API/bma400_defs.h
new file mode 100644
index 0000000000000000000000000000000000000000..85216f979317f7dd5602e6f70966e1ec690a6723
--- /dev/null
+++ b/lib/bosch/BMA400-API/bma400_defs.h
@@ -0,0 +1,1191 @@
+/**
+ * Copyright (C) 2017 - 2018 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	bma400_defs.h
+ * @date	25 Sep 2018
+ * @version	1.5.0
+ * @brief
+ *
+ */
+/*! \file bma400_defs.h */
+/*!
+ * @defgroup BMA400 SENSOR API
+ * @brief
+ * @{
+ */
+#ifndef BMA400_DEFS_H_
+#define BMA400_DEFS_H_
+/*********************************************************************/
+/**\ header files */
+#ifdef __KERNEL__
+#include <linux/types.h>
+#include <linux/kernel.h>
+#else
+#include <stdint.h>
+#include <stddef.h>
+#endif
+/*********************************************************************/
+/** \name		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
+
+#ifndef TRUE
+#define TRUE     UINT8_C(1)
+#endif
+
+#ifndef FALSE
+#define FALSE    UINT8_C(0)
+#endif
+/********************************************************/
+/**\name Macro definitions */
+/**\name API success code */
+#define BMA400_OK       INT8_C(0)
+/**\name API error codes */
+#define BMA400_E_NULL_PTR          INT8_C(-1)
+#define BMA400_E_COM_FAIL          INT8_C(-2)
+#define BMA400_E_DEV_NOT_FOUND     INT8_C(-3)
+#define BMA400_E_INVALID_CONFIG    INT8_C(-4)
+/**\name API warning codes */
+#define BMA400_W_SELF_TEST_FAIL    INT8_C(1)
+/**\name CHIP ID VALUE */
+#define BMA400_CHIP_ID     UINT8_C(0x90)
+/********************************************************/
+/**\name	USER CONFIGURATION MACROS               */
+/**\name BMA400 I2C address macros */
+#define BMA400_I2C_ADDRESS_SDO_LOW     UINT8_C(0x14)
+#define BMA400_I2C_ADDRESS_SDO_HIGH    UINT8_C(0x15)
+/**\name Power mode configurations */
+#define BMA400_NORMAL_MODE       UINT8_C(0x02)
+#define BMA400_SLEEP_MODE        UINT8_C(0x00)
+#define BMA400_LOW_POWER_MODE    UINT8_C(0x01)
+/**\name Enable / Disable macros */
+#define BMA400_DISABLE        UINT8_C(0)
+#define BMA400_ENABLE         UINT8_C(1)
+/**\name Data/sensortime selection macros */
+#define BMA400_DATA_ONLY          UINT8_C(0x00)
+#define BMA400_DATA_SENSOR_TIME   UINT8_C(0x01)
+/**\name ODR configurations  */
+#define BMA400_ODR_12_5HZ     UINT8_C(0x05)
+#define BMA400_ODR_25HZ       UINT8_C(0x06)
+#define BMA400_ODR_50HZ       UINT8_C(0x07)
+#define BMA400_ODR_100HZ      UINT8_C(0x08)
+#define BMA400_ODR_200HZ      UINT8_C(0x09)
+#define BMA400_ODR_400HZ      UINT8_C(0x0A)
+#define BMA400_ODR_800HZ      UINT8_C(0x0B)
+/**\name Accel Range configuration */
+#define BMA400_2G_RANGE      UINT8_C(0x00)
+#define BMA400_4G_RANGE      UINT8_C(0x01)
+#define BMA400_8G_RANGE      UINT8_C(0x02)
+#define BMA400_16G_RANGE     UINT8_C(0x03)
+/**\name Accel Axes selection settings for
+ * DATA SAMPLING, WAKEUP, ORIENTATION CHANGE,
+ * GEN1, GEN2 , ACTIVITY CHANGE
+ */
+#define BMA400_X_AXIS_EN       UINT8_C(0x01)
+#define BMA400_Y_AXIS_EN       UINT8_C(0x02)
+#define BMA400_Z_AXIS_EN       UINT8_C(0x04)
+#define BMA400_XYZ_AXIS_EN     UINT8_C(0x07)
+/**\name Accel filter(data_src_reg) selection settings */
+#define BMA400_DATA_SRC_ACCEL_FILT_1     UINT8_C(0x00)
+#define BMA400_DATA_SRC_ACCEL_FILT_2     UINT8_C(0x01)
+#define BMA400_DATA_SRC_ACCEL_FILT_LP    UINT8_C(0x02)
+/**\name Accel OSR (OSR,OSR_LP) settings */
+#define BMA400_ACCEL_OSR_SETTING_0       UINT8_C(0x00)
+#define BMA400_ACCEL_OSR_SETTING_1       UINT8_C(0x01)
+#define BMA400_ACCEL_OSR_SETTING_2       UINT8_C(0x02)
+#define BMA400_ACCEL_OSR_SETTING_3       UINT8_C(0x03)
+/**\name Accel filt1_bw settings */
+/* Accel filt1_bw = 0.48 * ODR */
+#define BMA400_ACCEL_FILT1_BW_0    UINT8_C(0x00)
+/* Accel filt1_bw = 0.24 * ODR */
+#define BMA400_ACCEL_FILT1_BW_1    UINT8_C(0x01)
+/**\name Auto wake-up timeout value of 10.24s */
+#define BMA400_AUTO_WAKEUP_TIMEOUT_MAX  UINT16_C(0x0FFF)
+/**\name Auto low power timeout value of 10.24s */
+#define BMA400_AUTO_LP_TIMEOUT_MAX      UINT16_C(0x0FFF)
+/**\name Reference Update macros */
+#define BMA400_MANUAL_UPDATE         UINT8_C(0x00)
+#define BMA400_ONE_TIME_UPDATE       UINT8_C(0x01)
+#define BMA400_EVERY_TIME_UPDATE     UINT8_C(0x02)
+#define BMA400_LP_EVERY_TIME_UPDATE  UINT8_C(0x03)
+/**\name Reference Update macros for orient interrupts */
+#define BMA400_ORIENT_REFU_ACC_FILT_2       UINT8_C(0x01)
+#define BMA400_ORIENT_REFU_ACC_FILT_LP      UINT8_C(0x02)
+/**\name Stability evaluation macros for orient interrupts */
+#define BMA400_STABILITY_DISABLED        UINT8_C(0x00)
+#define BMA400_STABILITY_ACC_FILT_2      UINT8_C(0x01)
+#define BMA400_STABILITY_ACC_FILT_LP     UINT8_C(0x02)
+/**\name Number of samples needed for Auto-wakeup interrupt evaluation  */
+#define BMA400_SAMPLE_COUNT_1   UINT8_C(0x00)
+#define BMA400_SAMPLE_COUNT_2   UINT8_C(0x01)
+#define BMA400_SAMPLE_COUNT_3   UINT8_C(0x02)
+#define BMA400_SAMPLE_COUNT_4   UINT8_C(0x03)
+#define BMA400_SAMPLE_COUNT_5   UINT8_C(0x04)
+#define BMA400_SAMPLE_COUNT_6   UINT8_C(0x05)
+#define BMA400_SAMPLE_COUNT_7   UINT8_C(0x06)
+#define BMA400_SAMPLE_COUNT_8   UINT8_C(0x07)
+/**\name Auto low power configurations */
+/* Auto low power timeout disabled  */
+#define BMA400_AUTO_LP_TIMEOUT_DISABLE    UINT8_C(0x00)
+/* Auto low power entered on drdy interrupt */
+#define BMA400_AUTO_LP_DRDY_TRIGGER       UINT8_C(0x01)
+/* Auto low power entered on GEN1 interrupt */
+#define BMA400_AUTO_LP_GEN1_TRIGGER       UINT8_C(0x02)
+/* Auto low power entered on timeout of threshold value */
+#define BMA400_AUTO_LP_TIMEOUT_EN         UINT8_C(0x04)
+/* Auto low power entered on timeout of threshold value
+ * but reset on activity detection
+ */
+#define BMA400_AUTO_LP_TIME_RESET_EN      UINT8_C(0x08)
+/**\name    TAP INTERRUPT CONFIG MACROS   */
+/* Axes select for TAP interrupt */
+#define BMA400_X_AXIS_EN_TAP   UINT8_C(0x02)
+#define BMA400_Y_AXIS_EN_TAP   UINT8_C(0x01)
+#define BMA400_Z_AXIS_EN_TAP   UINT8_C(0x00)
+/*! TAP tics_th setting */
+/* Maximum time between upper and lower peak of a tap, in data samples
+ * this time depends on the mechanics of the device tapped onto
+ * default = 12 samples
+ */
+/* Configures 6 data samples for high-low tap signal change time */
+#define BMA400_TICS_TH_6_DATA_SAMPLES  UINT8_C(0x00)
+/* Configures 9 data samples for high-low tap signal change time */
+#define BMA400_TICS_TH_9_DATA_SAMPLES  UINT8_C(0x01)
+/* Configures 12 data samples for high-low tap signal change time */
+#define BMA400_TICS_TH_12_DATA_SAMPLES UINT8_C(0x02)
+/* Configures 18 data samples for high-low tap signal change time */
+#define BMA400_TICS_TH_18_DATA_SAMPLES UINT8_C(0x03)
+/*! TAP Sensitivity setting */
+/* It modifies the threshold for minimum TAP amplitude */
+/* BMA400_TAP_SENSITIVITY_0 correspond to highest sensitivity */
+#define BMA400_TAP_SENSITIVITY_0  UINT8_C(0x00)
+#define BMA400_TAP_SENSITIVITY_1  UINT8_C(0x01)
+#define BMA400_TAP_SENSITIVITY_2  UINT8_C(0x02)
+#define BMA400_TAP_SENSITIVITY_3  UINT8_C(0x03)
+#define BMA400_TAP_SENSITIVITY_4  UINT8_C(0x04)
+#define BMA400_TAP_SENSITIVITY_5  UINT8_C(0x05)
+#define BMA400_TAP_SENSITIVITY_6  UINT8_C(0x06)
+/* BMA400_TAP_SENSITIVITY_7 correspond to lowest sensitivity */
+#define BMA400_TAP_SENSITIVITY_7  UINT8_C(0x07)
+/*!  BMA400 TAP - quiet  settings */
+/* Quiet refers to minimum quiet time before and after double tap,
+ * in the data samples This time also defines the longest time interval
+ * between two taps so that they are considered as double tap
+ */
+/* Configures 60 data samples quiet time between single or double taps */
+#define BMA400_QUIET_60_DATA_SAMPLES   UINT8_C(0x00)
+/* Configures 80 data samples quiet time between single or double taps */
+#define BMA400_QUIET_80_DATA_SAMPLES   UINT8_C(0x01)
+/* Configures 100 data samples quiet time between single or double taps */
+#define BMA400_QUIET_100_DATA_SAMPLES  UINT8_C(0x02)
+/* Configures 120 data samples quiet time between single or double taps */
+#define BMA400_QUIET_120_DATA_SAMPLES  UINT8_C(0x03)
+/*!  BMA400 TAP - quiet_dt  settings */
+/* quiet_dt refers to Minimum time between the two taps of a
+ * double tap, in data samples
+ */
+/* Configures 4 data samples minimum time between double taps */
+#define BMA400_QUIET_DT_4_DATA_SAMPLES   UINT8_C(0x00)
+/* Configures 8 data samples minimum time between double taps */
+#define BMA400_QUIET_DT_8_DATA_SAMPLES   UINT8_C(0x01)
+/* Configures 12 data samples minimum time between double taps */
+#define BMA400_QUIET_DT_12_DATA_SAMPLES  UINT8_C(0x02)
+/* Configures 16 data samples minimum time between double taps */
+#define BMA400_QUIET_DT_16_DATA_SAMPLES  UINT8_C(0x03)
+/**\name	ACTIVITY CHANGE CONFIG MACROS	*/
+/* Data source for activity change detection */
+#define BMA400_DATA_SRC_ACC_FILT1      UINT8_C(0x00)
+#define BMA400_DATA_SRC_ACC_FILT2      UINT8_C(0x01)
+/* Number of samples to evaluate for activity change detection */
+#define BMA400_ACT_CH_SAMPLE_CNT_32    UINT8_C(0x00)
+#define BMA400_ACT_CH_SAMPLE_CNT_64    UINT8_C(0x01)
+#define BMA400_ACT_CH_SAMPLE_CNT_128   UINT8_C(0x02)
+#define BMA400_ACT_CH_SAMPLE_CNT_256   UINT8_C(0x03)
+#define BMA400_ACT_CH_SAMPLE_CNT_512   UINT8_C(0x04)
+/**\name Interrupt pin configuration macros */
+#define BMA400_INT_PUSH_PULL_ACTIVE_0    UINT8_C(0x00)
+#define BMA400_INT_PUSH_PULL_ACTIVE_1    UINT8_C(0x01)
+#define BMA400_INT_OPEN_DRIVE_ACTIVE_0   UINT8_C(0x02)
+#define BMA400_INT_OPEN_DRIVE_ACTIVE_1   UINT8_C(0x03)
+/**\name Interrupt Assertion status macros */
+#define BMA400_WAKEUP_INT_ASSERTED      UINT16_C(0x0001)
+#define BMA400_ORIENT_CH_INT_ASSERTED   UINT16_C(0x0002)
+#define BMA400_GEN1_INT_ASSERTED        UINT16_C(0x0004)
+#define BMA400_GEN2_INT_ASSERTED        UINT16_C(0x0008)
+#define BMA400_INT_OVERRUN_ASSERTED     UINT16_C(0x0010)
+#define BMA400_FIFO_FULL_INT_ASSERTED   UINT16_C(0x0020)
+#define BMA400_FIFO_WM_INT_ASSERTED     UINT16_C(0x0040)
+#define BMA400_DRDY_INT_ASSERTED        UINT16_C(0x0080)
+#define BMA400_STEP_INT_ASSERTED        UINT16_C(0x0300)
+#define BMA400_S_TAP_INT_ASSERTED       UINT16_C(0x0400)
+#define BMA400_D_TAP_INT_ASSERTED       UINT16_C(0x0800)
+#define BMA400_ACT_CH_X_ASSERTED        UINT16_C(0x2000)
+#define BMA400_ACT_CH_Y_ASSERTED        UINT16_C(0x4000)
+#define BMA400_ACT_CH_Z_ASSERTED        UINT16_C(0x8000)
+/**\name Generic interrupt criterion_sel configuration macros */
+#define BMA400_ACTIVITY_INT             UINT8_C(0x01)
+#define BMA400_INACTIVITY_INT           UINT8_C(0x00)
+/**\name Generic interrupt axes evaluation logic configuration macros */
+#define BMA400_ALL_AXES_INT             UINT8_C(0x01)
+#define BMA400_ANY_AXES_INT             UINT8_C(0x00)
+/**\name Generic interrupt hysteresis configuration macros */
+#define BMA400_HYST_0_MG     UINT8_C(0x00)
+#define BMA400_HYST_24_MG    UINT8_C(0x01)
+#define BMA400_HYST_48_MG    UINT8_C(0x02)
+#define BMA400_HYST_96_MG    UINT8_C(0x03)
+/**********************************************************************/
+/**\name BMA400 Register Address */
+#define BMA400_CHIP_ID_ADDR              UINT8_C(0x00)
+#define BMA400_STATUS_ADDR               UINT8_C(0x03)
+#define BMA400_ACCEL_DATA_ADDR           UINT8_C(0x04)
+#define BMA400_INT_STAT0_ADDR            UINT8_C(0x0E)
+#define BMA400_TEMP_DATA_ADDR            UINT8_C(0x11)
+#define BMA400_FIFO_LENGTH_ADDR          UINT8_C(0x12)
+#define BMA400_FIFO_DATA_ADDR            UINT8_C(0x14)
+#define BMA400_STEP_CNT_0_ADDR           UINT8_C(0x15)
+#define BMA400_ACCEL_CONFIG_0_ADDR       UINT8_C(0x19)
+#define BMA400_ACCEL_CONFIG_1_ADDR       UINT8_C(0x1A)
+#define BMA400_ACCEL_CONFIG_2_ADDR       UINT8_C(0x1B)
+#define BMA400_INT_CONF_0_ADDR           UINT8_C(0x1F)
+#define BMA400_INT_12_IO_CTRL_ADDR       UINT8_C(0x24)
+#define BMA400_INT_MAP_ADDR              UINT8_C(0x21)
+#define BMA400_FIFO_CONFIG_0_ADDR        UINT8_C(0x26)
+#define BMA400_FIFO_READ_EN_ADDR         UINT8_C(0x29)
+#define BMA400_AUTO_LOW_POW_0_ADDR       UINT8_C(0x2A)
+#define BMA400_AUTO_LOW_POW_1_ADDR       UINT8_C(0x2B)
+#define BMA400_AUTOWAKEUP_0_ADDR         UINT8_C(0x2C)
+#define BMA400_AUTOWAKEUP_1_ADDR         UINT8_C(0x2D)
+#define BMA400_WAKEUP_INT_CONF_0_ADDR    UINT8_C(0x2F)
+#define BMA400_ORIENTCH_INT_CONFIG_ADDR  UINT8_C(0x35)
+#define BMA400_GEN1_INT_CONFIG_ADDR      UINT8_C(0x3F)
+#define BMA400_GEN2_INT_CONFIG_ADDR      UINT8_C(0x4A)
+#define BMA400_ACT_CH_CONFIG_0_ADDR      UINT8_C(0x55)
+#define BMA400_TAP_CONFIG_ADDR           UINT8_C(0x57)
+#define BMA400_SELF_TEST_ADDR            UINT8_C(0x7D)
+#define BMA400_COMMAND_REG_ADDR          UINT8_C(0x7E)
+/**\name BMA400 Command register */
+#define BMA400_SOFT_RESET_CMD     UINT8_C(0xB6)
+#define BMA400_FIFO_FLUSH_CMD     UINT8_C(0xB0)
+/**\name BMA400 Delay definitions */
+#define BMA400_SOFT_RESET_DELAY_MS       UINT8_C(5)
+#define BMA400_SELF_TEST_DELAY_MS        UINT8_C(7)
+#define BMA400_SELF_TEST_DATA_READ_MS    UINT8_C(50)
+/**\name Interface selection macro */
+#define BMA400_SPI_WR_MASK    UINT8_C(0x7F)
+#define BMA400_SPI_RD_MASK    UINT8_C(0x80)
+/**\name UTILITY MACROS	*/
+#define BMA400_SET_LOW_BYTE     UINT16_C(0x00FF)
+#define BMA400_SET_HIGH_BYTE    UINT16_C(0xFF00)
+/**\name Interrupt mapping selection */
+#define BMA400_DATA_READY_INT_MAP     UINT8_C(0x01)
+#define BMA400_FIFO_WM_INT_MAP        UINT8_C(0x02)
+#define BMA400_FIFO_FULL_INT_MAP      UINT8_C(0x03)
+#define BMA400_GEN2_INT_MAP           UINT8_C(0x04)
+#define BMA400_GEN1_INT_MAP           UINT8_C(0x05)
+#define BMA400_ORIENT_CH_INT_MAP      UINT8_C(0x06)
+#define BMA400_WAKEUP_INT_MAP         UINT8_C(0x07)
+#define BMA400_ACT_CH_INT_MAP         UINT8_C(0x08)
+#define BMA400_TAP_INT_MAP            UINT8_C(0x09)
+#define BMA400_STEP_INT_MAP           UINT8_C(0x0A)
+#define BMA400_INT_OVERRUN_MAP        UINT8_C(0x0B)
+/**\name BMA400 FIFO configurations */
+#define BMA400_FIFO_AUTO_FLUSH          UINT8_C(0x01)
+#define BMA400_FIFO_STOP_ON_FULL        UINT8_C(0x02)
+#define BMA400_FIFO_TIME_EN             UINT8_C(0x04)
+#define BMA400_FIFO_DATA_SRC            UINT8_C(0x08)
+#define BMA400_FIFO_8_BIT_EN            UINT8_C(0x10)
+#define BMA400_FIFO_X_EN                UINT8_C(0x20)
+#define BMA400_FIFO_Y_EN                UINT8_C(0x40)
+#define BMA400_FIFO_Z_EN                UINT8_C(0x80)
+/**\name BMA400 FIFO data configurations */
+#define BMA400_FIFO_EN_X         UINT8_C(0x01)
+#define BMA400_FIFO_EN_Y         UINT8_C(0x02)
+#define BMA400_FIFO_EN_Z         UINT8_C(0x04)
+#define BMA400_FIFO_EN_XY        UINT8_C(0x03)
+#define BMA400_FIFO_EN_YZ        UINT8_C(0x06)
+#define BMA400_FIFO_EN_XZ        UINT8_C(0x05)
+#define BMA400_FIFO_EN_XYZ       UINT8_C(0x07)
+/**\name BMA400 Self test configurations */
+#define BMA400_DISABLE_SELF_TEST          UINT8_C(0x00)
+#define BMA400_ENABLE_POSITIVE_SELF_TEST  UINT8_C(0x07)
+#define BMA400_ENABLE_NEGATIVE_SELF_TEST  UINT8_C(0x0F)
+/**\name BMA400 FIFO data masks */
+#define BMA400_FIFO_HEADER_MASK        UINT8_C(0x3E)
+#define BMA400_FIFO_BYTES_OVERREAD     UINT8_C(25)
+#define BMA400_AWIDTH_MASK             UINT8_C(0xEF)
+#define BMA400_FIFO_DATA_EN_MASK       UINT8_C(0x0E)
+/**\name BMA400 Step status field - Activity status */
+#define BMA400_STILL_ACT     UINT8_C(0x00)
+#define BMA400_WALK_ACT      UINT8_C(0x01)
+#define BMA400_RUN_ACT       UINT8_C(0x02)
+/*! It is inserted when FIFO_CONFIG0.fifo_data_src
+ * is changed during the FIFO read
+ */
+#define BMA400_FIFO_CONF0_CHANGE  UINT8_C(0x01)
+/*! It is inserted when ACC_CONFIG0.filt1_bw
+ * is changed during the FIFO read
+  */
+#define BMA400_ACCEL_CONF0_CHANGE  UINT8_C(0x02)
+/*! It is inserted when ACC_CONFIG1.acc_range
+ * acc_odr or osr is changed during the FIFO read
+ */
+#define BMA400_ACCEL_CONF1_CHANGE  UINT8_C(0x04)
+/*! Accel width setting either 12/8 bit mode */
+#define BMA400_12_BIT_FIFO_DATA       UINT8_C(0x01)
+#define BMA400_8_BIT_FIFO_DATA        UINT8_C(0x00)
+/**\name BMA400 FIFO header configurations */
+#define BMA400_FIFO_SENSOR_TIME     UINT8_C(0xA0)
+#define BMA400_FIFO_EMPTY_FRAME     UINT8_C(0x80)
+#define BMA400_FIFO_CONTROL_FRAME   UINT8_C(0x48)
+#define BMA400_FIFO_XYZ_ENABLE      UINT8_C(0x8E)
+#define BMA400_FIFO_X_ENABLE        UINT8_C(0x82)
+#define BMA400_FIFO_Y_ENABLE        UINT8_C(0x84)
+#define BMA400_FIFO_Z_ENABLE        UINT8_C(0x88)
+#define BMA400_FIFO_XY_ENABLE       UINT8_C(0x86)
+#define BMA400_FIFO_YZ_ENABLE       UINT8_C(0x8C)
+#define BMA400_FIFO_XZ_ENABLE       UINT8_C(0x8A)
+/**\name BMA400 bit mask definitions */
+#define BMA400_POWER_MODE_STATUS_MSK         UINT8_C(0x06)
+#define BMA400_POWER_MODE_STATUS_POS         UINT8_C(1)
+
+#define BMA400_POWER_MODE_MSK      UINT8_C(0x03)
+
+#define BMA400_ACCEL_ODR_MSK      UINT8_C(0x0F)
+
+#define BMA400_ACCEL_RANGE_MSK    UINT8_C(0xC0)
+#define BMA400_ACCEL_RANGE_POS    UINT8_C(6)
+
+#define BMA400_DATA_FILTER_MSK   UINT8_C(0x0C)
+#define BMA400_DATA_FILTER_POS   UINT8_C(2)
+
+#define BMA400_OSR_MSK    UINT8_C(0x30)
+#define BMA400_OSR_POS    UINT8_C(4)
+
+#define BMA400_OSR_LP_MSK        UINT8_C(0x60)
+#define BMA400_OSR_LP_POS        UINT8_C(5)
+
+#define BMA400_FILT_1_BW_MSK            UINT8_C(0x80)
+#define BMA400_FILT_1_BW_POS            UINT8_C(7)
+
+#define BMA400_WAKEUP_TIMEOUT_MSK       UINT8_C(0x04)
+#define BMA400_WAKEUP_TIMEOUT_POS       UINT8_C(2)
+
+#define BMA400_WAKEUP_THRES_LSB_MSK     UINT16_C(0x000F)
+
+#define BMA400_WAKEUP_THRES_MSB_MSK     UINT16_C(0x0FF0)
+#define BMA400_WAKEUP_THRES_MSB_POS     UINT8_C(4)
+
+#define BMA400_WAKEUP_TIMEOUT_THRES_MSK UINT8_C(0xF0)
+#define BMA400_WAKEUP_TIMEOUT_THRES_POS UINT8_C(4)
+
+#define BMA400_WAKEUP_INTERRUPT_MSK     UINT8_C(0x02)
+#define BMA400_WAKEUP_INTERRUPT_POS     UINT8_C(1)
+
+#define BMA400_AUTO_LOW_POW_MSK       UINT8_C(0x0F)
+
+#define BMA400_AUTO_LP_THRES_MSK      UINT16_C(0x0FF0)
+#define BMA400_AUTO_LP_THRES_POS      UINT8_C(4)
+
+#define BMA400_AUTO_LP_THRES_LSB_MSK  UINT16_C(0x000F)
+
+#define BMA400_WKUP_REF_UPDATE_MSK    UINT8_C(0x03)
+
+#define BMA400_AUTO_LP_TIMEOUT_LSB_MSK UINT8_C(0xF0)
+#define BMA400_AUTO_LP_TIMEOUT_LSB_POS UINT8_C(4)
+
+#define BMA400_SAMPLE_COUNT_MSK        UINT8_C(0x1C)
+#define BMA400_SAMPLE_COUNT_POS        UINT8_C(2)
+
+#define BMA400_WAKEUP_EN_AXES_MSK      UINT8_C(0xE0)
+#define BMA400_WAKEUP_EN_AXES_POS      UINT8_C(5)
+
+#define BMA400_TAP_AXES_EN_MSK         UINT8_C(0x18)
+#define BMA400_TAP_AXES_EN_POS         UINT8_C(3)
+
+#define BMA400_TAP_QUIET_DT_MSK         UINT8_C(0x30)
+#define BMA400_TAP_QUIET_DT_POS         UINT8_C(4)
+
+#define BMA400_TAP_QUIET_MSK            UINT8_C(0x0C)
+#define BMA400_TAP_QUIET_POS            UINT8_C(2)
+
+#define BMA400_TAP_TICS_TH_MSK         UINT8_C(0x03)
+
+#define BMA400_TAP_SENSITIVITY_MSK     UINT8_C(0X07)
+
+#define BMA400_ACT_CH_AXES_EN_MSK      UINT8_C(0xE0)
+#define BMA400_ACT_CH_AXES_EN_POS      UINT8_C(5)
+
+#define BMA400_ACT_CH_DATA_SRC_MSK     UINT8_C(0x10)
+#define BMA400_ACT_CH_DATA_SRC_POS     UINT8_C(4)
+
+#define BMA400_ACT_CH_NPTS_MSK         UINT8_C(0x0F)
+
+#define BMA400_INT_AXES_EN_MSK    UINT8_C(0xE0)
+#define BMA400_INT_AXES_EN_POS    UINT8_C(5)
+
+#define BMA400_INT_DATA_SRC_MSK   UINT8_C(0x10)
+#define BMA400_INT_DATA_SRC_POS   UINT8_C(4)
+
+#define BMA400_INT_REFU_MSK       UINT8_C(0x0C)
+#define BMA400_INT_REFU_POS       UINT8_C(2)
+
+#define BMA400_INT_HYST_MSK         UINT8_C(0x03)
+#define BMA400_STABILITY_MODE_MSK   UINT8_C(0x03)
+
+#define BMA400_GEN_INT_COMB_MSK      UINT8_C(0x01)
+
+#define BMA400_GEN_INT_CRITERION_MSK  UINT8_C(0x02)
+#define BMA400_GEN_INT_CRITERION_POS  UINT8_C(0x01)
+
+#define BMA400_INT_PIN1_CONF_MSK   UINT8_C(0x06)
+#define BMA400_INT_PIN1_CONF_POS   UINT8_C(1)
+
+#define BMA400_INT_PIN2_CONF_MSK   UINT8_C(0x60)
+#define BMA400_INT_PIN2_CONF_POS   UINT8_C(5)
+
+#define BMA400_INT_STATUS_MSK     UINT8_C(0xE0)
+#define BMA400_INT_STATUS_POS     UINT8_C(5)
+
+#define BMA400_EN_DRDY_MSK  UINT8_C(0x80)
+#define BMA400_EN_DRDY_POS  UINT8_C(7)
+
+#define BMA400_EN_FIFO_WM_MSK  UINT8_C(0x40)
+#define BMA400_EN_FIFO_WM_POS  UINT8_C(6)
+
+#define BMA400_EN_FIFO_FULL_MSK  UINT8_C(0x20)
+#define BMA400_EN_FIFO_FULL_POS  UINT8_C(5)
+
+#define BMA400_EN_INT_OVERRUN_MSK  UINT8_C(0x10)
+#define BMA400_EN_INT_OVERRUN_POS  UINT8_C(4)
+
+#define BMA400_EN_GEN2_MSK  UINT8_C(0x08)
+#define BMA400_EN_GEN2_POS  UINT8_C(3)
+
+#define BMA400_EN_GEN1_MSK  UINT8_C(0x04)
+#define BMA400_EN_GEN1_POS  UINT8_C(2)
+
+#define BMA400_EN_ORIENT_CH_MSK  UINT8_C(0x02)
+#define BMA400_EN_ORIENT_CH_POS  UINT8_C(1)
+
+#define BMA400_EN_LATCH_MSK  UINT8_C(0x80)
+#define BMA400_EN_LATCH_POS  UINT8_C(7)
+
+#define BMA400_EN_ACTCH_MSK  UINT8_C(0x10)
+#define BMA400_EN_ACTCH_POS  UINT8_C(4)
+
+#define BMA400_EN_D_TAP_MSK  UINT8_C(0x08)
+#define BMA400_EN_D_TAP_POS  UINT8_C(3)
+
+#define BMA400_EN_S_TAP_MSK  UINT8_C(0x04)
+#define BMA400_EN_S_TAP_POS  UINT8_C(2)
+
+#define BMA400_EN_STEP_INT_MSK  UINT8_C(0x01)
+
+#define BMA400_STEP_MAP_INT2_MSK  UINT8_C(0x10)
+#define BMA400_STEP_MAP_INT2_POS  UINT8_C(4)
+
+#define BMA400_EN_WAKEUP_INT_MSK  UINT8_C(0x01)
+
+#define BMA400_TAP_MAP_INT1_MSK  UINT8_C(0x04)
+#define BMA400_TAP_MAP_INT1_POS  UINT8_C(2)
+
+#define BMA400_TAP_MAP_INT2_MSK  UINT8_C(0x40)
+#define BMA400_TAP_MAP_INT2_POS  UINT8_C(6)
+
+#define BMA400_ACTCH_MAP_INT1_MSK  UINT8_C(0x08)
+#define BMA400_ACTCH_MAP_INT1_POS  UINT8_C(3)
+
+#define BMA400_ACTCH_MAP_INT2_MSK  UINT8_C(0x80)
+#define BMA400_ACTCH_MAP_INT2_POS  UINT8_C(7)
+
+#define BMA400_FIFO_BYTES_CNT_MSK  UINT8_C(0x07)
+
+#define BMA400_FIFO_TIME_EN_MSK  UINT8_C(0x04)
+#define BMA400_FIFO_TIME_EN_POS  UINT8_C(2)
+
+#define BMA400_FIFO_AXES_EN_MSK  UINT8_C(0xE0)
+#define BMA400_FIFO_AXES_EN_POS  UINT8_C(5)
+
+#define BMA400_FIFO_8_BIT_EN_MSK  UINT8_C(0x10)
+#define BMA400_FIFO_8_BIT_EN_POS  UINT8_C(4)
+/**\name Macro to SET and GET BITS of a register */
+#define BMA400_SET_BITS(reg_data, bitname, data) \
+	((reg_data & ~(bitname ## _MSK)) |	 \
+	 ((data << bitname ## _POS) & bitname ## _MSK))
+
+#define BMA400_GET_BITS(reg_data, bitname)  ((reg_data & (bitname ## _MSK)) >> \
+					     (bitname ## _POS))
+
+#define BMA400_SET_BITS_POS_0(reg_data, bitname, data) \
+	((reg_data & ~(bitname ## _MSK)) |	       \
+	 (data & bitname ## _MSK))
+
+#define BMA400_GET_BITS_POS_0(reg_data, bitname)  (reg_data & (bitname ## _MSK))
+
+#define BMA400_SET_BIT_VAL_0(reg_data, bitname) (reg_data & ~(bitname ## _MSK))
+
+#define BMA400_GET_LSB(var)     (uint8_t)(var & BMA400_SET_LOW_BYTE)
+#define BMA400_GET_MSB(var)     (uint8_t)((var & BMA400_SET_HIGH_BYTE) >> 8)
+/********************************************************/
+/*!
+ * @brief Interface selection enums
+ */
+enum bma400_intf {
+	/*! SPI interface */
+	BMA400_SPI_INTF,
+	/*! I2C interface */
+	BMA400_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 (*bma400_com_fptr_t)(void *intf_ptr, uint8_t dev_id, uint8_t reg_addr, uint8_t *reg_data,
+				    uint16_t length);
+/*!	Delay function pointer */
+typedef void (*bma400_delay_fptr_t)(uint32_t period);
+/********************************************************/
+/**\name	STRUCTURE DEFINITIONS*/
+/*!
+ * @brief Sensor selection enums
+ */
+enum bma400_sensor {
+	BMA400_ACCEL,
+	BMA400_TAP_INT,
+	BMA400_ACTIVITY_CHANGE_INT,
+	BMA400_GEN1_INT,
+	BMA400_GEN2_INT,
+	BMA400_ORIENT_CHANGE_INT,
+	BMA400_STEP_COUNTER_INT
+};
+
+/*!
+ * @brief Interrupt channel selection enums
+ */
+enum bma400_int_chan {
+	BMA400_UNMAP_INT_PIN,
+	BMA400_INT_CHANNEL_1,
+	BMA400_INT_CHANNEL_2,
+	BMA400_MAP_BOTH_INT_PINS
+};
+/*!
+ * @brief Interrupt pin hardware configurations
+ */
+struct bma400_int_pin_conf {
+	/*! Interrupt channel selection enums */
+	enum bma400_int_chan int_chan;
+	/*! Interrupt pin configuration
+	 * Assignable Macros :
+	 *  - BMA400_INT_PUSH_PULL_ACTIVE_0
+	 *  - BMA400_INT_PUSH_PULL_ACTIVE_1
+	 *  - BMA400_INT_OPEN_DRIVE_ACTIVE_0
+	 *  - BMA400_INT_OPEN_DRIVE_ACTIVE_1
+	 */
+	uint8_t pin_conf;
+};
+/*!
+ * @brief Accel basic configuration
+ */
+struct bma400_acc_conf {
+	/*! Output data rate
+	 * Assignable macros :
+	 *  - BMA400_ODR_12_5HZ  - BMA400_ODR_25HZ   - BMA400_ODR_50HZ
+	 *  - BMA400_ODR_100HZ   - BMA400_ODR_200HZ  - BMA400_ODR_400HZ
+	 *  - BMA400_ODR_800HZ
+	 */
+	uint8_t odr;
+	/*! Range of sensor
+	 * Assignable macros :
+	 *  - BMA400_2G_RANGE   - BMA400_8G_RANGE
+	 *  - BMA400_4G_RANGE   - BMA400_16G_RANGE
+	 */
+	uint8_t range;
+	/*! Filter setting for data source
+	 * Assignable Macros :
+	 * - BMA400_DATA_SRC_ACCEL_FILT_1
+	 * - BMA400_DATA_SRC_ACCEL_FILT_2
+	 * - BMA400_DATA_SRC_ACCEL_FILT_LP
+	 */
+	uint8_t data_src;
+	/*! Assignable Macros for osr and osr_lp:
+	 * - BMA400_ACCEL_OSR_SETTING_0     - BMA400_ACCEL_OSR_SETTING_2
+	 * - BMA400_ACCEL_OSR_SETTING_1     - BMA400_ACCEL_OSR_SETTING_3
+	 */
+	/*! OSR setting for data source */
+	uint8_t osr;
+	/*! OSR setting for low power mode */
+	uint8_t osr_lp;
+	/*! Filter 1 Bandwidth
+	 * Assignable macros :
+	 *  - BMA400_ACCEL_FILT1_BW_0
+	 *  - BMA400_ACCEL_FILT1_BW_1
+	 */
+	uint8_t filt1_bw;
+	/*! Interrupt channel to be mapped */
+	enum bma400_int_chan int_chan;
+};
+/*!
+ * @brief Tap interrupt configurations
+ */
+struct bma400_tap_conf {
+	/*! Axes enabled to sense tap setting
+	 * Assignable macros :
+	 *   - BMA400_X_AXIS_EN_TAP
+	 *   - BMA400_Y_AXIS_EN_TAP
+	 *   - BMA400_Z_AXIS_EN_TAP
+	 */
+	uint8_t axes_sel;
+	/*! TAP sensitivity settings modifies the threshold
+	 *  for minimum TAP amplitude
+	 * Assignable macros :
+	 *   - BMA400_TAP_SENSITIVITY_0  - BMA400_TAP_SENSITIVITY_4
+	 *   - BMA400_TAP_SENSITIVITY_1  - BMA400_TAP_SENSITIVITY_5
+	 *   - BMA400_TAP_SENSITIVITY_2  - BMA400_TAP_SENSITIVITY_6
+	 *   - BMA400_TAP_SENSITIVITY_3  - BMA400_TAP_SENSITIVITY_7
+	 *
+	 * @note :
+	 *  - BMA400_TAP_SENSITIVITY_0 correspond to highest sensitivity
+	 *  - BMA400_TAP_SENSITIVITY_7 correspond to lowest sensitivity
+	 */
+	uint8_t sensitivity;
+	/*! TAP tics_th setting is the maximum time between upper and lower
+	 * peak of a tap, in data samples, This time depends on the
+	 * mechanics of the device tapped onto  default = 12 samples
+	 * Assignable macros :
+	 *   - BMA400_TICS_TH_6_DATA_SAMPLES
+	 *   - BMA400_TICS_TH_9_DATA_SAMPLES
+	 *   - BMA400_TICS_TH_12_DATA_SAMPLES
+	 *   - BMA400_TICS_TH_18_DATA_SAMPLES
+	 */
+	uint8_t tics_th;
+	/*! BMA400 TAP - quiet  settings to configure minimum quiet time
+	 *  before and after double tap, in the data samples.
+	 * This time also defines the longest time interval between two
+	 * taps so that they are considered as double tap
+	 * Assignable macros :
+	 *   - BMA400_QUIET_60_DATA_SAMPLES
+	 *   - BMA400_QUIET_80_DATA_SAMPLES
+	 *   - BMA400_QUIET_100_DATA_SAMPLES
+	 *   - BMA400_QUIET_120_DATA_SAMPLES
+	 */
+	uint8_t quiet;
+	/*! BMA400 TAP - quiet_dt  settings
+	 * quiet_dt refers to Minimum time between the two taps of a
+	 * double tap, in data samples
+	 * Assignable macros :
+	 *   - BMA400_QUIET_DT_4_DATA_SAMPLES
+	 *   - BMA400_QUIET_DT_8_DATA_SAMPLES
+	 *   - BMA400_QUIET_DT_12_DATA_SAMPLES
+	 *   - BMA400_QUIET_DT_16_DATA_SAMPLES
+	 */
+	uint8_t quiet_dt;
+	/*! Interrupt channel to be mapped */
+	enum bma400_int_chan int_chan;
+};
+/*!
+ * @brief Activity change interrupt configurations
+ */
+struct bma400_act_ch_conf {
+	/*! Threshold for activity change (8 mg/LSB) */
+	uint8_t act_ch_thres;
+	/*! Axes enabled to sense activity change
+	 * Assignable macros :
+	 *   - BMA400_X_AXIS_EN
+	 *   - BMA400_Y_AXIS_EN
+	 *   - BMA400_Z_AXIS_EN
+	 *   - BMA400_XYZ_AXIS_EN
+	 */
+	uint8_t axes_sel;
+	/*! Data Source for activity change
+	 * Assignable macros :
+	 *    - BMA400_DATA_SRC_ACC_FILT1
+	 *    - BMA400_DATA_SRC_ACC_FILT2
+	 */
+	uint8_t data_source;
+	/*! Sample count for sensing act_ch
+	 * Assignable macros :
+	 *  - BMA400_ACT_CH_SAMPLE_CNT_32
+	 *  - BMA400_ACT_CH_SAMPLE_CNT_64
+	 *  - BMA400_ACT_CH_SAMPLE_CNT_128
+	 *  - BMA400_ACT_CH_SAMPLE_CNT_256
+	 *  - BMA400_ACT_CH_SAMPLE_CNT_512
+	 */
+	uint8_t act_ch_ntps;
+	/*! Interrupt channel to be mapped */
+	enum bma400_int_chan int_chan;
+};
+/*!
+ * @brief Generic interrupt configurations
+ */
+struct bma400_gen_int_conf {
+	/*! Threshold for the gen1 interrupt (1 LSB = 8mg)
+	 * if gen_int_thres = 10, then threshold = 10 * 8 = 80mg
+	 */
+	uint8_t gen_int_thres;
+	/*! Duration for which the condition has to persist until
+	 *  interrupt can be triggered
+	 *  duration is measured in data samples of selected data source
+	 */
+	uint16_t gen_int_dur;
+	/*! Enable axes to sense for the gen1 interrupt
+	 * Assignable macros :
+	 *  - BMA400_X_AXIS_EN
+	 *  - BMA400_Y_AXIS_EN
+	 *  - BMA400_Z_AXIS_EN
+	 *  - BMA400_XYZ_AXIS_EN
+	 */
+	uint8_t axes_sel;
+	/*! Data source to sense for the gen1 interrupt
+	 * Assignable macros :
+	 *  - BMA400_DATA_SRC_ACC_FILT1
+	 *  - BMA400_DATA_SRC_ACC_FILT2
+	 */
+	uint8_t data_src;
+	/*! Activity/Inactivity selection macros
+	 * Assignable macros :
+	 *  - BMA400_ACTIVITY_INT
+	 *  - BMA400_INACTIVITY_INT
+	 */
+	uint8_t criterion_sel;
+	/*! Axes selection logic macros
+	 * Assignable macros :
+	 *  - BMA400_ALL_AXES_INT
+	 *  - BMA400_ANY_AXES_INT
+	 */
+	uint8_t evaluate_axes;
+	/*! Reference x,y,z values updates
+	 * Assignable macros :
+	 *  - BMA400_MANUAL_UPDATE
+	 *  - BMA400_ONE_TIME_UPDATE
+	 *  - BMA400_EVERY_TIME_UPDATE
+	 *  - BMA400_LP_EVERY_TIME_UPDATE
+	 */
+	uint8_t ref_update;
+	/*! Hysteresis value
+	 * Higher the hysteresis value, Lower the value of noise
+	 * Assignable macros :
+	 *  - BMA400_HYST_0_MG
+	 *  - BMA400_HYST_24_MG
+	 *  - BMA400_HYST_48_MG
+	 *  - BMA400_HYST_96_MG
+	 */
+	uint8_t hysteresis;
+	/*! Threshold value for x axes */
+	uint16_t int_thres_ref_x;
+	/*! Threshold value for y axes */
+	uint16_t int_thres_ref_y;
+	/*! Threshold value for z axes */
+	uint16_t int_thres_ref_z;
+	/*! Interrupt channel to be mapped */
+	enum bma400_int_chan int_chan;
+};
+/*!
+ * @brief Orient interrupt configurations
+ */
+struct bma400_orient_int_conf {
+	/*! Enable axes to sense for the gen1 interrupt
+	 * Assignable macros :
+	 *  - BMA400_X_AXIS_EN
+	 *  - BMA400_Y_AXIS_EN
+	 *  - BMA400_Z_AXIS_EN
+	 *  - BMA400_XYZ_AXIS_EN
+	 */
+	uint8_t axes_sel;
+	/*! Data source to sense for the gen1 interrupt
+	 * Assignable macros :
+	 *  - BMA400_DATA_SRC_ACC_FILT1
+	 *  - BMA400_DATA_SRC_ACC_FILT2
+	 */
+	uint8_t data_src;
+	/*! Reference x,y,z values updates
+	 * Assignable macros :
+	 *  - BMA400_MANUAL_UPDATE
+	 *  - BMA400_ORIENT_REFU_ACC_FILT_2
+	 *  - BMA400_ORIENT_REFU_ACC_FILT_LP
+	 */
+	uint8_t ref_update;
+	/*! Threshold for the orient interrupt (1 LSB = 8mg)
+	 * if orient_thres = 10, then threshold = 10 * 8 = 80mg
+	 */
+	uint8_t orient_thres;
+	/*! Threshold to check for stability (1 LSB = 8mg)
+	 * if stability_thres = 10, then threshold = 10 * 8 = 80mg
+	 */
+	uint8_t stability_thres;
+	/*! orient_int_dur duration in which orient interrupt
+	 * should occur, It is 8bit value configurable at 10ms/LSB.
+	 */
+	uint8_t orient_int_dur;
+	/*! Stability check conditions
+	 * Assignable macros :
+	 *  - BMA400_STABILITY_DISABLED
+	 *  - BMA400_STABILITY_ACC_FILT_2
+	 *  - BMA400_STABILITY_ACC_FILT_LP
+	 */
+	uint8_t stability_mode;
+	/*! Reference value for x axes */
+	uint16_t orient_ref_x;
+	/*! Reference value for y axes */
+	uint16_t orient_ref_y;
+	/*! Reference value for z axes */
+	uint16_t orient_ref_z;
+	/*! Interrupt channel to be mapped */
+	enum bma400_int_chan int_chan;
+};
+/* Step counter configurations */
+struct bma400_step_int_conf {
+	/*! Interrupt channel to be mapped */
+	enum bma400_int_chan int_chan;
+};
+/*!
+ * @brief Union of sensor Configurations
+ */
+union bma400_set_param {
+	/* Accel configurations */
+	struct bma400_acc_conf accel;
+	/* TAP configurations */
+	struct bma400_tap_conf tap;
+	/* Activity change configurations */
+	struct bma400_act_ch_conf act_ch;
+	/* Generic interrupt configurations */
+	struct bma400_gen_int_conf gen_int;
+	/* Orient configurations */
+	struct bma400_orient_int_conf orient;
+	/* Step counter configurations */
+	struct bma400_step_int_conf step_cnt;
+};
+/*!
+ * @brief Sensor selection and their configurations
+ */
+struct bma400_sensor_conf {
+	/* Sensor selection */
+	enum bma400_sensor type;
+	/* Sensor configuration */
+	union bma400_set_param param;
+};
+/*!
+ * @brief enum to select device settings
+ */
+enum bma400_device {
+	BMA400_AUTOWAKEUP_TIMEOUT,
+	BMA400_AUTOWAKEUP_INT,
+	BMA400_AUTO_LOW_POWER,
+	BMA400_INT_PIN_CONF,
+	BMA400_INT_OVERRUN_CONF,
+	BMA400_FIFO_CONF
+};
+
+/*!
+ * @brief BMA400 auto-wakeup configurations
+ */
+struct bma400_auto_wakeup_conf {
+	/*! Enable auto wake-up by using timeout threshold
+	 * Assignable Macros :
+	 *   - BMA400_ENABLE    - BMA400_DISABLE
+	 */
+	uint8_t wakeup_timeout;
+	/*! Timeout threshold after which auto wake-up occurs
+	 * It is 12bit value configurable at 2.5ms/LSB
+	 * Maximum timeout is 10.24s (4096 * 2.5) for
+	 * which the assignable macro is :
+	 *      - BMA400_AUTO_WAKEUP_TIMEOUT_MAX
+	 */
+	uint16_t timeout_thres;
+};
+/*!
+ * @brief BMA400 wakeup configurations
+ */
+struct bma400_wakeup_conf {
+	/*! Wakeup reference update
+	 *  Assignable macros:
+	 *   - BMA400_MANUAL_UPDATE
+	 *   - BMA400_ONE_TIME_UPDATE
+	 *   - BMA400_EVERY_TIME_UPDATE
+	 */
+	uint8_t wakeup_ref_update;
+	/*! Number of samples for interrupt condition evaluation
+	 * Assignable Macros :
+	 *  - BMA400_SAMPLE_COUNT_1  - BMA400_SAMPLE_COUNT_5
+	 *  - BMA400_SAMPLE_COUNT_2  - BMA400_SAMPLE_COUNT_6
+	 *  - BMA400_SAMPLE_COUNT_3  - BMA400_SAMPLE_COUNT_7
+	 *  - BMA400_SAMPLE_COUNT_4  - BMA400_SAMPLE_COUNT_8
+	 */
+	uint8_t sample_count;
+	/*! Enable low power wake-up interrupt for X(BIT 0), Y(BIT 1), Z(BIT 2)
+	 * axes  0 - not active; 1 - active
+	 * Assignable macros :
+	 *  - BMA400_X_AXIS_EN
+	 *  - BMA400_Y_AXIS_EN
+	 *  - BMA400_Z_AXIS_EN
+	 *  - BMA400_XYZ_AXIS_EN
+	 */
+	uint8_t wakeup_axes_en;
+	/*! Interrupt threshold configuration  */
+	uint8_t int_wkup_threshold;
+	/*! Reference acceleration x-axis for the wake-up interrupt */
+	uint8_t int_wkup_ref_x;
+	/*! Reference acceleration y-axis for the wake-up interrupt */
+	uint8_t int_wkup_ref_y;
+	/*! Reference acceleration z-axis for the wake-up interrupt */
+	uint8_t int_wkup_ref_z;
+	/*! Interrupt channel to be mapped */
+	enum bma400_int_chan int_chan;
+};
+/*!
+ * @brief BMA400 auto-low power configurations
+ */
+struct bma400_auto_lp_conf {
+	/*! Enable auto low power mode using  data ready interrupt /
+	 * Genric interrupt1 / timeout counter value
+	 * Assignable macros :
+	 * - BMA400_AUTO_LP_DRDY_TRIGGER
+	 * - BMA400_AUTO_LP_GEN1_TRIGGER
+	 * - BMA400_AUTO_LP_TIMEOUT_EN
+	 * - BMA400_AUTO_LP_TIME_RESET_EN
+	 * - BMA400_AUTO_LP_TIMEOUT_DISABLE
+	 */
+	uint8_t auto_low_power_trigger;
+	/*! Timeout threshold after which auto wake-up occurs
+	 * It is 12bit value configurable at 2.5ms/LSB
+	 * Maximum timeout is 10.24s (4096 * 2.5) for
+	 *  which the assignable macro is :
+	 *  - BMA400_AUTO_LP_TIMEOUT_MAX
+	 */
+	uint16_t auto_lp_timeout_threshold;
+};
+/*!
+ * @brief FIFO configurations
+ */
+struct bma400_fifo_conf {
+	/*! Select FIFO configurations to enable/disable
+	 * Assignable Macros :
+	 *   - BMA400_FIFO_AUTO_FLUSH
+	 *   - BMA400_FIFO_STOP_ON_FULL
+	 *   - BMA400_FIFO_TIME_EN
+	 *   - BMA400_FIFO_DATA_SRC
+	 *   - BMA400_FIFO_8_BIT_EN
+	 *   - BMA400_FIFO_X_EN
+	 *   - BMA400_FIFO_Y_EN
+	 *   - BMA400_FIFO_Z_EN
+	 */
+	uint8_t conf_regs;
+	/*! Enable/ disable selected FIFO configurations
+	 * Assignable Macros :
+	 *   - BMA400_ENABLE
+	 *   - BMA400_DISABLE
+	 */
+	uint8_t conf_status;
+	/*! Value to set the water-mark */
+	uint16_t fifo_watermark;
+	/*! Interrupt pin mapping for FIFO full interrupt */
+	enum bma400_int_chan fifo_full_channel;
+	/*! Interrupt pin mapping for FIFO water-mark interrupt */
+	enum bma400_int_chan fifo_wm_channel;
+};
+/*!
+ * @brief Interrupt overrun configurations
+ */
+struct bma400_int_overrun {
+	/*! Interrupt pin mapping for interrupt overrun */
+	enum bma400_int_chan int_chan;
+};
+/*!
+ * @brief Union of device configuration parameters
+ */
+union bma400_device_params {
+	/* Auto wakeup configurations */
+	struct bma400_auto_wakeup_conf auto_wakeup;
+	/* Wakeup interrupt configurations */
+	struct bma400_wakeup_conf wakeup;
+	/* Auto Low power configurations */
+	struct bma400_auto_lp_conf auto_lp;
+	/* Interrupt pin configurations */
+	struct bma400_int_pin_conf int_conf;
+	/* FIFO configuration */
+	struct bma400_fifo_conf fifo_conf;
+	/* Interrupt overrun configuration */
+	struct bma400_int_overrun overrun_int;
+};
+/*!
+ * @brief BMA400 device configuration
+ */
+struct bma400_device_conf {
+	/* Device feature selection */
+	enum bma400_device type;
+	/* Device feature configuration */
+	union bma400_device_params param;
+};
+/*!
+ * @brief BMA400 sensor data
+ */
+struct bma400_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 BMA400 interrupt selection
+ */
+enum bma400_int_type {
+	/* DRDY interrupt */
+	BMA400_DRDY_INT_EN,
+	/* FIFO watermark interrupt */
+	BMA400_FIFO_WM_INT_EN,
+	/* FIFO full interrupt */
+	BMA400_FIFO_FULL_INT_EN,
+	/* Generic interrupt 2 */
+	BMA400_GEN2_INT_EN,
+	/* Generic interrupt 1 */
+	BMA400_GEN1_INT_EN,
+	/* Orient change interrupt */
+	BMA400_ORIENT_CHANGE_INT_EN,
+	/* Latch interrupt */
+	BMA400_LATCH_INT_EN,
+	/* Activity change interrupt */
+	BMA400_ACTIVITY_CHANGE_INT_EN,
+	/* Double tap interrupt */
+	BMA400_DOUBLE_TAP_INT_EN,
+	/* Single tap interrupt */
+	BMA400_SINGLE_TAP_INT_EN,
+	/* Step interrupt */
+	BMA400_STEP_COUNTER_INT_EN,
+	/* Auto wakeup interrupt */
+	BMA400_AUTO_WAKEUP_EN
+};
+/*!
+ * @brief Interrupt enable/disable configurations
+ */
+struct bma400_int_enable {
+	/*! Enum to choose the interrupt to be enabled */
+	enum bma400_int_type type;
+	/*! Enable/ disable selected interrupts
+	 * Assignable Macros :
+	 *   - BMA400_ENABLE
+	 *   - BMA400_DISABLE
+	 */
+	uint8_t conf;
+};
+struct bma400_fifo_data {
+	/*! Data buffer of user defined length is to be mapped here */
+	uint8_t *data;
+	/*! While calling the API  "bma400_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;
+	/*! FIFO 8bit mode enable */
+	uint8_t fifo_8_bit_en;
+	/*! Streaming of the Accelerometer data for selected x,y,z axes
+	 *   - BMA400_FIFO_X_EN
+	 *   - BMA400_FIFO_Y_EN
+	 *   - BMA400_FIFO_Z_EN
+	 */
+	uint8_t fifo_data_enable;
+	/*! Will be equal to length when no more frames are there to parse */
+	uint16_t accel_byte_start_idx;
+	/*! It stores the value of configuration changes
+	 * in sensor during FIFO read */
+	uint8_t conf_change;
+	/*! Value of FIFO sensor time time */
+	uint32_t fifo_sensor_time;
+};
+/*!
+ * @brief bma400 device structure
+ */
+struct bma400_dev {
+	/*! Chip Id */
+	uint8_t chip_id;
+	/*! Device Id */
+	uint8_t dev_id;
+	/*! SPI/I2C Interface selection */
+	enum bma400_intf intf;
+	/*! Interface handle pointer */
+	void *intf_ptr;
+	/*! Decide SPI or I2C read mechanism */
+	uint8_t dummy_byte;
+	/*! Bus read function pointer */
+	bma400_com_fptr_t read;
+	/*! Bus write function pointer */
+	bma400_com_fptr_t write;
+	/*! delay(in ms) function pointer */
+	bma400_delay_fptr_t delay_ms;
+};
+
+#endif /* BMA400_DEFS_H_ */
+/** @}*/
+/** @}*/
diff --git a/lib/bosch/BMA400-API/examples/accelerometer.c b/lib/bosch/BMA400-API/examples/accelerometer.c
new file mode 100644
index 0000000000000000000000000000000000000000..e76bb6c8365e66ccb017baf3487db424aa604ec7
--- /dev/null
+++ b/lib/bosch/BMA400-API/examples/accelerometer.c
@@ -0,0 +1,163 @@
+#include <stdio.h>
+#include "bma400.h"
+
+#define GRAVITY_EARTH (9.80665f) /* Earth's gravity in m/s^2 */
+
+void set_interface(enum bma400_intf intf, struct bma400_dev *dev);
+void delay_ms(uint32_t period);
+int8_t i2c_reg_write(void *intf_ptr, uint8_t i2c_addr, uint8_t reg_addr, uint8_t *reg_data, uint16_t length);
+int8_t i2c_reg_read(void *intf_ptr, uint8_t i2c_addr, uint8_t reg_addr, uint8_t *reg_data, uint16_t length);
+int8_t spi_reg_write(void *intf_ptr, uint8_t cs, uint8_t reg_addr, uint8_t *reg_data, uint16_t length);
+int8_t spi_reg_read(void *intf_ptr, uint8_t cs, uint8_t reg_addr, uint8_t *reg_data, uint16_t length);
+void print_rslt(int8_t rslt);
+float lsb_to_ms2(int16_t val, float g_range, uint8_t bit_width);
+float sensor_ticks_to_s(uint32_t sensor_time);
+
+int main(int argc, char const *argv[])
+{
+	struct bma400_dev bma;
+	struct bma400_sensor_conf conf;
+	struct bma400_sensor_data data;
+	int8_t rslt;
+	uint8_t n_samples = 200;
+	float t, x, y, z;
+
+	set_interface(BMA400_SPI_INTF, &bma);
+
+	rslt = bma400_init(&bma);
+	print_rslt(rslt);
+
+	rslt = bma400_soft_reset(&bma);
+	print_rslt(rslt);
+
+	/* Select the type of configuration to be modified */
+	conf.type = BMA400_ACCEL;
+
+	/* Get the accelerometer configurations which are set in the sensor */
+	rslt = bma400_get_sensor_conf(&conf, 1, &bma);
+	print_rslt(rslt);
+
+	/* Modify the desired configurations as per macros
+	 * available in bma400_defs.h file */
+	conf.param.accel.odr = BMA400_ODR_100HZ;
+	conf.param.accel.range = BMA400_2G_RANGE;
+	conf.param.accel.data_src = BMA400_DATA_SRC_ACCEL_FILT_1;
+
+	/* Set the desired configurations to the sensor */
+	rslt = bma400_set_sensor_conf(&conf, 1, &bma);
+	print_rslt(rslt);
+
+	rslt = bma400_set_power_mode(BMA400_LOW_POWER_MODE, &bma);
+	print_rslt(rslt);
+
+	printf("t[s], Ax[m/s2], Ay[m/s2], Az[m/s2]\r\n");
+
+	while (n_samples && (rslt == BMA400_OK)) {
+		bma.delay_ms(10); /* Wait for 10ms as ODR is set to 100Hz */
+
+		rslt = bma400_get_accel_data(BMA400_DATA_SENSOR_TIME, &data, &bma);
+		print_rslt(rslt);
+
+		/* 12-bit accelerometer at range 2G */
+		x = lsb_to_ms2(data.x, 2, 12);
+		y = lsb_to_ms2(data.y, 2, 12);
+		z = lsb_to_ms2(data.z, 2, 12);
+		t = sensor_ticks_to_s(data.sensortime);
+
+		printf("%.4f, %.2f, %.2f, %.2f\r\n", t, x, y, z);
+		n_samples--;
+	}
+
+	return 0;
+}
+
+void set_interface(enum bma400_intf intf, struct bma400_dev *dev)
+{
+	switch (intf) {
+	case BMA400_I2C_INTF:
+		dev->intf_ptr = NULL; /* To attach your interface device reference */
+		dev->delay_ms = delay_ms;
+		dev->dev_id = BMA400_I2C_ADDRESS_SDO_LOW;
+		dev->read = i2c_reg_read;
+		dev->write = i2c_reg_write;
+		dev->intf = BMA400_I2C_INTF;
+		break;
+	case BMA400_SPI_INTF:
+		dev->intf_ptr = NULL; /* To attach your interface device reference */
+		dev->dev_id = 0; /* Could be used to identify the chip select line. */
+		dev->read = spi_reg_read;
+		dev->write = spi_reg_write;
+		dev->intf = BMA400_SPI_INTF;
+		break;
+	default:
+		printf("Interface not supported.\r\n");
+	}
+}
+
+void delay_ms(uint32_t period)
+{
+	/* Wait for a period amount of ms*/
+}
+
+int8_t i2c_reg_write(void *intf_ptr, uint8_t i2c_addr, uint8_t reg_addr, uint8_t *reg_data, uint16_t length)
+{
+	/* Write to registers using I2C. Return 0 for a successful execution. */
+	return -1;
+}
+
+int8_t i2c_reg_read(void *intf_ptr, uint8_t i2c_addr, uint8_t reg_addr, uint8_t *reg_data, uint16_t length)
+{
+	/* Read from registers using I2C. Return 0 for a successful execution. */
+	return -1;
+}
+
+int8_t spi_reg_write(void *intf_ptr, uint8_t cs, uint8_t reg_addr, uint8_t *reg_data, uint16_t length)
+{
+	/* Write to registers using SPI. Return 0 for a successful execution. */
+	return -1;
+}
+
+int8_t spi_reg_read(void *intf_ptr, uint8_t cs, uint8_t reg_addr, uint8_t *reg_data, uint16_t length)
+{
+	/* Read from registers using SPI. Return 0 for a successful execution. */
+	return -1;
+}
+
+void print_rslt(int8_t rslt)
+{
+	switch (rslt) {
+	case BMA400_OK:
+		/* Do nothing */
+		break;
+	case BMA400_E_NULL_PTR:
+		printf("Error [%d] : Null pointer\r\n", rslt);
+		break;
+	case BMA400_E_COM_FAIL:
+		printf("Error [%d] : Communication failure\r\n", rslt);
+		break;
+	case BMA400_E_DEV_NOT_FOUND:
+		printf("Error [%d] : Device not found\r\n", rslt);
+		break;
+	case BMA400_E_INVALID_CONFIG:
+		printf("Error [%d] : Invalid configuration\r\n", rslt);
+		break;
+	case BMA400_W_SELF_TEST_FAIL:
+		printf("Warning [%d] : Self test failed\r\n", rslt);
+		break;
+	default:
+		printf("Error [%d] : Unknown error code\r\n", rslt);
+		break;
+	}
+}
+
+float lsb_to_ms2(int16_t val, float g_range, uint8_t bit_width)
+{
+	float half_scale = (float)(1 << bit_width) / 2.0f;
+
+	return GRAVITY_EARTH * val * g_range / half_scale;
+}
+
+float sensor_ticks_to_s(uint32_t sensor_time)
+{
+	return (float)sensor_time * 0.0000390625f;
+}
diff --git a/lib/bosch/BMA400-API/examples/basic.c b/lib/bosch/BMA400-API/examples/basic.c
new file mode 100644
index 0000000000000000000000000000000000000000..d01fd82fb54453704cb5844913660389d260fe68
--- /dev/null
+++ b/lib/bosch/BMA400-API/examples/basic.c
@@ -0,0 +1,106 @@
+#include <stdio.h>
+#include "bma400.h"
+
+void set_interface(enum bma400_intf intf, struct bma400_dev *dev);
+void delay_ms(uint32_t period);
+int8_t i2c_reg_write(void *intf_ptr, uint8_t i2c_addr, uint8_t reg_addr, uint8_t *reg_data, uint16_t length);
+int8_t i2c_reg_read(void *intf_ptr, uint8_t i2c_addr, uint8_t reg_addr, uint8_t *reg_data, uint16_t length);
+int8_t spi_reg_write(void *intf_ptr, uint8_t cs, uint8_t reg_addr, uint8_t *reg_data, uint16_t length);
+int8_t spi_reg_read(void *intf_ptr, uint8_t cs, uint8_t reg_addr, uint8_t *reg_data, uint16_t length);
+void print_rslt(int8_t rslt);
+
+int main(int argc, char const *argv[])
+{
+	struct bma400_dev bma;
+	int8_t rslt;
+
+	set_interface(BMA400_SPI_INTF, &bma);
+
+	rslt = bma400_init(&bma);
+	print_rslt(rslt);
+
+	if (rslt == BMA400_OK) {
+		printf("BMA400 found with chip ID 0x%X\r\n", bma.chip_id);
+	}
+
+	return 0;
+}
+
+void set_interface(enum bma400_intf intf, struct bma400_dev *dev)
+{
+	switch (intf) {
+	case BMA400_I2C_INTF:
+		dev->intf_ptr = NULL; /* To attach your interface device reference */
+		dev->delay_ms = delay_ms;
+		dev->dev_id = BMA400_I2C_ADDRESS_SDO_LOW;
+		dev->read = i2c_reg_read;
+		dev->write = i2c_reg_write;
+		dev->intf = BMA400_I2C_INTF;
+		break;
+	case BMA400_SPI_INTF:
+		dev->intf_ptr = NULL; /* To attach your interface device reference */
+		dev->dev_id = 0; /* Could be used to identify the chip select line. */
+		dev->read = spi_reg_read;
+		dev->write = spi_reg_write;
+		dev->intf = BMA400_SPI_INTF;
+		break;
+	default:
+		printf("Interface not supported.\r\n");
+	}
+}
+
+void delay_ms(uint32_t period)
+{
+	/* Wait for a period amount of ms*/
+}
+
+int8_t i2c_reg_write(void *intf_ptr, uint8_t i2c_addr, uint8_t reg_addr, uint8_t *reg_data, uint16_t length)
+{
+	/* Write to registers using I2C. Return 0 for a successful execution. */
+	return -1;
+}
+
+int8_t i2c_reg_read(void *intf_ptr, uint8_t i2c_addr, uint8_t reg_addr, uint8_t *reg_data, uint16_t length)
+{
+	/* Read from registers using I2C. Return 0 for a successful execution. */
+	return -1;
+}
+
+int8_t spi_reg_write(void *intf_ptr, uint8_t cs, uint8_t reg_addr, uint8_t *reg_data, uint16_t length)
+{
+	/* Write to registers using SPI. Return 0 for a successful execution. */
+	return -1;
+}
+
+int8_t spi_reg_read(void *intf_ptr, uint8_t cs, uint8_t reg_addr, uint8_t *reg_data, uint16_t length)
+{
+	/* Read from registers using SPI. Return 0 for a successful execution. */
+	return -1;
+}
+
+void print_rslt(int8_t rslt)
+{
+	switch (rslt) {
+	case BMA400_OK:
+		/* Do nothing */
+		break;
+	case BMA400_E_NULL_PTR:
+		printf("Error [%d] : Null pointer\r\n", rslt);
+		break;
+	case BMA400_E_COM_FAIL:
+		printf("Error [%d] : Communication failure\r\n", rslt);
+		break;
+	case BMA400_E_DEV_NOT_FOUND:
+		printf("Error [%d] : Device not found\r\n", rslt);
+		break;
+	case BMA400_E_INVALID_CONFIG:
+		printf("Error [%d] : Invalid configuration\r\n", rslt);
+		break;
+	case BMA400_W_SELF_TEST_FAIL:
+		printf("Warning [%d] : Self test failed\r\n", rslt);
+		break;
+	default:
+		printf("Error [%d] : Unknown error code\r\n", rslt);
+		break;
+	}
+}
diff --git a/lib/bosch/BMA400-API/examples/fifo.c b/lib/bosch/BMA400-API/examples/fifo.c
new file mode 100644
index 0000000000000000000000000000000000000000..18f5249af8d349dd379660ec47254a7e6bd935fb
--- /dev/null
+++ b/lib/bosch/BMA400-API/examples/fifo.c
@@ -0,0 +1,246 @@
+#include <stdio.h>
+#include "bma400.h"
+
+#define GRAVITY_EARTH (9.80665f) /* Earth's gravity in m/s^2 */
+
+/* Include 2 additional frames to account for
+ * the next frame already being in the FIFO
+ * and the sensor time frame
+ */
+#define N_FRAMES        50
+/* 50 Frames result in 50*7, 350 bytes.
+ * A few extra for the sensor time frame and
+ * in case the next frame is available too.
+ */
+#define FIFO_SIZE       (357 + BMA400_FIFO_BYTES_OVERREAD)
+/* Delay to fill FIFO data At ODR of say 100 Hz,
+ * 1 frame gets updated in 1/100 = 0.01s i.e. for
+ * 50 frames we need 50 * 0.01 =  0.5 seconds delay
+ */
+#define WAIT_PERIOD_MS  500
+
+void set_interface(enum bma400_intf intf, struct bma400_dev *dev);
+void delay_ms(uint32_t period);
+int8_t i2c_reg_write(void *intf_ptr, uint8_t i2c_addr, uint8_t reg_addr, uint8_t *reg_data, uint16_t length);
+int8_t i2c_reg_read(void *intf_ptr, uint8_t i2c_addr, uint8_t reg_addr, uint8_t *reg_data, uint16_t length);
+int8_t spi_reg_write(void *intf_ptr, uint8_t cs, uint8_t reg_addr, uint8_t *reg_data, uint16_t length);
+int8_t spi_reg_read(void *intf_ptr, uint8_t cs, uint8_t reg_addr, uint8_t *reg_data, uint16_t length);
+void print_rslt(int8_t rslt);
+float lsb_to_ms2(int16_t val, float g_range, uint8_t bit_width);
+float sensor_ticks_to_s(uint32_t sensor_time);
+
+int main(int argc, char const *argv[])
+{
+	struct bma400_dev bma;
+	struct bma400_sensor_data accel_data[N_FRAMES] = { 0 };
+	struct bma400_fifo_data fifo_frame;
+	struct bma400_device_conf fifo_conf;
+	struct bma400_sensor_conf conf;
+	int8_t rslt;
+	uint16_t i;
+	uint8_t fifo_buff[FIFO_SIZE] = { 0 };
+	uint16_t accel_frames_req = N_FRAMES;
+	float x, y, z, t;
+	uint8_t n = 20; /* Read the FIFO 20 times */
+
+	set_interface(BMA400_SPI_INTF, &bma);
+
+	rslt = bma400_init(&bma);
+	print_rslt(rslt);
+
+	rslt = bma400_soft_reset(&bma);
+	print_rslt(rslt);
+
+	/* Select the type of configuration to be modified */
+	conf.type = BMA400_ACCEL;
+
+	/* Get the accelerometer configurations which are set in the sensor */
+	rslt = bma400_get_sensor_conf(&conf, 1, &bma);
+	print_rslt(rslt);
+
+	/* Modify the desired configurations as per macros
+	 * available in bma400_defs.h file */
+	conf.param.accel.odr = BMA400_ODR_100HZ;
+	conf.param.accel.range = BMA400_2G_RANGE;
+	conf.param.accel.data_src = BMA400_DATA_SRC_ACCEL_FILT_1;
+
+	/* Set the desired configurations to the sensor */
+	rslt = bma400_set_sensor_conf(&conf, 1, &bma);
+	print_rslt(rslt);
+
+	fifo_conf.type = BMA400_FIFO_CONF;
+
+	rslt = bma400_get_device_conf(&fifo_conf, 1, &bma);
+	print_rslt(rslt);
+
+	fifo_conf.param.fifo_conf.conf_regs = BMA400_FIFO_X_EN | BMA400_FIFO_Y_EN | BMA400_FIFO_Z_EN
+					      | BMA400_FIFO_TIME_EN;
+	fifo_conf.param.fifo_conf.conf_status = BMA400_ENABLE;
+
+	rslt = bma400_set_device_conf(&fifo_conf, 1, &bma);
+	print_rslt(rslt);
+
+	rslt = bma400_set_power_mode(BMA400_NORMAL_MODE, &bma);
+	print_rslt(rslt);
+
+	while ((rslt == BMA400_OK) && n) {
+		fifo_frame.data = fifo_buff;
+		fifo_frame.length = FIFO_SIZE;
+		bma.delay_ms(WAIT_PERIOD_MS);
+
+		printf("Requested FIFO length : %d\r\n", fifo_frame.length);
+
+		rslt = bma400_get_fifo_data(&fifo_frame, &bma);
+		print_rslt(rslt);
+
+		if (rslt != BMA400_OK) {
+			printf("FIFO read failed\r\n");
+		}
+
+		printf("Available FIFO length : %d \r\n", fifo_frame.length);
+
+		do {
+			accel_frames_req = N_FRAMES;
+			rslt = bma400_extract_accel(&fifo_frame, accel_data, &accel_frames_req, &bma);
+			print_rslt(rslt);
+
+			if (rslt != BMA400_OK) {
+				printf("Accelerometer data extraction failed\r\n");
+			}
+
+			if (accel_frames_req) {
+				printf("Extracted FIFO frames : %d \r\n", accel_frames_req);
+
+				printf("Frame index, Ax[m/s2], Ay[m/s2], Az[m/s2]\r\n");
+				for (i = 0; i < accel_frames_req; i++) {
+					bma.delay_ms(10); /* Wait for 10ms as ODR is set to 100Hz */
+
+					/* 12-bit accelerometer at range 2G */
+					x = lsb_to_ms2(accel_data[i].x, 2, 12);
+					y = lsb_to_ms2(accel_data[i].y, 2, 12);
+					z = lsb_to_ms2(accel_data[i].z, 2, 12);
+
+					printf("%d, %.2f, %.2f, %.2f\r\n", i, x, y, z);
+				}
+			}
+		} while (accel_frames_req);
+
+		if(fifo_frame.fifo_sensor_time) {
+			t = sensor_ticks_to_s(fifo_frame.fifo_sensor_time);
+
+			printf("FIFO sensor time : %.4fs\r\n", t);
+		}
+		
+		if(fifo_frame.conf_change) {
+			printf("FIFO configuration change: 0x%X\r\n", fifo_frame.conf_change);
+
+			if (fifo_frame.conf_change & BMA400_FIFO_CONF0_CHANGE) {
+				printf("FIFO data source configuration changed \r\n");
+			}
+
+			if (fifo_frame.conf_change & BMA400_ACCEL_CONF0_CHANGE) {
+				printf("Accel filt1_bw configuration changed \r\n");
+			}
+
+			if (fifo_frame.conf_change & BMA400_ACCEL_CONF1_CHANGE) {
+				printf("Accel odr/osr/range configuration changed \r\n");
+			}
+		}
+
+		n--;
+	}
+
+	return 0;
+}
+
+void set_interface(enum bma400_intf intf, struct bma400_dev *dev)
+{
+	switch (intf) {
+	case BMA400_I2C_INTF:
+		dev->intf_ptr = NULL; /* To attach your interface device reference */
+		dev->delay_ms = delay_ms;
+		dev->dev_id = BMA400_I2C_ADDRESS_SDO_LOW;
+		dev->read = i2c_reg_read;
+		dev->write = i2c_reg_write;
+		dev->intf = BMA400_I2C_INTF;
+		break;
+	case BMA400_SPI_INTF:
+		dev->intf_ptr = NULL; /* To attach your interface device reference */
+		dev->dev_id = 0; /* Could be used to identify the chip select line. */
+		dev->read = spi_reg_read;
+		dev->write = spi_reg_write;
+		dev->intf = BMA400_SPI_INTF;
+		break;
+	default:
+		printf("Interface not supported.\r\n");
+	}
+}
+
+void delay_ms(uint32_t period)
+{
+	/* Wait for a period amount of ms*/
+}
+
+int8_t i2c_reg_write(void *intf_ptr, uint8_t i2c_addr, uint8_t reg_addr, uint8_t *reg_data, uint16_t length)
+{
+	/* Write to registers using I2C. Return 0 for a successful execution. */
+	return -1;
+}
+
+int8_t i2c_reg_read(void *intf_ptr, uint8_t i2c_addr, uint8_t reg_addr, uint8_t *reg_data, uint16_t length)
+{
+	/* Read from registers using I2C. Return 0 for a successful execution. */
+	return -1;
+}
+
+int8_t spi_reg_write(void *intf_ptr, uint8_t cs, uint8_t reg_addr, uint8_t *reg_data, uint16_t length)
+{
+	/* Write to registers using SPI. Return 0 for a successful execution. */
+	return -1;
+}
+
+int8_t spi_reg_read(void *intf_ptr, uint8_t cs, uint8_t reg_addr, uint8_t *reg_data, uint16_t length)
+{
+	/* Read from registers using SPI. Return 0 for a successful execution. */
+	return -1;
+}
+
+void print_rslt(int8_t rslt)
+{
+	switch (rslt) {
+	case BMA400_OK:
+		/* Do nothing */
+		break;
+	case BMA400_E_NULL_PTR:
+		printf("Error [%d] : Null pointer\r\n", rslt);
+		break;
+	case BMA400_E_COM_FAIL:
+		printf("Error [%d] : Communication failure\r\n", rslt);
+		break;
+	case BMA400_E_DEV_NOT_FOUND:
+		printf("Error [%d] : Device not found\r\n", rslt);
+		break;
+	case BMA400_E_INVALID_CONFIG:
+		printf("Error [%d] : Invalid configuration\r\n", rslt);
+		break;
+	case BMA400_W_SELF_TEST_FAIL:
+		printf("Warning [%d] : Self test failed\r\n", rslt);
+		break;
+	default:
+		printf("Error [%d] : Unknown error code\r\n", rslt);
+		break;
+	}
+}
+
+float lsb_to_ms2(int16_t val, float g_range, uint8_t bit_width)
+{
+	float half_scale = (float)(1 << bit_width) / 2.0f;
+
+	return GRAVITY_EARTH * val * g_range / half_scale;
+}
+
+float sensor_ticks_to_s(uint32_t sensor_time)
+{
+	return (float)sensor_time * 0.0000390625f;
+}
+
diff --git a/lib/bosch/BMA400-API/examples/self_test.c b/lib/bosch/BMA400-API/examples/self_test.c
new file mode 100644
index 0000000000000000000000000000000000000000..2908c735950d268521185424cc1fe3337bf69bb7
--- /dev/null
+++ b/lib/bosch/BMA400-API/examples/self_test.c
@@ -0,0 +1,112 @@
+#include <stdio.h>
+#include "bma400.h"
+
+void set_interface(enum bma400_intf intf, struct bma400_dev *dev);
+void delay_ms(uint32_t period);
+int8_t i2c_reg_write(void *intf_ptr, uint8_t i2c_addr, uint8_t reg_addr, uint8_t *reg_data, uint16_t length);
+int8_t i2c_reg_read(void *intf_ptr, uint8_t i2c_addr, uint8_t reg_addr, uint8_t *reg_data, uint16_t length);
+int8_t spi_reg_write(void *intf_ptr, uint8_t cs, uint8_t reg_addr, uint8_t *reg_data, uint16_t length);
+int8_t spi_reg_read(void *intf_ptr, uint8_t cs, uint8_t reg_addr, uint8_t *reg_data, uint16_t length);
+void print_rslt(int8_t rslt);
+
+int main(int argc, char const *argv[])
+{
+	struct bma400_dev bma;
+	int8_t rslt;
+
+	set_interface(BMA400_SPI_INTF, &bma);
+
+	rslt = bma400_init(&bma);
+	print_rslt(rslt);
+
+	rslt = bma400_soft_reset(&bma);
+	print_rslt(rslt);
+
+	rslt = bma400_perform_self_test(&bma);
+	print_rslt(rslt);
+
+	if (rslt == BMA400_OK) {
+		printf("Self test passed.\r\n");
+	}
+
+	return 0;
+}
+
+void set_interface(enum bma400_intf intf, struct bma400_dev *dev)
+{
+	switch (intf) {
+	case BMA400_I2C_INTF:
+		dev->intf_ptr = NULL; /* To attach your interface device reference */
+		dev->delay_ms = delay_ms;
+		dev->dev_id = BMA400_I2C_ADDRESS_SDO_LOW;
+		dev->read = i2c_reg_read;
+		dev->write = i2c_reg_write;
+		dev->intf = BMA400_I2C_INTF;
+		break;
+	case BMA400_SPI_INTF:
+		dev->intf_ptr = NULL; /* To attach your interface device reference */
+		dev->dev_id = 0; /* Could be used to identify the chip select line. */
+		dev->read = spi_reg_read;
+		dev->write = spi_reg_write;
+		dev->intf = BMA400_SPI_INTF;
+		break;
+	default:
+		printf("Interface not supported.\r\n");
+	}
+}
+
+void delay_ms(uint32_t period)
+{
+	/* Wait for a period amount of ms*/
+}
+
+int8_t i2c_reg_write(void *intf_ptr, uint8_t i2c_addr, uint8_t reg_addr, uint8_t *reg_data, uint16_t length)
+{
+	/* Write to registers using I2C. Return 0 for a successful execution. */
+	return -1;
+}
+
+int8_t i2c_reg_read(void *intf_ptr, uint8_t i2c_addr, uint8_t reg_addr, uint8_t *reg_data, uint16_t length)
+{
+	/* Read from registers using I2C. Return 0 for a successful execution. */
+	return -1;
+}
+
+int8_t spi_reg_write(void *intf_ptr, uint8_t cs, uint8_t reg_addr, uint8_t *reg_data, uint16_t length)
+{
+	/* Write to registers using SPI. Return 0 for a successful execution. */
+	return -1;
+}
+
+int8_t spi_reg_read(void *intf_ptr, uint8_t cs, uint8_t reg_addr, uint8_t *reg_data, uint16_t length)
+{
+	/* Read from registers using SPI. Return 0 for a successful execution. */
+	return -1;
+}
+
+void print_rslt(int8_t rslt)
+{
+	switch (rslt) {
+	case BMA400_OK:
+		/* Do nothing */
+		break;
+	case BMA400_E_NULL_PTR:
+		printf("Error [%d] : Null pointer\r\n", rslt);
+		break;
+	case BMA400_E_COM_FAIL:
+		printf("Error [%d] : Communication failure\r\n", rslt);
+		break;
+	case BMA400_E_DEV_NOT_FOUND:
+		printf("Error [%d] : Device not found\r\n", rslt);
+		break;
+	case BMA400_E_INVALID_CONFIG:
+		printf("Error [%d] : Invalid configuration\r\n", rslt);
+		break;
+	case BMA400_W_SELF_TEST_FAIL:
+		printf("Warning [%d] : Self test failed\r\n", rslt);
+		break;
+	default:
+		printf("Error [%d] : Unknown error code\r\n", rslt);
+		break;
+	}
+}
diff --git a/lib/bosch/BMA400-API/examples/step_counter.c b/lib/bosch/BMA400-API/examples/step_counter.c
new file mode 100644
index 0000000000000000000000000000000000000000..59a4307e57264d8436da22d39e9abc145cbbc210
--- /dev/null
+++ b/lib/bosch/BMA400-API/examples/step_counter.c
@@ -0,0 +1,144 @@
+#include <stdio.h>
+#include "bma400.h"
+
+void set_interface(enum bma400_intf intf, struct bma400_dev *dev);
+void delay_ms(uint32_t period);
+int8_t i2c_reg_write(void *intf_ptr, uint8_t i2c_addr, uint8_t reg_addr, uint8_t *reg_data, uint16_t length);
+int8_t i2c_reg_read(void *intf_ptr, uint8_t i2c_addr, uint8_t reg_addr, uint8_t *reg_data, uint16_t length);
+int8_t spi_reg_write(void *intf_ptr, uint8_t cs, uint8_t reg_addr, uint8_t *reg_data, uint16_t length);
+int8_t spi_reg_read(void *intf_ptr, uint8_t cs, uint8_t reg_addr, uint8_t *reg_data, uint16_t length);
+void print_rslt(int8_t rslt);
+
+int main(int argc, char const *argv[])
+{
+	struct bma400_dev bma;
+	struct bma400_int_enable step_int;
+	int8_t rslt;
+	uint8_t test_dur = 30;
+	uint32_t step_count;
+	uint8_t activity;
+
+	set_interface(BMA400_SPI_INTF, &bma);
+
+	rslt = bma400_init(&bma);
+	print_rslt(rslt);
+
+	rslt = bma400_soft_reset(&bma);
+	print_rslt(rslt);
+
+	step_int.type = BMA400_STEP_COUNTER_INT_EN;
+	step_int.conf = BMA400_ENABLE;
+
+	rslt = bma400_enable_interrupt(&step_int, 1, &bma);
+	print_rslt(rslt);
+
+	rslt = bma400_set_power_mode(BMA400_NORMAL_MODE, &bma);
+	print_rslt(rslt);
+
+	printf("Steps counted, Activity classifier\r\n");
+
+	while (test_dur) {
+		bma.delay_ms(1000);
+
+		rslt = bma400_get_steps_counted(&step_count, &activity, &bma);
+		printf("%ld", step_count);
+
+		switch (activity) {
+		case BMA400_STILL_ACT:
+			printf(", Still\r\n");
+			break;
+		case BMA400_WALK_ACT:
+			printf(", Walking\r\n");
+			break;
+		case BMA400_RUN_ACT:
+			printf(", Running\r\n");
+			break;
+		default:
+			printf(", undefined\r\n");
+			break;
+		}
+
+		test_dur--;
+	}
+
+	return 0;
+}
+
+void set_interface(enum bma400_intf intf, struct bma400_dev *dev)
+{
+	switch (intf) {
+	case BMA400_I2C_INTF:
+		dev->intf_ptr = NULL; /* To attach your interface device reference */
+		dev->delay_ms = delay_ms;
+		dev->dev_id = BMA400_I2C_ADDRESS_SDO_LOW;
+		dev->read = i2c_reg_read;
+		dev->write = i2c_reg_write;
+		dev->intf = BMA400_I2C_INTF;
+		break;
+	case BMA400_SPI_INTF:
+		dev->intf_ptr = NULL; /* To attach your interface device reference */
+		dev->dev_id = 0; /* Could be used to identify the chip select line. */
+		dev->read = spi_reg_read;
+		dev->write = spi_reg_write;
+		dev->intf = BMA400_SPI_INTF;
+		break;
+	default:
+		printf("Interface not supported.\r\n");
+	}
+}
+
+void delay_ms(uint32_t period)
+{
+	/* Wait for a period amount of ms*/
+}
+
+int8_t i2c_reg_write(void *intf_ptr, uint8_t i2c_addr, uint8_t reg_addr, uint8_t *reg_data, uint16_t length)
+{
+	/* Write to registers using I2C. Return 0 for a successful execution. */
+	return -1;
+}
+
+int8_t i2c_reg_read(void *intf_ptr, uint8_t i2c_addr, uint8_t reg_addr, uint8_t *reg_data, uint16_t length)
+{
+	/* Read from registers using I2C. Return 0 for a successful execution. */
+	return -1;
+}
+
+int8_t spi_reg_write(void *intf_ptr, uint8_t cs, uint8_t reg_addr, uint8_t *reg_data, uint16_t length)
+{
+	/* Write to registers using SPI. Return 0 for a successful execution. */
+	return -1;
+}
+
+int8_t spi_reg_read(void *intf_ptr, uint8_t cs, uint8_t reg_addr, uint8_t *reg_data, uint16_t length)
+{
+	/* Read from registers using SPI. Return 0 for a successful execution. */
+	return -1;
+}
+
+void print_rslt(int8_t rslt)
+{
+	switch (rslt) {
+	case BMA400_OK:
+		/* Do nothing */
+		break;
+	case BMA400_E_NULL_PTR:
+		printf("Error [%d] : Null pointer\r\n", rslt);
+		break;
+	case BMA400_E_COM_FAIL:
+		printf("Error [%d] : Communication failure\r\n", rslt);
+		break;
+	case BMA400_E_DEV_NOT_FOUND:
+		printf("Error [%d] : Device not found\r\n", rslt);
+		break;
+	case BMA400_E_INVALID_CONFIG:
+		printf("Error [%d] : Invalid configuration\r\n", rslt);
+		break;
+	case BMA400_W_SELF_TEST_FAIL:
+		printf("Warning [%d] : Self test failed\r\n", rslt);
+		break;
+	default:
+		printf("Error [%d] : Unknown error code\r\n", rslt);
+		break;
+	}
+}
diff --git a/lib/bosch/BMA400-API/examples/tap_detection.c b/lib/bosch/BMA400-API/examples/tap_detection.c
new file mode 100644
index 0000000000000000000000000000000000000000..7babf4046a789b00c7696b9ae75941a387b4449a
--- /dev/null
+++ b/lib/bosch/BMA400-API/examples/tap_detection.c
@@ -0,0 +1,167 @@
+#include <stdio.h>
+#include "bma400.h"
+
+void set_interface(enum bma400_intf intf, struct bma400_dev *dev);
+void delay_ms(uint32_t period);
+int8_t i2c_reg_write(void *intf_ptr, uint8_t i2c_addr, uint8_t reg_addr, uint8_t *reg_data, uint16_t length);
+int8_t i2c_reg_read(void *intf_ptr, uint8_t i2c_addr, uint8_t reg_addr, uint8_t *reg_data, uint16_t length);
+int8_t spi_reg_write(void *intf_ptr, uint8_t cs, uint8_t reg_addr, uint8_t *reg_data, uint16_t length);
+int8_t spi_reg_read(void *intf_ptr, uint8_t cs, uint8_t reg_addr, uint8_t *reg_data, uint16_t length);
+void print_rslt(int8_t rslt);
+
+int main(int argc, char const *argv[])
+{
+	struct bma400_dev bma;
+	struct bma400_int_enable tap_int[2];
+	struct bma400_sensor_conf conf[2];
+	int8_t rslt;
+	uint32_t poll_period = 5, test_dur_ms = 30000;
+	uint16_t int_status;
+
+	set_interface(BMA400_SPI_INTF, &bma);
+
+	rslt = bma400_init(&bma);
+	print_rslt(rslt);
+
+	rslt = bma400_soft_reset(&bma);
+	print_rslt(rslt);
+
+	conf[0].type = BMA400_ACCEL;
+	conf[1].type = BMA400_TAP_INT;
+
+	rslt = bma400_get_sensor_conf(conf, 2, &bma);
+	print_rslt(rslt);
+
+	conf[0].param.accel.odr = BMA400_ODR_200HZ;
+	conf[0].param.accel.range = BMA400_4G_RANGE;
+	conf[0].param.accel.data_src = BMA400_DATA_SRC_ACCEL_FILT_1;
+	conf[0].param.accel.filt1_bw = BMA400_ACCEL_FILT1_BW_1;
+
+	conf[1].param.tap.int_chan = BMA400_UNMAP_INT_PIN;
+	conf[1].param.tap.axes_sel = BMA400_Z_AXIS_EN_TAP;
+	conf[1].param.tap.sensitivity = BMA400_TAP_SENSITIVITY_0;
+
+	rslt = bma400_set_sensor_conf(conf, 2, &bma);
+	print_rslt(rslt);
+
+	bma.delay_ms(100);
+
+	tap_int[0].type = BMA400_SINGLE_TAP_INT_EN;
+	tap_int[0].conf = BMA400_ENABLE;
+
+	tap_int[1].type = BMA400_DOUBLE_TAP_INT_EN;
+	tap_int[1].conf = BMA400_ENABLE;
+
+	rslt = bma400_enable_interrupt(tap_int, 2, &bma);
+	print_rslt(rslt);
+
+	bma.delay_ms(100);
+
+	rslt = bma400_set_power_mode(BMA400_NORMAL_MODE, &bma);
+	print_rslt(rslt);
+
+	bma.delay_ms(100);
+
+	if (rslt == BMA400_OK) {
+		printf("Tap configured.\r\n");
+
+		while (test_dur_ms) {
+			bma.delay_ms(poll_period);
+
+			rslt = bma400_get_interrupt_status(&int_status, &bma);
+			print_rslt(rslt);
+
+			if (int_status & BMA400_S_TAP_INT_ASSERTED) {
+				printf("Single tap detected!\r\n");
+			}
+
+			if (int_status & BMA400_D_TAP_INT_ASSERTED) {
+				printf("Double tap detected!\r\n");
+			}
+
+			test_dur_ms -= poll_period;
+		}
+
+	}
+
+	return 0;
+}
+
+void set_interface(enum bma400_intf intf, struct bma400_dev *dev)
+{
+	switch (intf) {
+	case BMA400_I2C_INTF:
+		dev->intf_ptr = NULL; /* To attach your interface device reference */
+		dev->delay_ms = delay_ms;
+		dev->dev_id = BMA400_I2C_ADDRESS_SDO_LOW;
+		dev->read = i2c_reg_read;
+		dev->write = i2c_reg_write;
+		dev->intf = BMA400_I2C_INTF;
+		break;
+	case BMA400_SPI_INTF:
+		dev->intf_ptr = NULL; /* To attach your interface device reference */
+		dev->dev_id = 0; /* Could be used to identify the chip select line. */
+		dev->read = spi_reg_read;
+		dev->write = spi_reg_write;
+		dev->intf = BMA400_SPI_INTF;
+		break;
+	default:
+		printf("Interface not supported.\r\n");
+	}
+}
+
+void delay_ms(uint32_t period)
+{
+	/* Wait for a period amount of ms*/
+}
+
+int8_t i2c_reg_write(void *intf_ptr, uint8_t i2c_addr, uint8_t reg_addr, uint8_t *reg_data, uint16_t length)
+{
+	/* Write to registers using I2C. Return 0 for a successful execution. */
+	return -1;
+}
+
+int8_t i2c_reg_read(void *intf_ptr, uint8_t i2c_addr, uint8_t reg_addr, uint8_t *reg_data, uint16_t length)
+{
+	/* Read from registers using I2C. Return 0 for a successful execution. */
+	return -1;
+}
+
+int8_t spi_reg_write(void *intf_ptr, uint8_t cs, uint8_t reg_addr, uint8_t *reg_data, uint16_t length)
+{
+	/* Write to registers using SPI. Return 0 for a successful execution. */
+	return -1;
+}
+
+int8_t spi_reg_read(void *intf_ptr, uint8_t cs, uint8_t reg_addr, uint8_t *reg_data, uint16_t length)
+{
+	/* Read from registers using SPI. Return 0 for a successful execution. */
+	return -1;
+}
+
+void print_rslt(int8_t rslt)
+{
+	switch (rslt) {
+	case BMA400_OK:
+		/* Do nothing */
+		break;
+	case BMA400_E_NULL_PTR:
+		printf("Error [%d] : Null pointer\r\n", rslt);
+		break;
+	case BMA400_E_COM_FAIL:
+		printf("Error [%d] : Communication failure\r\n", rslt);
+		break;
+	case BMA400_E_DEV_NOT_FOUND:
+		printf("Error [%d] : Device not found\r\n", rslt);
+		break;
+	case BMA400_E_INVALID_CONFIG:
+		printf("Error [%d] : Invalid configuration\r\n", rslt);
+		break;
+	case BMA400_W_SELF_TEST_FAIL:
+		printf("Warning [%d] : Self test failed\r\n", rslt);
+		break;
+	default:
+		printf("Error [%d] : Unknown error code\r\n", rslt);
+		break;
+	}
+}
diff --git a/lib/card10/bosch.c b/lib/card10/bosch.c
index 772208dd796c7bda01da008978a98948b4254fd1..95d4719cd58e27fb31599b18e72800698aadd068 100644
--- a/lib/card10/bosch.c
+++ b/lib/card10/bosch.c
@@ -53,3 +53,13 @@ void card10_bosch_delay(uint32_t msec)
 {
     TMR_Delay(MXC_TMR0, MSEC(msec), 0);
 }
+
+int8_t card10_bosch_i2c_write_ex(void *_, uint8_t addr, uint8_t reg, uint8_t *p_buf, uint16_t size)
+{
+    return card10_bosch_i2c_write(addr, reg, p_buf, size);
+}
+
+int8_t card10_bosch_i2c_read_ex(void *_, uint8_t addr, uint8_t reg, uint8_t *p_buf, uint16_t size)
+{
+    return card10_bosch_i2c_read(addr, reg, p_buf, size);
+}
diff --git a/lib/card10/bosch.h b/lib/card10/bosch.h
index b183a85dbd9f1a247d3858948fe1ccb47dd40132..7ece8e156bf15460994c44c67f0ce35772d85cd9 100644
--- a/lib/card10/bosch.h
+++ b/lib/card10/bosch.h
@@ -7,4 +7,6 @@ int8_t card10_bosch_i2c_write(uint8_t addr, uint8_t reg, uint8_t *p_buf, uint16_
 int8_t card10_bosch_i2c_read(uint8_t addr, uint8_t reg, uint8_t *p_buf, uint16_t size);
 void card10_bosch_delay(uint32_t msec);
 
+int8_t card10_bosch_i2c_write_ex(void*, uint8_t addr, uint8_t reg, uint8_t *p_buf, uint16_t size);
+int8_t card10_bosch_i2c_read_ex(void*, uint8_t addr, uint8_t reg, uint8_t *p_buf, uint16_t size);
 #endif