Merge pull request #11270 from haslinghuis/rename_attr
[betaflight.git] / lib / main / BoschSensortec / BMI270-Sensor-API / bmi270.h
blobf42676d65e5f5f510b96913efe82014550076982
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 bmi270.h
34 * @date 2020-11-04
35 * @version v2.63.1
39 /**
40 * \ingroup bmi2xy
41 * \defgroup bmi270 BMI270
42 * @brief Sensor driver for BMI270 sensor
45 #ifndef BMI270_H_
46 #define BMI270_H_
48 /*! CPP guard */
49 #ifdef __cplusplus
50 extern "C" {
51 #endif
53 /***************************************************************************/
55 /*! Header files
56 ****************************************************************************/
57 #include "bmi2.h"
59 /***************************************************************************/
61 /*! Macro definitions
62 ****************************************************************************/
64 /*! @name BMI270 Chip identifier */
65 #define BMI270_CHIP_ID UINT8_C(0x24)
67 /*! @name BMI270 feature input start addresses */
68 #define BMI270_CONFIG_ID_STRT_ADDR UINT8_C(0x00)
69 #define BMI270_MAX_BURST_LEN_STRT_ADDR UINT8_C(0x02)
70 #define BMI270_CRT_GYRO_SELF_TEST_STRT_ADDR UINT8_C(0x03)
71 #define BMI270_ABORT_STRT_ADDR UINT8_C(0x03)
72 #define BMI270_AXIS_MAP_STRT_ADDR UINT8_C(0x04)
73 #define BMI270_GYRO_SELF_OFF_STRT_ADDR UINT8_C(0x05)
74 #define BMI270_NVM_PROG_PREP_STRT_ADDR UINT8_C(0x05)
75 #define BMI270_GYRO_GAIN_UPDATE_STRT_ADDR UINT8_C(0x06)
76 #define BMI270_ANY_MOT_STRT_ADDR UINT8_C(0x0C)
77 #define BMI270_NO_MOT_STRT_ADDR UINT8_C(0x00)
78 #define BMI270_SIG_MOT_STRT_ADDR UINT8_C(0x04)
79 #define BMI270_STEP_CNT_1_STRT_ADDR UINT8_C(0x00)
80 #define BMI270_STEP_CNT_4_STRT_ADDR UINT8_C(0x02)
81 #define BMI270_WRIST_GEST_STRT_ADDR UINT8_C(0x06)
82 #define BMI270_WRIST_WEAR_WAKE_UP_STRT_ADDR UINT8_C(0x00)
84 /*! @name BMI270 feature output start addresses */
85 #define BMI270_STEP_CNT_OUT_STRT_ADDR UINT8_C(0x00)
86 #define BMI270_STEP_ACT_OUT_STRT_ADDR UINT8_C(0x04)
87 #define BMI270_WRIST_GEST_OUT_STRT_ADDR UINT8_C(0x06)
88 #define BMI270_GYR_USER_GAIN_OUT_STRT_ADDR UINT8_C(0x08)
89 #define BMI270_GYRO_CROSS_SENSE_STRT_ADDR UINT8_C(0x0C)
90 #define BMI270_NVM_VFRM_OUT_STRT_ADDR UINT8_C(0x0E)
92 /*! @name Defines maximum number of pages */
93 #define BMI270_MAX_PAGE_NUM UINT8_C(8)
95 /*! @name Defines maximum number of feature input configurations */
96 #define BMI270_MAX_FEAT_IN UINT8_C(17)
98 /*! @name Defines maximum number of feature outputs */
99 #define BMI270_MAX_FEAT_OUT UINT8_C(7)
101 /*! @name Mask definitions for feature interrupt status bits */
102 #define BMI270_SIG_MOT_STATUS_MASK UINT8_C(0x01)
103 #define BMI270_STEP_CNT_STATUS_MASK UINT8_C(0x02)
104 #define BMI270_STEP_ACT_STATUS_MASK UINT8_C(0x04)
105 #define BMI270_WRIST_WAKE_UP_STATUS_MASK UINT8_C(0x08)
106 #define BMI270_WRIST_GEST_STATUS_MASK UINT8_C(0x10)
107 #define BMI270_NO_MOT_STATUS_MASK UINT8_C(0x20)
108 #define BMI270_ANY_MOT_STATUS_MASK UINT8_C(0x40)
110 /*! @name Mask definitions for feature interrupt mapping bits */
111 #define BMI270_INT_SIG_MOT_MASK UINT8_C(0x01)
112 #define BMI270_INT_STEP_COUNTER_MASK UINT8_C(0x02)
113 #define BMI270_INT_STEP_DETECTOR_MASK UINT8_C(0x02)
114 #define BMI270_INT_STEP_ACT_MASK UINT8_C(0x04)
115 #define BMI270_INT_WRIST_WEAR_WAKEUP_MASK UINT8_C(0x08)
116 #define BMI270_INT_WRIST_GEST_MASK UINT8_C(0x10)
117 #define BMI270_INT_NO_MOT_MASK UINT8_C(0x20)
118 #define BMI270_INT_ANY_MOT_MASK UINT8_C(0x40)
120 /*! @name Defines maximum number of feature interrupts */
121 #define BMI270_MAX_INT_MAP UINT8_C(8)
123 /***************************************************************************/
125 /*! BMI270 User Interface function prototypes
126 ****************************************************************************/
129 * \ingroup bmi270
130 * \defgroup bmi270ApiInit Initialization
131 * @brief Initialize the sensor and device structure
135 * \ingroup bmi270ApiInit
136 * \page bmi270_api_bmi270_init bmi270_init
137 * \code
138 * int8_t bmi270_init(struct bmi2_dev *dev);
139 * \endcode
140 * @details This API:
141 * 1) updates the device structure with address of the configuration file.
142 * 2) Initializes BMI270 sensor.
143 * 3) Writes the configuration file.
144 * 4) Updates the feature offset parameters in the device structure.
145 * 5) Updates the maximum number of pages, in the device structure.
147 * @param[in, out] dev : Structure instance of bmi2_dev.
149 * @return Result of API execution status
150 * @retval 0 -> Success
151 * @retval < 0 -> Fail
153 int8_t bmi270_init(struct bmi2_dev *dev);
156 * \ingroup bmi270
157 * \defgroup bmi270ApiSensor Feature Set
158 * @brief Enable / Disable features of the sensor
162 * \ingroup bmi270ApiSensor
163 * \page bmi270_api_bmi270_sensor_enable bmi270_sensor_enable
164 * \code
165 * int8_t bmi270_sensor_enable(const uint8_t *sens_list, uint8_t n_sens, struct bmi2_dev *dev);
166 * \endcode
167 * @details This API selects the sensors/features to be enabled.
169 * @param[in] sens_list : Pointer to select the sensor/feature.
170 * @param[in] n_sens : Number of sensors selected.
171 * @param[in, out] dev : Structure instance of bmi2_dev.
173 * @note Sensors/features that can be enabled.
175 *@verbatim
176 * sens_list | Values
177 * ----------------------------|-----------
178 * BMI2_ACCEL | 0
179 * BMI2_GYRO | 1
180 * BMI2_AUX | 2
181 * BMI2_SIG_MOTION | 3
182 * BMI2_ANY_MOTION | 4
183 * BMI2_NO_MOTION | 5
184 * BMI2_STEP_DETECTOR | 6
185 * BMI2_STEP_COUNTER | 7
186 * BMI2_STEP_ACTIVITY | 8
187 * BMI2_GYRO_GAIN_UPDATE | 9
188 * BMI2_WRIST_GESTURE | 19
189 * BMI2_WRIST_WEAR_WAKE_UP | 20
190 * BMI2_GYRO_SELF_OFF | 33
191 *@endverbatim
193 * @note :
194 * example uint8_t sens_list[2] = {BMI2_ACCEL, BMI2_GYRO};
195 * uint8_t n_sens = 2;
197 * @return Result of API execution status
198 * @retval 0 -> Success
199 * @retval < 0 -> Fail
201 int8_t bmi270_sensor_enable(const uint8_t *sens_list, uint8_t n_sens, struct bmi2_dev *dev);
204 * \ingroup bmi270ApiSensor
205 * \page bmi270_api_bmi270_sensor_disable bmi270_sensor_disable
206 * \code
207 * int8_t bmi270_sensor_disable(const uint8_t *sens_list, uint8_t n_sens, struct bmi2_dev *dev);
208 * \endcode
209 * @details This API selects the sensors/features to be disabled.
211 * @param[in] sens_list : Pointer to select the sensor/feature.
212 * @param[in] n_sens : Number of sensors selected.
213 * @param[in, out] dev : Structure instance of bmi2_dev.
215 * @note Sensors/features that can be disabled.
217 *@verbatim
218 * sens_list | Values
219 * ----------------------------|-----------
220 * BMI2_ACCEL | 0
221 * BMI2_GYRO | 1
222 * BMI2_AUX | 2
223 * BMI2_SIG_MOTION | 3
224 * BMI2_ANY_MOTION | 4
225 * BMI2_NO_MOTION | 5
226 * BMI2_STEP_DETECTOR | 6
227 * BMI2_STEP_COUNTER | 7
228 * BMI2_STEP_ACTIVITY | 8
229 * BMI2_GYRO_GAIN_UPDATE | 9
230 * BMI2_WRIST_GESTURE | 19
231 * BMI2_WRIST_WEAR_WAKE_UP | 20
232 * BMI2_GYRO_SELF_OFF | 33
233 *@endverbatim
235 * @note :
236 * example uint8_t sens_list[2] = {BMI2_ACCEL, BMI2_GYRO};
237 * uint8_t n_sens = 2;
239 * @return Result of API execution status
240 * @retval 0 -> Success
241 * @retval < 0 -> Fail
243 int8_t bmi270_sensor_disable(const uint8_t *sens_list, uint8_t n_sens, struct bmi2_dev *dev);
246 * \ingroup bmi270
247 * \defgroup bmi270ApiSensorC Sensor Configuration
248 * @brief Enable / Disable feature configuration of the sensor
252 * \ingroup bmi270ApiSensorC
253 * \page bmi270_api_bmi270_set_sensor_config bmi270_set_sensor_config
254 * \code
255 * int8_t bmi270_set_sensor_config(struct bmi2_sens_config *sens_cfg, uint8_t n_sens, struct bmi2_dev *dev);
256 * \endcode
257 * @details This API sets the sensor/feature configuration.
259 * @param[in] sens_cfg : Structure instance of bmi2_sens_config.
260 * @param[in] n_sens : Number of sensors selected.
261 * @param[in, out] dev : Structure instance of bmi2_dev.
263 * @note Sensors/features that can be configured
265 *@verbatim
266 * sens_list | Values
267 * ----------------------------|-----------
268 * BMI2_SIG_MOTION | 3
269 * BMI2_ANY_MOTION | 4
270 * BMI2_NO_MOTION | 5
271 * BMI2_STEP_DETECTOR | 6
272 * BMI2_STEP_COUNTER | 7
273 * BMI2_STEP_ACTIVITY | 8
274 * BMI2_WRIST_GESTURE | 19
275 * BMI2_WRIST_WEAR_WAKE_UP | 20
276 * BMI2_STEP_COUNTER_PARAMS | 28
277 *@endverbatim
279 * @return Result of API execution status
280 * @retval 0 -> Success
281 * @retval < 0 -> Fail
283 int8_t bmi270_set_sensor_config(struct bmi2_sens_config *sens_cfg, uint8_t n_sens, struct bmi2_dev *dev);
286 * \ingroup bmi270ApiSensorC
287 * \page bmi270_api_bmi270_get_sensor_config bmi270_get_sensor_config
288 * \code
289 * int8_t bmi270_get_sensor_config(struct bmi2_sens_config *sens_cfg, uint8_t n_sens, struct bmi2_dev *dev);
290 * \endcode
291 * @details This API gets the sensor/feature configuration.
293 * @param[in] sens_cfg : Structure instance of bmi2_sens_config.
294 * @param[in] n_sens : Number of sensors selected.
295 * @param[in, out] dev : Structure instance of bmi2_dev.
297 * @note Sensors/features whose configurations can be read.
299 *@verbatim
300 * sens_list | Values
301 * ----------------------------|-----------
302 * BMI2_SIG_MOTION | 3
303 * BMI2_ANY_MOTION | 4
304 * BMI2_NO_MOTION | 5
305 * BMI2_STEP_DETECTOR | 6
306 * BMI2_STEP_COUNTER | 7
307 * BMI2_STEP_ACTIVITY | 8
308 * BMI2_WRIST_GESTURE | 19
309 * BMI2_WRIST_WEAR_WAKE_UP | 20
310 * BMI2_STEP_COUNTER_PARAMS | 28
311 *@endverbatim
313 * @return Result of API execution status
314 * @retval 0 -> Success
315 * @retval < 0 -> Fail
317 int8_t bmi270_get_sensor_config(struct bmi2_sens_config *sens_cfg, uint8_t n_sens, struct bmi2_dev *dev);
320 * \ingroup bmi270
321 * \defgroup bmi270ApiSensorD Sensor Data
322 * @brief Get sensor data
326 * \ingroup bmi270ApiSensorD
327 * \page bmi270_api_bmi270_get_sensor_data bmi270_get_sensor_data
328 * \code
329 * int8_t bmi270_get_sensor_data(struct bmi2_sensor_data *sensor_data, uint8_t n_sens, struct bmi2_dev *dev);
330 * \endcode
331 * @details This API gets the sensor/feature data for accelerometer, gyroscope,
332 * auxiliary sensor, step counter, high-g, gyroscope user-gain update,
333 * orientation, gyroscope cross sensitivity and error status for NVM and VFRM.
335 * @param[out] sensor_data : Structure instance of bmi2_sensor_data.
336 * @param[in] n_sens : Number of sensors selected.
337 * @param[in] dev : Structure instance of bmi2_dev.
339 * @note Sensors/features whose data can be read
341 *@verbatim
342 * sens_list | Values
343 * ----------------------------|-----------
344 * BMI2_STEP_COUNTER | 7
345 * BMI2_STEP_ACTIVITY | 8
346 * BMI2_WRIST_GESTURE | 19
347 * BMI2_NVM_STATUS | 38
348 * BMI2_VFRM_STATUS | 39
349 *@endverbatim
351 * @return Result of API execution status
352 * @retval 0 -> Success
353 * @retval < 0 -> Fail
355 int8_t bmi270_get_sensor_data(struct bmi2_sensor_data *sensor_data, uint8_t n_sens, struct bmi2_dev *dev);
358 * \ingroup bmi270
359 * \defgroup bmi270ApiGyroUG Gyro User Gain
360 * @brief Set / Get Gyro User Gain of the sensor
364 * \ingroup bmi270ApiGyroUG
365 * \page bmi270_api_bmi270_update_gyro_user_gain bmi270_update_gyro_user_gain
366 * \code
367 * int8_t bmi270_update_gyro_user_gain(const struct bmi2_gyro_user_gain_config *user_gain, struct bmi2_dev *dev);
368 * \endcode
369 * @details This API updates the gyroscope user-gain.
371 * @param[in] user_gain : Structure that stores user-gain configurations.
372 * @param[in] dev : Structure instance of bmi2_dev.
374 * @return Result of API execution status
375 * @retval 0 -> Success
376 * @retval < 0 -> Fail
378 int8_t bmi270_update_gyro_user_gain(const struct bmi2_gyro_user_gain_config *user_gain, struct bmi2_dev *dev);
381 * \ingroup bmi270ApiGyroUG
382 * \page bmi270_api_bmi270_read_gyro_user_gain bmi270_read_gyro_user_gain
383 * \code
384 * int8_t bmi270_read_gyro_user_gain(struct bmi2_gyro_user_gain_data *gyr_usr_gain, const struct bmi2_dev *dev);
385 * \endcode
386 * @details This API reads the compensated gyroscope user-gain values.
388 * @param[out] gyr_usr_gain : Structure that stores gain values.
389 * @param[in] dev : Structure instance of bmi2_dev.
391 * @return Result of API execution status
392 * @retval 0 -> Success
393 * @retval < 0 -> Fail
395 int8_t bmi270_read_gyro_user_gain(struct bmi2_gyro_user_gain_data *gyr_usr_gain, struct bmi2_dev *dev);
398 * \ingroup bmi270ApiInt
399 * \page bmi270_api_bmi270_map_feat_int bmi270_map_feat_int
400 * \code
401 * int8_t bmi270_map_feat_int(const struct bmi2_sens_int_config *sens_int, uint8_t n_sens, struct bmi2_dev *dev)
402 * \endcode
403 * @details This API maps/unmaps feature interrupts to that of interrupt pins.
405 * @param[in] sens_int : Structure instance of bmi2_sens_int_config.
406 * @param[in] n_sens : Number of interrupts to be mapped.
407 * @param[in] dev : Structure instance of bmi2_dev.
409 * @return Result of API execution status
410 * @retval 0 -> Success
411 * @retval < 0 -> Fail
413 int8_t bmi270_map_feat_int(const struct bmi2_sens_int_config *sens_int, uint8_t n_sens, struct bmi2_dev *dev);
415 /******************************************************************************/
416 /*! @name C++ Guard Macros */
417 /******************************************************************************/
418 #ifdef __cplusplus
420 #endif /* End of CPP guard */
422 #endif /* BMI270_H_ */