Merge pull request #11538 from klutvott123/osd-visual-beeper
[betaflight.git] / lib / main / BoschSensortec / BMI270-Sensor-API / bmi270_hc.h
blob2a1b5bc07b01e714f0e1ff8e47f4024bd3aac8f6
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_hc.h
34 * @date 2020-11-04
35 * @version v2.63.1
39 /**
40 * \ingroup bmi2xy
41 * \defgroup bmi270_hc BMI270_HC
42 * @brief Sensor driver for BMI270_HC sensor
45 #ifndef BMI270_HC_H_
46 #define BMI270_HC_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_HC Chip identifier */
65 #define BMI270_HC_CHIP_ID UINT8_C(0x24)
67 /*! @name BMI270_HC feature input start addresses */
68 #define BMI270_HC_CONFIG_ID_STRT_ADDR UINT8_C(0x06)
69 #define BMI270_HC_STEP_CNT_1_STRT_ADDR UINT8_C(0x00)
70 #define BMI270_HC_STEP_CNT_4_STRT_ADDR UINT8_C(0x02)
71 #define BMI270_HC_MAX_BURST_LEN_STRT_ADDR UINT8_C(0x08)
72 #define BMI270_HC_CRT_GYRO_SELF_TEST_STRT_ADDR UINT8_C(0x09)
73 #define BMI270_HC_ABORT_STRT_ADDR UINT8_C(0x09)
74 #define BMI270_HC_NVM_PROG_PREP_STRT_ADDR UINT8_C(0x0A)
75 #define BMI270_HC_ACT_RGN_SETT_STRT_ADDR UINT8_C(0x02)
76 #define BMI270_HC_ACT_RGN_STRT_ADDR UINT8_C(0x00)
78 /*! @name BMI270_HC feature output start addresses */
79 #define BMI270_HC_STEP_CNT_OUT_STRT_ADDR UINT8_C(0x00)
80 #define BMI270_HC_GYR_USER_GAIN_OUT_STRT_ADDR UINT8_C(0x04)
81 #define BMI270_HC_GYRO_CROSS_SENSE_STRT_ADDR UINT8_C(0x0C)
82 #define BMI270_HC_NVM_VFRM_OUT_STRT_ADDR UINT8_C(0x0E)
84 /*! @name Defines maximum number of pages */
85 #define BMI270_HC_MAX_PAGE_NUM UINT8_C(8)
87 /*! @name Defines maximum number of feature input configurations */
88 #define BMI270_HC_MAX_FEAT_IN UINT8_C(10)
90 /*! @name Defines maximum number of feature outputs */
91 #define BMI270_HC_MAX_FEAT_OUT UINT8_C(5)
93 /*! @name Mask definitions for feature interrupt status bits */
94 #define BMI270_HC_STEP_CNT_STATUS_MASK UINT8_C(0x01)
96 /*! @name Mask definitions for feature interrupt mapping bits */
97 #define BMI270_HC_INT_STEP_COUNTER_MASK UINT8_C(0x01)
98 #define BMI270_HC_INT_STEP_DETECTOR_MASK UINT8_C(0x01)
100 /*! @name Defines maximum number of feature interrupts */
101 #define BMI270_HC_MAX_INT_MAP UINT8_C(2)
103 /***************************************************************************/
105 /*! BMI270_HC User Interface function prototypes
106 ****************************************************************************/
109 * \ingroup bmi270_hc
110 * \defgroup bmi270_hcApiInit Initialization
111 * @brief Initialize the sensor and device structure
115 * \ingroup bmi270_hcApiInit
116 * \page bmi270_hc_api_bmi270_hc_init bmi270_hc_init
117 * \code
118 * int8_t bmi270_hc_init(struct bmi2_dev *dev);
119 * \endcode
120 * @details This API:
121 * 1) updates the device structure with address of the configuration file.
122 * 2) Initializes BMI270_HC sensor.
123 * 3) Writes the configuration file.
124 * 4) Updates the feature offset parameters in the device structure.
125 * 5) Updates the maximum number of pages, in the device structure.
127 * @param[in, out] dev : Structure instance of bmi2_dev.
129 * @return Result of API execution status
130 * @retval 0 -> Success
131 * @retval < 0 -> Fail
133 int8_t bmi270_hc_init(struct bmi2_dev *dev);
136 * \ingroup bmi270_hc
137 * \defgroup bmi270_hcApiSensor Feature Set
138 * @brief Enable / Disable features of the sensor
142 * \ingroup bmi270_hcApiSensor
143 * \page bmi270_hc_api_bmi270_hc_sensor_enable bmi270_hc_sensor_enable
144 * \code
145 * int8_t bmi270_hc_sensor_enable(const uint8_t *sens_list, uint8_t n_sens, struct bmi2_dev *dev);
146 * \endcode
147 * @details This API selects the sensors/features to be enabled.
149 * @param[in] sens_list : Pointer to select the sensor/feature.
150 * @param[in] n_sens : Number of sensors selected.
151 * @param[in, out] dev : Structure instance of bmi2_dev.
153 * @note Sensors/features that can be enabled.
155 *@verbatim
156 * sens_list | Values
157 * ----------------------------|-----------
158 * BMI2_ACCEL | 0
159 * BMI2_GYRO | 1
160 * BMI2_AUX | 2
161 * BMI2_STEP_DETECTOR | 6
162 * BMI2_STEP_COUNTER | 7
163 * BMI2_GYRO_GAIN_UPDATE | 9
164 * BMI2_ACTIVITY_RECOGNITION | 34
165 *@endverbatim
167 * @note :
168 * example uint8_t sens_list[2] = {BMI2_ACCEL, BMI2_GYRO};
169 * uint8_t n_sens = 2;
171 * @return Result of API execution status
172 * @retval 0 -> Success
173 * @retval < 0 -> Fail
175 int8_t bmi270_hc_sensor_enable(const uint8_t *sens_list, uint8_t n_sens, struct bmi2_dev *dev);
178 * \ingroup bmi270_hcApiSensor
179 * \page bmi270_hc_api_bmi270_hc_sensor_disable bmi270_hc_sensor_disable
180 * \code
181 * int8_t bmi270_hc_sensor_disable(const uint8_t *sens_list, uint8_t n_sens, struct bmi2_dev *dev);
182 * \endcode
183 * @details This API selects the sensors/features to be disabled.
185 * @param[in] sens_list : Pointer to select the sensor/feature.
186 * @param[in] n_sens : Number of sensors selected.
187 * @param[in, out] dev : Structure instance of bmi2_dev.
189 * @note Sensors/features that can be disabled.
191 *@verbatim
192 * sens_list | Values
193 * ----------------------------|-----------
194 * BMI2_ACCEL | 0
195 * BMI2_GYRO | 1
196 * BMI2_AUX | 2
197 * BMI2_STEP_DETECTOR | 6
198 * BMI2_STEP_COUNTER | 7
199 * BMI2_GYRO_GAIN_UPDATE | 9
200 * BMI2_ACTIVITY_RECOGNITION | 34
201 *@endverbatim
203 * @note :
204 * example uint8_t sens_list[2] = {BMI2_ACCEL, BMI2_GYRO};
205 * uint8_t n_sens = 2;
207 * @return Result of API execution status
208 * @retval 0 -> Success
209 * @retval < 0 -> Fail
211 int8_t bmi270_hc_sensor_disable(const uint8_t *sens_list, uint8_t n_sens, struct bmi2_dev *dev);
214 * \ingroup bmi270_hc
215 * \defgroup bmi270_hcApiSensorC Sensor Configuration
216 * @brief Enable / Disable feature configuration of the sensor
220 * \ingroup bmi270_hcApiSensorC
221 * \page bmi270_hc_api_bmi270_hc_set_sensor_config bmi270_hc_set_sensor_config
222 * \code
223 * int8_t bmi270_hc_set_sensor_config(struct bmi2_sens_config *sens_cfg, uint8_t n_sens, struct bmi2_dev *dev);
224 * \endcode
225 * @details This API sets the sensor/feature configuration.
227 * @param[in] sens_cfg : Structure instance of bmi2_sens_config.
228 * @param[in] n_sens : Number of sensors selected.
229 * @param[in, out] dev : Structure instance of bmi2_dev.
231 * @note Sensors/features that can be configured
233 *@verbatim
234 * sens_list | Values
235 * ----------------------------|-----------
236 * BMI2_STEP_DETECTOR | 6
237 * BMI2_STEP_COUNTER | 7
238 * BMI2_STEP_COUNTER_PARAMS | 28
239 *@endverbatim
241 * @return Result of API execution status
242 * @retval 0 -> Success
243 * @retval < 0 -> Fail
245 int8_t bmi270_hc_set_sensor_config(struct bmi2_sens_config *sens_cfg, uint8_t n_sens, struct bmi2_dev *dev);
248 * \ingroup bmi270_hcApiSensorC
249 * \page bmi270_hc_api_bmi270_hc_get_sensor_config bmi270_hc_get_sensor_config
250 * \code
251 * int8_t bmi270_hc_get_sensor_config(struct bmi2_sens_config *sens_cfg, uint8_t n_sens, struct bmi2_dev *dev);
252 * \endcode
253 * @details This API gets the sensor/feature configuration.
255 * @param[in] sens_cfg : Structure instance of bmi2_sens_config.
256 * @param[in] n_sens : Number of sensors selected.
257 * @param[in, out] dev : Structure instance of bmi2_dev.
259 * @note Sensors/features whose configurations can be read.
261 *@verbatim
262 * sens_list | Values
263 * ----------------------------|-----------
264 * BMI2_STEP_DETECTOR | 6
265 * BMI2_STEP_COUNTER | 7
266 * BMI2_STEP_COUNTER_PARAMS | 28
267 *@endverbatim
269 * @return Result of API execution status
270 * @retval 0 -> Success
271 * @retval < 0 -> Fail
273 int8_t bmi270_hc_get_sensor_config(struct bmi2_sens_config *sens_cfg, uint8_t n_sens, struct bmi2_dev *dev);
276 * \ingroup bmi270_hc
277 * \defgroup bmi270_hcApiSensorD Sensor Data
278 * @brief Get sensor data
282 * \ingroup bmi270_hcApiSensorD
283 * \page bmi270_hc_api_bmi270_hc_get_sensor_data bmi270_hc_get_sensor_data
284 * \code
285 * int8_t bmi270_hc_get_sensor_data(struct bmi2_sensor_data *sensor_data, uint8_t n_sens, struct bmi2_dev *dev);
286 * \endcode
287 * @details This API gets the sensor/feature data for accelerometer, gyroscope,
288 * auxiliary sensor, step counter, high-g, gyroscope user-gain update,
289 * orientation, gyroscope cross sensitivity and error status for NVM and VFRM.
291 * @param[out] sensor_data : Structure instance of bmi2_sensor_data.
292 * @param[in] n_sens : Number of sensors selected.
293 * @param[in] dev : Structure instance of bmi2_dev.
295 * @note Sensors/features whose data can be read
297 *@verbatim
298 * sens_list | Values
299 * ---------------------|-----------
300 * BMI2_STEP_COUNTER | 7
301 * BMI2_NVM_STATUS | 38
302 * BMI2_VFRM_STATUS | 39
303 *@endverbatim
305 * @return Result of API execution status
306 * @retval 0 -> Success
307 * @retval < 0 -> Fail
309 int8_t bmi270_hc_get_sensor_data(struct bmi2_sensor_data *sensor_data, uint8_t n_sens, struct bmi2_dev *dev);
312 * \ingroup bmi270_hc
313 * \defgroup bmi270_hcApiARecoghc Activity recognition settings
314 * @brief Set / Get activity recognition settings of bmi270hc sensor
318 * \ingroup bmi270_hcApiARecoghc
319 * \page bmi270_hc_api_bmi270_hc_get_act_recg_sett bmi270_hc_get_act_recg_sett
320 * \code
321 * int8_t bmi270_hc_get_act_recg_sett(struct bmi2_hc_act_recg_sett *sett, struct bmi2_dev *dev);
322 * \endcode
323 * @details This api is used for retrieving the following activity recognition settings currently set.
325 * @param[in] sett : Structure instance of bmi2_hc_act_recg_sett.
326 * @param[in] dev : Structure instance of bmi2_dev.
328 * @return Result of API execution status
329 * @retval 0 -> Success
330 * @retval < 0 -> Fail
332 int8_t bmi270_hc_get_act_recg_sett(struct bmi2_hc_act_recg_sett *sett, struct bmi2_dev *dev);
335 * \ingroup bmi270_hcApiARecoghc
336 * \page bmi270_hc_api_bmi270_hc_set_act_recg_sett bmi270_hc_set_act_recg_sett
337 * \code
338 * int8_t bmi270_hc_set_act_recg_sett(const struct bmi2_hc_act_recg_sett *sett, struct bmi2_dev *dev);
339 * \endcode
340 * @details This api is used for setting the following activity recognition settings
342 * @param[in] sett : Structure instance of bmi2_hc_act_recg_sett.
343 * @param[in] dev : Structure instance of bmi2_dev.
345 * @return Result of API execution status
346 * @retval 0 -> Success
347 * @retval < 0 -> Fail
349 int8_t bmi270_hc_set_act_recg_sett(const struct bmi2_hc_act_recg_sett *sett, struct bmi2_dev *dev);
352 * \ingroup bmi270_hc
353 * \defgroup bmi270_hcApiactOut Activity Output
354 * @brief Activity output operations of the sensor
358 * \ingroup bmi270_hcApiactOut
359 * \page bmi270_hc_api_bmi270_hc_get_act_recog_output bmi270_hc_get_act_recog_output
360 * \code
361 * int8_t bmi270_hc_get_act_recog_output(struct bmi2_act_recog_output *act_recog,
362 * uint16_t *act_frm_len,
363 * struct bmi2_fifo_frame *fifo,
364 * const struct bmi2_dev *dev);
366 * \endcode
367 * @details This internal API is used to parse the activity output from the
368 * FIFO in header mode.
370 * @param[out] act_recog : Pointer to buffer where the parsed activity data
371 * bytes are stored.
372 * @param[in] act_frm_len : Number of activity frames parsed.
373 * @param[in] fifo : Structure instance of bmi2_fifo_frame.
374 * @param[in] dev : Structure instance of bmi2_dev.
376 * @verbatim
377 * ----------------------------------------------------------------------------
378 * bmi2_act_rec_output |
379 * Structure parameters | Description
380 *--------------------------|--------------------------------------------------
381 * time_stamp | time-stamp (expressed in 50Hz ticks)
382 * -------------------------|---------------------------------------------------
383 * type | Type of activity
384 * -------------------------|---------------------------------------------------
385 * stat | Activity status
386 * -------------------------|---------------------------------------------------
387 * @endverbatim
389 *@verbatim
390 * type | Activities
391 *----------|---------------------
392 * 0 | UNKNOWN
393 * 1 | STILL
394 * 2 | WALK
395 * 3 | RUN
396 * 4 | BIKE
397 * 5 | VEHICLE
398 * 6 | TILTED
399 *@endverbatim
402 *@verbatim
403 * stat | Activity status
404 *----------|---------------------
405 * 1 | START
406 * 2 | END
407 *@endverbatim
409 * @return Result of API execution status
410 * @retval 0 -> Success
411 * @retval < 0 -> Fail
413 int8_t bmi270_hc_get_act_recog_output(struct bmi2_act_recog_output *act_recog,
414 uint16_t *act_frm_len,
415 struct bmi2_fifo_frame *fifo,
416 const struct bmi2_dev *dev);
419 * \ingroup bmi270_hc
420 * \defgroup bmi270_hcApiGyroUG Gyro User Gain
421 * @brief Set / Get Gyro User Gain of the sensor
425 * \ingroup bmi270_hcApiGyroUG
426 * \page bmi270_hc_api_bmi270_hc_update_gyro_user_gain bmi270_hc_update_gyro_user_gain
427 * \code
428 * int8_t bmi270_hc_update_gyro_user_gain(const struct bmi2_gyro_user_gain_config *user_gain, struct bmi2_dev *dev);
429 * \endcode
430 * @details This API updates the gyroscope user-gain.
432 * @param[in] user_gain : Structure that stores user-gain configurations.
433 * @param[in] dev : Structure instance of bmi2_dev.
435 * @return Result of API execution status
436 * @retval 0 -> Success
437 * @retval < 0 -> Fail
439 int8_t bmi270_hc_update_gyro_user_gain(const struct bmi2_gyro_user_gain_config *user_gain, struct bmi2_dev *dev);
442 * \ingroup bmi270_hcApiGyroUG
443 * \page bmi270_hc_api_bmi270_hc_read_gyro_user_gain bmi270_hc_read_gyro_user_gain
444 * \code
445 * int8_t bmi270_hc_read_gyro_user_gain(struct bmi2_gyro_user_gain_data *gyr_usr_gain, const struct bmi2_dev *dev);
446 * \endcode
447 * @details This API reads the compensated gyroscope user-gain values.
449 * @param[out] gyr_usr_gain : Structure that stores gain values.
450 * @param[in] dev : Structure instance of bmi2_dev.
452 * @return Result of API execution status
453 * @retval 0 -> Success
454 * @retval < 0 -> Fail
456 int8_t bmi270_hc_read_gyro_user_gain(struct bmi2_gyro_user_gain_data *gyr_usr_gain, struct bmi2_dev *dev);
459 * \ingroup bmi270_hcApiInt
460 * \page bmi270_hc_api_bmi270_hc_map_feat_int bmi270_hc_map_feat_int
461 * \code
462 * int8_t bmi270_hc_map_feat_int(const struct bmi2_sens_int_config *sens_int, uint8_t n_sens, struct bmi2_dev *dev)
463 * \endcode
464 * @details This API maps/unmaps feature interrupts to that of interrupt pins.
466 * @param[in] sens_int : Structure instance of bmi2_sens_int_config.
467 * @param[in] n_sens : Number of interrupts to be mapped.
468 * @param[in] dev : Structure instance of bmi2_dev.
470 * @return Result of API execution status
471 * @retval 0 -> Success
472 * @retval < 0 -> Fail
474 int8_t bmi270_hc_map_feat_int(const struct bmi2_sens_int_config *sens_int, uint8_t n_sens, struct bmi2_dev *dev);
476 /******************************************************************************/
477 /*! @name C++ Guard Macros */
478 /******************************************************************************/
479 #ifdef __cplusplus
481 #endif /* End of CPP guard */
483 #endif /* BMI270_HC_H_ */