Merge pull request #11270 from haslinghuis/rename_attr
[betaflight.git] / lib / main / BoschSensortec / BMI270-Sensor-API / bmi2_ois.h
blob9b700cd9554f9ee3c55e6e83ca02c447d5a16df0
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.h
34 * @date 2020-05-05
35 * @version v2.23.2
39 /**
40 * \ingroup bmi2xy
41 * \defgroup bmi2_ois BMI2_OIS
42 * @brief Sensor driver for BMI2_OIS sensor
44 #ifndef _BMI2_OIS_H
45 #define _BMI2_OIS_H
47 /*! CPP guard */
48 #ifdef __cplusplus
49 extern "C" {
50 #endif
52 /***************************************************************************/
54 /*! Header files
55 ****************************************************************************/
56 #ifdef __KERNEL__
57 #include <linux/types.h>
58 #include <linux/kernel.h>
59 #else
60 #include <stdint.h>
61 #include <stddef.h>
62 #endif
64 /******************************************************************************/
65 /*! @name Macros */
66 /******************************************************************************/
68 #ifndef BMI2_INTF_RETURN_TYPE
69 #define BMI2_INTF_RETURN_TYPE int8_t
70 #endif
72 /*! @name Utility macros */
73 #define BMI2_OIS_SET_BITS(reg_data, bitname, data) \
74 ((reg_data & ~(bitname##_MASK)) | \
75 ((data << bitname##_POS) & bitname##_MASK))
77 #define BMI2_OIS_GET_BITS(reg_data, bitname) \
78 ((reg_data & (bitname##_MASK)) >> \
79 (bitname##_POS))
81 #define BMI2_SET_BIT_POS0(reg_data, bitname, data) \
82 ((reg_data & ~(bitname##_MASK)) | \
83 (data & bitname##_MASK))
85 #define BMI2_GET_BIT_POS0(reg_data, bitname) (reg_data & (bitname##_MASK))
87 /*! @name For enable and disable */
88 #define BMI2_OIS_ENABLE UINT8_C(1)
89 #define BMI2_OIS_DISABLE UINT8_C(0)
91 /*! @name To define sensor interface success code */
92 #define BMI2_INTF_RET_SUCCESS INT8_C(0)
94 /*! @name To define success code */
95 #define BMI2_OIS_OK UINT8_C(0)
97 /*! @name To define error codes */
98 #define BMI2_OIS_E_NULL_PTR INT8_C(-1)
99 #define BMI2_OIS_E_COM_FAIL INT8_C(-2)
100 #define BMI2_OIS_E_INVALID_SENSOR INT8_C(-8)
102 /*! @name Mask definitions for SPI read/write address for OIS */
103 #define BMI2_OIS_SPI_RD_MASK UINT8_C(0x80)
104 #define BMI2_OIS_SPI_WR_MASK UINT8_C(0x7F)
106 /*! @name BMI2 OIS data bytes */
107 #define BMI2_OIS_ACC_GYR_NUM_BYTES UINT8_C(6)
109 /*! @name Macros to select sensor for OIS data read */
110 #define BMI2_OIS_ACCEL UINT8_C(0x01)
111 #define BMI2_OIS_GYRO UINT8_C(0x02)
113 /*! @name Macros to define OIS register addresses */
114 #define BMI2_OIS_CONFIG_ADDR UINT8_C(0x40)
115 #define BMI2_OIS_ACC_X_LSB_ADDR UINT8_C(0x0C)
116 #define BMI2_OIS_GYR_X_LSB_ADDR UINT8_C(0x12)
118 /*! @name Mask definitions for OIS configurations */
119 #define BMI2_OIS_GYR_EN_MASK UINT8_C(0x40)
120 #define BMI2_OIS_ACC_EN_MASK UINT8_C(0x80)
122 /*! @name Bit Positions for OIS configurations */
123 #define BMI2_OIS_GYR_EN_POS UINT8_C(0x06)
124 #define BMI2_OIS_ACC_EN_POS UINT8_C(0x07)
126 /*! Low pass filter configuration position and mask */
127 #define BMI2_OIS_LP_FILTER_EN_POS UINT8_C(0x00)
128 #define BMI2_OIS_LP_FILTER_EN_MASK UINT8_C(0x01)
130 #define BMI2_OIS_LP_FILTER_CONFIG_POS UINT8_C(0x01)
131 #define BMI2_OIS_LP_FILTER_CONFIG_MASK UINT8_C(0x06)
133 #define BMI2_OIS_LP_FILTER_MUTE_POS UINT8_C(0x05)
134 #define BMI2_OIS_LP_FILTER_MUTE_MASK UINT8_C(0x20)
136 /******************************************************************************/
137 /*! @name Function Pointers */
138 /******************************************************************************/
141 * @brief Bus communication function pointer which should be mapped to
142 * the platform specific read functions of the user
144 * @param[in] reg_addr : Register address from which data is read.
145 * @param[out] reg_data : Pointer to data buffer where read data is stored.
146 * @param[in] len : Number of bytes of data to be read.
147 * @param[in, out] intf_ptr : Void pointer that can enable the linking of descriptors
148 * for interface related call backs.
150 * retval = BMI2_INTF_RET_SUCCESS -> Success
151 * retval != BMI2_INTF_RET_SUCCESS -> Failure
154 typedef BMI2_INTF_RETURN_TYPE (*bmi2_ois_read_fptr_t)(uint8_t reg_addr, uint8_t *data, uint32_t len, void *intf_ptr);
157 * @brief Bus communication function pointer which should be mapped to
158 * the platform specific write functions of the user
160 * @param[in] reg_addr : Register address to which the data is written.
161 * @param[in] reg_data : Pointer to data buffer in which data to be written
162 * is stored.
163 * @param[in] len : Number of bytes of data to be written.
164 * @param[in, out] intf_ptr : Void pointer that can enable the linking of descriptors
165 * for interface related call backs
167 * retval = BMI2_INTF_RET_SUCCESS -> Success
168 * retval != BMI2_INTF_RET_SUCCESS -> Failure
171 typedef BMI2_INTF_RETURN_TYPE (*bmi2_ois_write_fptr_t)(uint8_t reg_addr, const uint8_t *data, uint32_t len,
172 void *intf_ptr);
175 * @brief Delay function pointer which should be mapped to
176 * delay function of the user
178 * @param[in] period : Delay in microseconds.
179 * @param[in, out] intf_ptr : Void pointer that can enable the linking of descriptors
180 * for interface related call backs
183 typedef void (*bmi2_ois_delay_fptr_t)(uint32_t period, void *intf_ptr);
185 /******************************************************************************/
186 /*! @name Structure Declarations */
187 /******************************************************************************/
188 /*! @name Structure to define accelerometer and gyroscope sensor axes for OIS */
189 struct bmi2_ois_sens_axes_data
191 /*! Data in x-axis */
192 int16_t x;
194 /*! Data in y-axis */
195 int16_t y;
197 /*! Data in z-axis */
198 int16_t z;
202 /*! @name Structure to define bmi2 OIS sensor configurations */
203 struct bmi2_ois_dev
205 /*! Read function pointer */
206 bmi2_ois_read_fptr_t ois_read;
208 /*! Write function pointer */
209 bmi2_ois_write_fptr_t ois_write;
211 /*! Delay function pointer */
212 bmi2_ois_delay_fptr_t ois_delay_us;
214 /*! Low pass filter en/dis */
215 uint8_t lp_filter_en;
217 /*! Void interface pointer */
218 void *intf_ptr;
220 /*! To store interface pointer error */
221 int8_t intf_rslt;
223 /*! Low pass filter cut-off frequency */
224 uint8_t lp_filter_config;
226 /*! Low pass filter mute */
227 uint8_t lp_filter_mute;
229 /*! Accelerometer enable for OIS */
230 uint8_t acc_en;
232 /*! Gyroscope enable for OIS */
233 uint8_t gyr_en;
235 /*! Accelerometer data axes */
236 struct bmi2_ois_sens_axes_data acc_data;
238 /*! Gyroscope data axes */
239 struct bmi2_ois_sens_axes_data gyr_data;
242 /***************************************************************************/
244 /*! BMI2 OIS User Interface function prototypes
245 ****************************************************************************/
248 * \ingroup bmi2_ois
249 * \defgroup bmi2_oisApiRegs Registers
250 * @brief Read data from the given OIS register address of bmi2
254 * \ingroup bmi2_oisApiRegs
255 * \page bmi2_ois_api_bmi2_ois_get_regs bmi2_ois_get_regs
256 * \code
257 * int8_t bmi2_ois_get_regs(uint8_t ois_reg_addr,
258 * uint8_t *ois_reg_data,
259 * uint16_t data_len,
260 * const struct bmi2_ois_dev *ois_dev);
261 * \endcode
262 * @details This API reads the data from the given OIS register address of bmi2
263 * sensor.
265 * @param[in] ois_reg_addr : OIS register address from which data is read.
266 * @param[out] ois_reg_data : Pointer to data buffer where read data is stored.
267 * @param[in] data_len : No. of bytes of data to be read.
268 * @param[in] ois_dev : Structure instance of bmi2_ois_dev.
270 * @return Result of API execution status
271 * @retval 0 -> Success
272 * @retval < 0 -> Fail
274 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);
277 * \ingroup bmi2_oisApiRegs
278 * \page bmi2_ois_api_bmi2_ois_set_regs bmi2_ois_set_regs
279 * \code
280 * int8_t bmi2_ois_set_regs(uint8_t ois_reg_addr,
281 * uint8_t *ois_reg_data,
282 * uint16_t data_len,
283 * const struct bmi2_ois_dev *ois_dev);
284 * \endcode
285 * @details This API writes data to the given OIS register address of bmi2 sensor.
287 * @param[in] ois_reg_addr : OIS register address to which the data is written.
288 * @param[in] ois_reg_data : Pointer to data buffer in which data to be written
289 * is stored.
290 * @param[in] data_len : No. of bytes of data to be written.
291 * @param[in] ois_dev : Structure instance of bmi2_ois_dev.
293 * @return Result of API execution status
294 * @retval 0 -> Success
295 * @retval < 0 -> Fail
297 int8_t bmi2_ois_set_regs(uint8_t ois_reg_addr,
298 const uint8_t *ois_reg_data,
299 uint16_t data_len,
300 struct bmi2_ois_dev *ois_dev);
303 * \ingroup bmi2_ois
304 * \defgroup bmi2_oisApiConfig Status update
305 * @brief Get / Set the status of Enable / Disable accelerometer / gyroscope data read through OIS interface
309 * \ingroup bmi2_oisApiConfig
310 * \page bmi2_ois_api_bmi2_ois_set_config bmi2_ois_set_config
311 * \code
312 * int8_t bmi2_ois_set_config(const struct bmi2_ois_dev *ois_dev);
313 * \endcode
314 * @details This API sets the status of enable/disable accelerometer/gyroscope data read through
315 * OIS interface.
317 * @param[in] ois_dev : Structure instance of bmi2_ois_dev.
319 * @return Result of API execution status
320 * @retval 0 -> Success
321 * @retval < 0 -> Fail
323 int8_t bmi2_ois_set_config(struct bmi2_ois_dev *ois_dev);
326 * \ingroup bmi2_oisApiConfig
327 * \page bmi2_ois_api_bmi2_ois_get_config bmi2_ois_get_config
328 * \code
329 * int8_t bmi2_ois_get_config(struct bmi2_ois_dev *ois_dev);
330 * \endcode
331 * @details This API gets the status of accelerometer/gyroscope enable for data
332 * read through OIS interface.
334 * @param[in, out] ois_dev : Structure instance of bmi2_ois_dev.
336 * @note Enabling and disabling is done during OIS structure initialization.
338 * @return Result of API execution status
339 * @retval 0 -> Success
340 * @retval < 0 -> Fail
342 int8_t bmi2_ois_get_config(struct bmi2_ois_dev *ois_dev);
345 * \ingroup bmi2_ois
346 * \defgroup bmi2_oisApiRead Data read
347 * @brief Read accelerometer / gyroscope data through OIS interface
351 * \ingroup bmi2_oisApiRead
352 * \page bmi2_ois_api_bmi2_ois_read_data bmi2_ois_read_data
353 * \code
354 * int8_t bmi2_ois_read_data(const uint8_t *sens_sel,
355 * uint8_t n_sens,
356 * struct bmi2_ois_dev *ois_dev,
357 * int16_t gyr_cross_sens_zx);
358 * \endcode
359 * @details This API reads accelerometer/gyroscope data through OIS interface.
361 * @param[in] sens_sel : Select sensor whose data is to be read.
362 * @param[in] n_sens : Number of sensors selected.
363 * @param[in, out] ois_dev : Structure instance of bmi2_ois_dev.
364 * @param[in] gyr_cross_sens_zx : Store the gyroscope cross sensitivity values taken from the bmi2xy
365 * (refer bmi2_ois example).
367 *@verbatim
368 * sens_sel | Value
369 * ---------------|---------------
370 * BMI2_OIS_ACCEL | 0x01
371 * BMI2_OIS_GYRO | 0x02
372 *@endverbatim
374 * @return Result of API execution status
375 * @retval 0 -> Success
376 * @retval < 0 -> Fail
378 int8_t bmi2_ois_read_data(const uint8_t *sens_sel,
379 uint8_t n_sens,
380 struct bmi2_ois_dev *ois_dev,
381 int16_t gyr_cross_sens_zx);
383 #ifdef __cplusplus
385 #endif /* End of CPP guard */
387 #endif /* End of _BMI2_OIS_H */