Merge pull request #11270 from haslinghuis/rename_attr
[betaflight.git] / lib / main / BoschSensortec / BMI270-Sensor-API / bmi2_ois.c
blob04350db08d65fbb072f420e024a2603d5a9ac279
1 /**
2 * Copyright (c) 2020 Bosch Sensortec GmbH. All rights reserved.
4 * BSD-3-Clause
6 * Redistribution and use in source and binary forms, with or without
7 * modification, are permitted provided that the following conditions are met:
9 * 1. Redistributions of source code must retain the above copyright
10 * notice, this list of conditions and the following disclaimer.
12 * 2. Redistributions in binary form must reproduce the above copyright
13 * notice, this list of conditions and the following disclaimer in the
14 * documentation and/or other materials provided with the distribution.
16 * 3. Neither the name of the copyright holder nor the names of its
17 * contributors may be used to endorse or promote products derived from
18 * this software without specific prior written permission.
20 * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
21 * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
22 * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
23 * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
24 * COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
25 * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES
26 * (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR
27 * SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION)
28 * HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT,
29 * STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING
30 * IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
31 * POSSIBILITY OF SUCH DAMAGE.
33 * @file bmi2_ois.c
34 * @date 2020-05-05
35 * @version v2.23.2
39 /******************************************************************************/
41 /*! @name Header Files */
42 /******************************************************************************/
43 #include "bmi2_ois.h"
45 /******************************************************************************/
47 /*! Local Function Prototypes
48 ******************************************************************************/
50 /*!
51 * @brief This internal API gets the OIS accelerometer and the gyroscope data.
53 * @param[out] ois_data : Structure instance of bmi2_sens_axes_data.
54 * @param[in] reg_addr : Register address where data is stored.
55 * @param[in] ois_dev : Structure instance of bmi2_ois_dev.
56 * @param[in] ois_gyr_cross_sens_zx :"gyroscope cross sensitivity value which was calculated during
57 * bmi2xy_init(), refer the example ois_accel_gyro.c for more info"
59 * @return Result of API execution status
60 * @retval 0 -> Success
61 * @retval < 0 -> Fail
63 static int8_t get_ois_acc_gyr_data(struct bmi2_ois_sens_axes_data *ois_data,
64 uint8_t reg_addr,
65 struct bmi2_ois_dev *ois_dev,
66 int16_t ois_gyr_cross_sens_zx);
68 /*!
69 * @brief This internal API is used to validate the OIS device pointer for null
70 * conditions.
72 * @param[in] ois_dev : Structure instance of bmi2_ois_dev.
74 * @return Result of API execution status
75 * @retval 0 -> Success
76 * @retval < 0 -> Fail
78 static int8_t null_ptr_check(const struct bmi2_ois_dev *ois_dev);
80 /*!
81 * @brief This internal API corrects the gyroscope cross-axis sensitivity
82 * between the z and the x axis.
84 * @param[in] ois_dev : Structure instance of bmi2_ois_dev.
85 * @param[in] ois_gyr_cross_sens_zx : "gyroscope cross sensitivity value which was calculated during bmi2xy_init(),
86 * refer the example ois_accel_gyro.c for more info"
89 static void comp_gyro_cross_axis_sensitivity(struct bmi2_ois_sens_axes_data *ois_data, int16_t ois_gyr_cross_sens_zx);
91 /******************************************************************************/
92 /*! @name User Interface Definitions */
93 /******************************************************************************/
95 /*!
96 * @brief This API reads the data from the given OIS register address of bmi2
97 * sensor.
99 int8_t bmi2_ois_get_regs(uint8_t ois_reg_addr, uint8_t *ois_reg_data, uint16_t data_len, struct bmi2_ois_dev *ois_dev)
101 /* Variable to define error */
102 int8_t rslt;
104 /* Variable to define dummy byte for SPI read */
105 uint8_t dummy_byte = 1;
107 /* Variable to define temporary length */
108 uint16_t temp_len = data_len + dummy_byte;
110 /* Variable to define temporary buffer */
111 uint8_t temp_buf[temp_len];
113 /* Variable to index bytes read */
114 uint16_t index = 0;
116 /* Null-pointer check */
117 rslt = null_ptr_check(ois_dev);
118 if ((rslt == BMI2_OIS_OK) && (ois_reg_data != NULL))
120 /* Configuring reg_addr for SPI Interface */
121 ois_reg_addr = (ois_reg_addr | BMI2_OIS_SPI_RD_MASK);
123 /* Read from OIS register through OIS interface */
124 ois_dev->intf_rslt = ois_dev->ois_read(ois_reg_addr, temp_buf, temp_len, ois_dev->intf_ptr);
125 if (ois_dev->intf_rslt == BMI2_INTF_RET_SUCCESS)
127 /* Read the data from the position next to dummy byte */
128 while (index < data_len)
130 ois_reg_data[index] = temp_buf[index + dummy_byte];
131 index++;
134 else
136 rslt = BMI2_OIS_E_COM_FAIL;
139 else
141 rslt = BMI2_OIS_E_NULL_PTR;
144 return rslt;
148 * @brief This API writes data to the given OIS register address of bmi2 sensor.
150 int8_t bmi2_ois_set_regs(uint8_t ois_reg_addr,
151 const uint8_t *ois_reg_data,
152 uint16_t data_len,
153 struct bmi2_ois_dev *ois_dev)
155 /* Variable to define error */
156 int8_t rslt;
158 /* Null-pointer check */
159 rslt = null_ptr_check(ois_dev);
160 if ((rslt == BMI2_OIS_OK) && (ois_reg_data != NULL))
162 /* Configuring reg_addr for SPI Interface */
163 ois_reg_addr = (ois_reg_addr & BMI2_OIS_SPI_WR_MASK);
165 /* Burst write to OIS register through OIS interface */
166 ois_dev->intf_rslt = ois_dev->ois_write(ois_reg_addr, ois_reg_data, data_len, ois_dev->intf_ptr);
167 if (ois_dev->intf_rslt != BMI2_INTF_RET_SUCCESS)
169 rslt = BMI2_OIS_E_COM_FAIL;
172 else
174 rslt = BMI2_OIS_E_NULL_PTR;
177 return rslt;
181 * @brief This API enables/disables accelerometer/gyroscope data read through
182 * OIS interface.
184 int8_t bmi2_ois_set_config(struct bmi2_ois_dev *ois_dev)
186 /* Variable to define error */
187 int8_t rslt;
189 /* Variable to store data */
190 uint8_t reg_data = 0;
192 /* Null-pointer check */
193 rslt = null_ptr_check(ois_dev);
194 if (rslt == BMI2_OIS_OK)
196 rslt = bmi2_ois_get_regs(BMI2_OIS_CONFIG_ADDR, &reg_data, 1, ois_dev);
197 if (rslt == BMI2_OIS_OK)
199 /* Enable/Disable Low pass filter */
200 reg_data = BMI2_SET_BIT_POS0(reg_data, BMI2_OIS_LP_FILTER_EN, ois_dev->lp_filter_en);
202 /* Configures Low pass filter cut-off frequency */
203 reg_data = BMI2_OIS_SET_BITS(reg_data, BMI2_OIS_LP_FILTER_CONFIG, ois_dev->lp_filter_config);
205 /* Low pass filter - mute on secondary interface */
206 reg_data = BMI2_OIS_SET_BITS(reg_data, BMI2_OIS_LP_FILTER_MUTE, ois_dev->lp_filter_mute);
208 /* Enable/Disable ois on accelerometer */
209 reg_data = BMI2_OIS_SET_BITS(reg_data, BMI2_OIS_ACC_EN, ois_dev->acc_en);
211 /* Enable/Disable ois on gyroscope */
212 reg_data = BMI2_OIS_SET_BITS(reg_data, BMI2_OIS_GYR_EN, ois_dev->gyr_en);
214 /* Set the OIS configurations */
215 rslt = bmi2_ois_set_regs(BMI2_OIS_CONFIG_ADDR, &reg_data, 1, ois_dev);
219 return rslt;
223 * @brief This API gets the status of accelerometer/gyroscope enable for data
224 * read through OIS interface.
226 int8_t bmi2_ois_get_config(struct bmi2_ois_dev *ois_dev)
228 /* Variable to define error */
229 int8_t rslt;
231 /* Variable to store data */
232 uint8_t reg_data = 0;
234 /* Null-pointer check */
235 rslt = null_ptr_check(ois_dev);
236 if (rslt == BMI2_OIS_OK)
238 rslt = bmi2_ois_get_regs(BMI2_OIS_CONFIG_ADDR, &reg_data, 1, ois_dev);
239 if (rslt == BMI2_OIS_OK)
241 /* Get the status of Low pass filter enable */
242 ois_dev->lp_filter_en = BMI2_GET_BIT_POS0(reg_data, BMI2_OIS_LP_FILTER_EN);
244 /* Get the status of Low pass filter cut-off frequency */
245 ois_dev->lp_filter_config = BMI2_OIS_GET_BITS(reg_data, BMI2_OIS_LP_FILTER_CONFIG);
247 /* Get the status of Low pass filter mute */
248 ois_dev->lp_filter_mute = BMI2_OIS_GET_BITS(reg_data, BMI2_OIS_LP_FILTER_MUTE);
250 /* Get the status of accelerometer enable */
251 ois_dev->acc_en = BMI2_OIS_GET_BITS(reg_data, BMI2_OIS_ACC_EN);
253 /* Get the status of gyroscope enable */
254 ois_dev->gyr_en = BMI2_OIS_GET_BITS(reg_data, BMI2_OIS_GYR_EN);
258 return rslt;
262 * @brief This API reads accelerometer/gyroscope data through OIS interface.
264 int8_t bmi2_ois_read_data(const uint8_t *sens_sel,
265 uint8_t n_sens,
266 struct bmi2_ois_dev *ois_dev,
267 int16_t gyr_cross_sens_zx)
269 /* Variable to define error */
270 int8_t rslt;
272 /* Variable to define loop */
273 uint8_t loop = 0;
275 /* Variable to update register address */
276 uint8_t reg_addr = 0;
278 /* Null-pointer check */
279 rslt = null_ptr_check(ois_dev);
280 if ((rslt == BMI2_OIS_OK) && (sens_sel != NULL))
283 for (loop = 0; loop < n_sens; loop++)
285 switch (sens_sel[loop])
287 case BMI2_OIS_ACCEL:
289 /* Update OIS accelerometer address */
290 reg_addr = BMI2_OIS_ACC_X_LSB_ADDR;
292 /* Get OIS accelerometer data */
293 rslt = get_ois_acc_gyr_data(&ois_dev->acc_data, reg_addr, ois_dev, 0);
294 break;
295 case BMI2_OIS_GYRO:
297 /* Update OIS gyroscope address */
298 reg_addr = BMI2_OIS_GYR_X_LSB_ADDR;
300 /* Get OIS gyroscope data */
301 rslt = get_ois_acc_gyr_data(&ois_dev->gyr_data, reg_addr, ois_dev, gyr_cross_sens_zx);
302 break;
303 default:
304 rslt = BMI2_OIS_E_INVALID_SENSOR;
305 break;
308 /* Return error if any of the get sensor data fails */
309 if (rslt != BMI2_OIS_OK)
311 break;
315 else
317 rslt = BMI2_OIS_E_NULL_PTR;
320 return rslt;
323 /***************************************************************************/
325 /*! Local Function Definitions
326 ****************************************************************************/
328 /*! @cond DOXYGEN_SUPRESS */
330 /* Suppressing doxygen warnings triggered for same static function names present across various sensor variant
331 * directories */
334 * @brief This internal API gets the accelerometer and the gyroscope data.
336 static int8_t get_ois_acc_gyr_data(struct bmi2_ois_sens_axes_data *ois_data,
337 uint8_t reg_addr,
338 struct bmi2_ois_dev *ois_dev,
339 int16_t ois_gyr_cross_sens_zx)
341 /* Variable to define error */
342 int8_t rslt;
344 /* Variables to store MSB value */
345 uint8_t msb;
347 /* Variables to store LSB value */
348 uint8_t lsb;
350 /* Variables to store both MSB and LSB value */
351 uint16_t msb_lsb;
353 /* Variables to define index */
354 uint8_t index = 0;
356 /* Array to define data stored in register */
357 uint8_t reg_data[BMI2_OIS_ACC_GYR_NUM_BYTES] = { 0 };
359 /* Read the sensor data */
360 rslt = bmi2_ois_get_regs(reg_addr, reg_data, BMI2_OIS_ACC_GYR_NUM_BYTES, ois_dev);
361 if (rslt == BMI2_OIS_OK)
363 /* Read x-axis data */
364 lsb = reg_data[index++];
365 msb = reg_data[index++];
366 msb_lsb = ((uint16_t)msb << 8) | (uint16_t)lsb;
367 ois_data->x = (int16_t)msb_lsb;
369 /* Read y-axis data */
370 lsb = reg_data[index++];
371 msb = reg_data[index++];
372 msb_lsb = ((uint16_t)msb << 8) | (uint16_t)lsb;
373 ois_data->y = (int16_t)msb_lsb;
375 /* Read z-axis data */
376 lsb = reg_data[index++];
377 msb = reg_data[index++];
378 msb_lsb = ((uint16_t)msb << 8) | (uint16_t)lsb;
379 ois_data->z = (int16_t)msb_lsb;
381 comp_gyro_cross_axis_sensitivity(ois_data, ois_gyr_cross_sens_zx);
384 return rslt;
388 * @brief This internal API is used to validate the device structure pointer for
389 * null conditions.
391 static int8_t null_ptr_check(const struct bmi2_ois_dev *ois_dev)
393 /* Variable to define error */
394 int8_t rslt = BMI2_OIS_OK;
396 if ((ois_dev == NULL) || (ois_dev->ois_read == NULL) || (ois_dev->ois_write == NULL) ||
397 (ois_dev->ois_delay_us == NULL))
399 /* Device structure pointer is NULL */
400 rslt = BMI2_OIS_E_NULL_PTR;
403 return rslt;
407 * @brief This internal API corrects the gyroscope cross-axis sensitivity
408 * between the z and the x axis.
410 static void comp_gyro_cross_axis_sensitivity(struct bmi2_ois_sens_axes_data *ois_data, int16_t ois_gyr_cross_sens_zx)
413 /* Get the compensated gyroscope x-axis */
414 ois_data->x = ois_data->x - (int16_t)(((int32_t)ois_gyr_cross_sens_zx * (int32_t)ois_data->z) / 512);
417 /*! @endcond */