Merge pull request #11270 from haslinghuis/rename_attr
[betaflight.git] / lib / main / BoschSensortec / BMI270-Sensor-API / bmi270_wh.h
blobd46251bbd15ff562824f89deb81ee1d48e350310
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_wh.h
34 * @date 2020-11-04
35 * @version v2.63.1
39 /**
40 * \ingroup bmi2xy
41 * \defgroup bmi270_wh BMI270_WH
42 * @brief Sensor driver for BMI270_WH sensor
45 #ifndef BMI270_WH_H_
46 #define BMI270_WH_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_WH Chip identifier */
65 #define BMI270_WH_CHIP_ID UINT8_C(0x24)
67 /*! @name BMI270_WH feature input start addresses */
68 #define BMI270_WH_CONFIG_ID_STRT_ADDR UINT8_C(0x00)
69 #define BMI270_WH_MAX_BURST_LEN_STRT_ADDR UINT8_C(0x02)
70 #define BMI270_WH_AXIS_MAP_STRT_ADDR UINT8_C(0x04)
71 #define BMI270_WH_NVM_PROG_PREP_STRT_ADDR UINT8_C(0x05)
72 #define BMI270_WH_GYRO_GAIN_UPDATE_STRT_ADDR UINT8_C(0x06)
73 #define BMI270_WH_ANY_MOT_STRT_ADDR UINT8_C(0x0C)
74 #define BMI270_WH_NO_MOT_STRT_ADDR UINT8_C(0x00)
75 #define BMI270_WH_STEP_CNT_1_STRT_ADDR UINT8_C(0x00)
76 #define BMI270_WH_STEP_CNT_4_STRT_ADDR UINT8_C(0x02)
77 #define BMI270_WH_WRIST_WEAR_WAKE_UP_STRT_ADDR UINT8_C(0x04)
79 /*! @name BMI270_WH feature output start addresses */
80 #define BMI270_WH_STEP_CNT_OUT_STRT_ADDR UINT8_C(0x00)
81 #define BMI270_WH_STEP_ACT_OUT_STRT_ADDR UINT8_C(0x04)
82 #define BMI270_WH_WRIST_GEST_OUT_STRT_ADDR UINT8_C(0x06)
83 #define BMI270_WH_GYR_USER_GAIN_OUT_STRT_ADDR UINT8_C(0x08)
84 #define BMI270_WH_GYRO_CROSS_SENSE_STRT_ADDR UINT8_C(0x0C)
85 #define BMI270_WH_NVM_VFRM_OUT_STRT_ADDR UINT8_C(0x0E)
87 /*! @name Defines maximum number of pages */
88 #define BMI270_WH_MAX_PAGE_NUM UINT8_C(8)
90 /*! @name Defines maximum number of feature input configurations */
91 #define BMI270_WH_MAX_FEAT_IN UINT8_C(12)
93 /*! @name Defines maximum number of feature outputs */
94 #define BMI270_WH_MAX_FEAT_OUT UINT8_C(6)
96 /*! @name Mask definitions for feature interrupt status bits */
97 #define BMI270_WH_STEP_CNT_STATUS_MASK UINT8_C(0x02)
98 #define BMI270_WH_STEP_ACT_STATUS_MASK UINT8_C(0x04)
99 #define BMI270_WH_WRIST_WEAR_WAKEUP_WH_STATUS_MASK UINT8_C(0x08)
100 #define BMI270_WH_NO_MOT_STATUS_MASK UINT8_C(0x20)
101 #define BMI270_WH_ANY_MOT_STATUS_MASK UINT8_C(0x40)
103 /*! @name Mask definitions for feature interrupt mapping bits */
104 #define BMI270_WH_INT_STEP_COUNTER_MASK UINT8_C(0x02)
105 #define BMI270_WH_INT_STEP_DETECTOR_MASK UINT8_C(0x02)
106 #define BMI270_WH_INT_STEP_ACT_MASK UINT8_C(0x04)
107 #define BMI270_WH_INT_WRIST_WEAR_WAKEUP_WH_MASK UINT8_C(0x08)
108 #define BMI270_WH_INT_NO_MOT_MASK UINT8_C(0x20)
109 #define BMI270_WH_INT_ANY_MOT_MASK UINT8_C(0x40)
111 /*! @name Defines maximum number of feature interrupts */
112 #define BMI270_WH_MAX_INT_MAP UINT8_C(6)
114 /***************************************************************************/
116 /*! BMI270_WH User Interface function prototypes
117 ****************************************************************************/
120 * \ingroup bmi270_wh
121 * \defgroup bmi270_whApiInit Initialization
122 * @brief Initialize the sensor and device structure
126 * \ingroup bmi270_whApiInit
127 * \page bmi270_wh_api_bmi270_wh_init bmi270_wh_init
128 * \code
129 * int8_t bmi270_wh_init(struct bmi2_dev *dev);
130 * \endcode
131 * @details This API:
132 * 1) updates the device structure with address of the configuration file.
133 * 2) Initializes BMI270_WH sensor.
134 * 3) Writes the configuration file.
135 * 4) Updates the feature offset parameters in the device structure.
136 * 5) Updates the maximum number of pages, in the device structure.
138 * @param[in, out] dev : Structure instance of bmi2_dev.
140 * @return Result of API execution status
141 * @retval 0 -> Success
142 * @retval < 0 -> Fail
144 int8_t bmi270_wh_init(struct bmi2_dev *dev);
147 * \ingroup bmi270_wh
148 * \defgroup bmi270_whApiSensor Feature Set
149 * @brief Enable / Disable features of the sensor
153 * \ingroup bmi270_whApiSensor
154 * \page bmi270_wh_api_bmi270_wh_sensor_enable bmi270_wh_sensor_enable
155 * \code
156 * int8_t bmi270_wh_sensor_enable(const uint8_t *sens_list, uint8_t n_sens, struct bmi2_dev *dev);
157 * \endcode
158 * @details This API selects the sensors/features to be enabled.
160 * @param[in] sens_list : Pointer to select the sensor/feature.
161 * @param[in] n_sens : Number of sensors selected.
162 * @param[in, out] dev : Structure instance of bmi2_dev.
164 * @note Sensors/features that can be enabled.
166 *@verbatim
167 * sens_list | Values
168 * ----------------------------|-----------
169 * BMI2_ACCEL | 0
170 * BMI2_GYRO | 1
171 * BMI2_AUX | 2
172 * BMI2_ANY_MOTION | 4
173 * BMI2_NO_MOTION | 5
174 * BMI2_STEP_DETECTOR | 6
175 * BMI2_STEP_COUNTER | 7
176 * BMI2_STEP_ACTIVITY | 8
177 * BMI2_GYRO_GAIN_UPDATE | 9
178 * BMI2_WRIST_WEAR_WAKE_UP_WH | 21
179 *@endverbatim
181 * @note :
182 * example uint8_t sens_list[2] = {BMI2_ACCEL, BMI2_GYRO};
183 * uint8_t n_sens = 2;
185 * @return Result of API execution status
186 * @retval 0 -> Success
187 * @retval < 0 -> Fail
189 int8_t bmi270_wh_sensor_enable(const uint8_t *sens_list, uint8_t n_sens, struct bmi2_dev *dev);
192 * \ingroup bmi270_whApiSensor
193 * \page bmi270_wh_api_bmi270_wh_sensor_disable bmi270_wh_sensor_disable
194 * \code
195 * int8_t bmi270_wh_sensor_disable(const uint8_t *sens_list, uint8_t n_sens, struct bmi2_dev *dev);
196 * \endcode
197 * @details This API selects the sensors/features to be disabled.
199 * @param[in] sens_list : Pointer to select the sensor/feature.
200 * @param[in] n_sens : Number of sensors selected.
201 * @param[in, out] dev : Structure instance of bmi2_dev.
203 * @note Sensors/features that can be disabled.
205 *@verbatim
206 * sens_list | Values
207 * ----------------------------|-----------
208 * BMI2_ACCEL | 0
209 * BMI2_GYRO | 1
210 * BMI2_AUX | 2
211 * BMI2_ANY_MOTION | 4
212 * BMI2_NO_MOTION | 5
213 * BMI2_STEP_DETECTOR | 6
214 * BMI2_STEP_COUNTER | 7
215 * BMI2_STEP_ACTIVITY | 8
216 * BMI2_GYRO_GAIN_UPDATE | 9
217 * BMI2_WRIST_WEAR_WAKE_UP_WH | 21
218 *@endverbatim
220 * @note :
221 * example uint8_t sens_list[2] = {BMI2_ACCEL, BMI2_GYRO};
222 * uint8_t n_sens = 2;
224 * @return Result of API execution status
225 * @retval 0 -> Success
226 * @retval < 0 -> Fail
228 int8_t bmi270_wh_sensor_disable(const uint8_t *sens_list, uint8_t n_sens, struct bmi2_dev *dev);
231 * \ingroup bmi270_wh
232 * \defgroup bmi270_whApiSensorC Sensor Configuration
233 * @brief Enable / Disable feature configuration of the sensor
237 * \ingroup bmi270_whApiSensorC
238 * \page bmi270_wh_api_bmi270_wh_set_sensor_config bmi270_wh_set_sensor_config
239 * \code
240 * int8_t bmi270_wh_set_sensor_config(struct bmi2_sens_config *sens_cfg, uint8_t n_sens, struct bmi2_dev *dev);
241 * \endcode
242 * @details This API sets the sensor/feature configuration.
244 * @param[in] sens_cfg : Structure instance of bmi2_sens_config.
245 * @param[in] n_sens : Number of sensors selected.
246 * @param[in, out] dev : Structure instance of bmi2_dev.
248 * @note Sensors/features that can be configured
250 *@verbatim
251 * sens_list | Values
252 * ----------------------------|-----------
253 * BMI2_ANY_MOTION | 4
254 * BMI2_NO_MOTION | 5
255 * BMI2_STEP_DETECTOR | 6
256 * BMI2_STEP_COUNTER | 7
257 * BMI2_STEP_ACTIVITY | 8
258 * BMI2_WRIST_WEAR_WAKE_UP_WH | 21
259 * BMI2_STEP_COUNTER_PARAMS | 28
260 *@endverbatim
262 * @return Result of API execution status
263 * @retval 0 -> Success
264 * @retval < 0 -> Fail
266 int8_t bmi270_wh_set_sensor_config(struct bmi2_sens_config *sens_cfg, uint8_t n_sens, struct bmi2_dev *dev);
269 * \ingroup bmi270_whApiSensorC
270 * \page bmi270_wh_api_bmi270_wh_get_sensor_config bmi270_wh_get_sensor_config
271 * \code
272 * int8_t bmi270_wh_get_sensor_config(struct bmi2_sens_config *sens_cfg, uint8_t n_sens, struct bmi2_dev *dev);
273 * \endcode
274 * @details This API gets the sensor/feature configuration.
276 * @param[in] sens_cfg : Structure instance of bmi2_sens_config.
277 * @param[in] n_sens : Number of sensors selected.
278 * @param[in, out] dev : Structure instance of bmi2_dev.
280 * @note Sensors/features whose configurations can be read.
282 *@verbatim
283 * sens_list | Values
284 * ----------------------------|-----------
285 * BMI2_ANY_MOTION | 4
286 * BMI2_NO_MOTION | 5
287 * BMI2_STEP_DETECTOR | 6
288 * BMI2_STEP_COUNTER | 7
289 * BMI2_STEP_ACTIVITY | 8
290 * BMI2_WRIST_WEAR_WAKE_UP_WH | 21
291 * BMI2_STEP_COUNTER_PARAMS | 28
292 *@endverbatim
294 * @return Result of API execution status
295 * @retval 0 -> Success
296 * @retval < 0 -> Fail
298 int8_t bmi270_wh_get_sensor_config(struct bmi2_sens_config *sens_cfg, uint8_t n_sens, struct bmi2_dev *dev);
301 * \ingroup bmi270_wh
302 * \defgroup bmi270_whApiSensorD Sensor Data
303 * @brief Get sensor data
307 * \ingroup bmi270_whApiSensorD
308 * \page bmi270_wh_api_bmi270_wh_get_sensor_data bmi270_wh_get_sensor_data
309 * \code
310 * int8_t bmi270_wh_get_sensor_data(struct bmi2_sensor_data *sensor_data, uint8_t n_sens, struct bmi2_dev *dev);
311 * \endcode
312 * @details This API gets the sensor/feature data for accelerometer, gyroscope,
313 * auxiliary sensor, step counter, high-g, gyroscope user-gain update,
314 * orientation, gyroscope cross sensitivity and error status for NVM and VFRM.
316 * @param[out] sensor_data : Structure instance of bmi2_sensor_data.
317 * @param[in] n_sens : Number of sensors selected.
318 * @param[in] dev : Structure instance of bmi2_dev.
320 * @note Sensors/features whose data can be read
322 *@verbatim
323 * sens_list | Values
324 * ---------------------|-----------
325 * BMI2_STEP_COUNTER | 7
326 * BMI2_STEP_ACTIVITY | 8
327 * BMI2_NVM_STATUS | 38
328 * BMI2_VFRM_STATUS | 39
329 *@endverbatim
331 * @return Result of API execution status
332 * @retval 0 -> Success
333 * @retval < 0 -> Fail
335 int8_t bmi270_wh_get_sensor_data(struct bmi2_sensor_data *sensor_data, uint8_t n_sens, struct bmi2_dev *dev);
338 * \ingroup bmi270_wh
339 * \defgroup bmi270_whApiGyroUG Gyro User Gain
340 * @brief Set / Get Gyro User Gain of the sensor
344 * \ingroup bmi270_whApiGyroUG
345 * \page bmi270_wh_api_bmi270_wh_update_gyro_user_gain bmi270_wh_update_gyro_user_gain
346 * \code
347 * int8_t bmi270_wh_update_gyro_user_gain(const struct bmi2_gyro_user_gain_config *user_gain, struct bmi2_dev *dev);
348 * \endcode
349 * @details This API updates the gyroscope user-gain.
351 * @param[in] user_gain : Structure that stores user-gain configurations.
352 * @param[in] dev : Structure instance of bmi2_dev.
354 * @return Result of API execution status
355 * @retval 0 -> Success
356 * @retval < 0 -> Fail
358 int8_t bmi270_wh_update_gyro_user_gain(const struct bmi2_gyro_user_gain_config *user_gain, struct bmi2_dev *dev);
361 * \ingroup bmi270_whApiGyroUG
362 * \page bmi270_wh_api_bmi270_wh_read_gyro_user_gain bmi270_wh_read_gyro_user_gain
363 * \code
364 * int8_t bmi270_wh_read_gyro_user_gain(struct bmi2_gyro_user_gain_data *gyr_usr_gain, const struct bmi2_dev *dev);
365 * \endcode
366 * @details This API reads the compensated gyroscope user-gain values.
368 * @param[out] gyr_usr_gain : Structure that stores gain values.
369 * @param[in] dev : Structure instance of bmi2_dev.
371 * @return Result of API execution status
372 * @retval 0 -> Success
373 * @retval < 0 -> Fail
375 int8_t bmi270_wh_read_gyro_user_gain(struct bmi2_gyro_user_gain_data *gyr_usr_gain, struct bmi2_dev *dev);
378 * \ingroup bmi270_whApiInt
379 * \page bmi270_wh_api_bmi270_wh_map_feat_int bmi270_wh_map_feat_int
380 * \code
381 * int8_t bmi270_wh_map_feat_int(const struct bmi2_sens_int_config *sens_int, uint8_t n_sens, struct bmi2_dev *dev)
382 * \endcode
383 * @details This API maps/unmaps feature interrupts to that of interrupt pins.
385 * @param[in] sens_int : Structure instance of bmi2_sens_int_config.
386 * @param[in] n_sens : Number of interrupts to be mapped.
387 * @param[in] dev : Structure instance of bmi2_dev.
389 * @return Result of API execution status
390 * @retval 0 -> Success
391 * @retval < 0 -> Fail
393 int8_t bmi270_wh_map_feat_int(const struct bmi2_sens_int_config *sens_int, uint8_t n_sens, struct bmi2_dev *dev);
395 /******************************************************************************/
396 /*! @name C++ Guard Macros */
397 /******************************************************************************/
398 #ifdef __cplusplus
400 #endif /* End of CPP guard */
402 #endif /* BMI270_WH_H_ */