2 * Copyright (c) 2020 Bosch Sensortec GmbH. All rights reserved.
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.
42 /******************************************************************************/
43 /*! @name Header includes */
44 /******************************************************************************/
46 #include <linux/types.h>
47 #include <linux/kernel.h>
53 /******************************************************************************/
54 /*! @name Common macros */
55 /******************************************************************************/
57 #if !defined(UINT8_C) && !defined(INT8_C)
58 #define INT8_C(x) S8_C(x)
59 #define UINT8_C(x) U8_C(x)
62 #if !defined(UINT16_C) && !defined(INT16_C)
63 #define INT16_C(x) S16_C(x)
64 #define UINT16_C(x) U16_C(x)
67 #if !defined(INT32_C) && !defined(UINT32_C)
68 #define INT32_C(x) S32_C(x)
69 #define UINT32_C(x) U32_C(x)
72 #if !defined(INT64_C) && !defined(UINT64_C)
73 #define INT64_C(x) S64_C(x)
74 #define UINT64_C(x) U64_C(x)
78 /*! @name C standard macros */
83 #define NULL ((void *) 0)
87 /******************************************************************************/
88 /*! @name General Macro Definitions */
89 /******************************************************************************/
90 /*! @name Utility macros */
91 #define BMI2_SET_BITS(reg_data, bitname, data) \
92 ((reg_data & ~(bitname##_MASK)) | \
93 ((data << bitname##_POS) & bitname##_MASK))
95 #define BMI2_GET_BITS(reg_data, bitname) \
96 ((reg_data & (bitname##_MASK)) >> \
99 #define BMI2_SET_BIT_POS0(reg_data, bitname, data) \
100 ((reg_data & ~(bitname##_MASK)) | \
101 (data & bitname##_MASK))
103 #define BMI2_GET_BIT_POS0(reg_data, bitname) (reg_data & (bitname##_MASK))
104 #define BMI2_SET_BIT_VAL0(reg_data, bitname) (reg_data & ~(bitname##_MASK))
106 /*! @name For getting LSB and MSB */
107 #define BMI2_GET_LSB(var) (uint8_t)(var & BMI2_SET_LOW_BYTE)
108 #define BMI2_GET_MSB(var) (uint8_t)((var & BMI2_SET_HIGH_BYTE) >> 8)
110 #ifndef BMI2_INTF_RETURN_TYPE
111 #define BMI2_INTF_RETURN_TYPE int8_t
114 /*! @name For defining absolute values */
115 #define BMI2_ABS(a) ((a) > 0 ? (a) : -(a))
117 /*! @name LSB and MSB mask definitions */
118 #define BMI2_SET_LOW_BYTE UINT16_C(0x00FF)
119 #define BMI2_SET_HIGH_BYTE UINT16_C(0xFF00)
120 #define BMI2_SET_LOW_NIBBLE UINT8_C(0x0F)
122 /*! @name For enable and disable */
123 #define BMI2_ENABLE UINT8_C(1)
124 #define BMI2_DISABLE UINT8_C(0)
126 /*! @name To define TRUE or FALSE */
127 #define BMI2_TRUE UINT8_C(1)
128 #define BMI2_FALSE UINT8_C(0)
130 /*! @name To define sensor interface success code */
131 #define BMI2_INTF_RET_SUCCESS INT8_C(0)
133 /*! @name To define success code */
134 #define BMI2_OK INT8_C(0)
136 /*! @name To define error codes */
137 #define BMI2_E_NULL_PTR INT8_C(-1)
138 #define BMI2_E_COM_FAIL INT8_C(-2)
139 #define BMI2_E_DEV_NOT_FOUND INT8_C(-3)
140 #define BMI2_E_OUT_OF_RANGE INT8_C(-4)
141 #define BMI2_E_ACC_INVALID_CFG INT8_C(-5)
142 #define BMI2_E_GYRO_INVALID_CFG INT8_C(-6)
143 #define BMI2_E_ACC_GYR_INVALID_CFG INT8_C(-7)
144 #define BMI2_E_INVALID_SENSOR INT8_C(-8)
145 #define BMI2_E_CONFIG_LOAD INT8_C(-9)
146 #define BMI2_E_INVALID_PAGE INT8_C(-10)
147 #define BMI2_E_INVALID_FEAT_BIT INT8_C(-11)
148 #define BMI2_E_INVALID_INT_PIN INT8_C(-12)
149 #define BMI2_E_SET_APS_FAIL INT8_C(-13)
150 #define BMI2_E_AUX_INVALID_CFG INT8_C(-14)
151 #define BMI2_E_AUX_BUSY INT8_C(-15)
152 #define BMI2_E_SELF_TEST_FAIL INT8_C(-16)
153 #define BMI2_E_REMAP_ERROR INT8_C(-17)
154 #define BMI2_E_GYR_USER_GAIN_UPD_FAIL INT8_C(-18)
155 #define BMI2_E_SELF_TEST_NOT_DONE INT8_C(-19)
156 #define BMI2_E_INVALID_INPUT INT8_C(-20)
157 #define BMI2_E_INVALID_STATUS INT8_C(-21)
158 #define BMI2_E_CRT_ERROR INT8_C(-22)
159 #define BMI2_E_ST_ALREADY_RUNNING INT8_C(-23)
160 #define BMI2_E_CRT_READY_FOR_DL_FAIL_ABORT INT8_C(-24)
161 #define BMI2_E_DL_ERROR INT8_C(-25)
162 #define BMI2_E_PRECON_ERROR INT8_C(-26)
163 #define BMI2_E_ABORT_ERROR INT8_C(-27)
164 #define BMI2_E_GYRO_SELF_TEST_ERROR INT8_C(-28)
165 #define BMI2_E_GYRO_SELF_TEST_TIMEOUT INT8_C(-29)
166 #define BMI2_E_WRITE_CYCLE_ONGOING INT8_C(-30)
167 #define BMI2_E_WRITE_CYCLE_TIMEOUT INT8_C(-31)
168 #define BMI2_E_ST_NOT_RUNING INT8_C(-32)
169 #define BMI2_E_DATA_RDY_INT_FAILED INT8_C(-33)
170 #define BMI2_E_INVALID_FOC_POSITION INT8_C(-34)
172 /*! @name To define warnings for FIFO activity */
173 #define BMI2_W_FIFO_EMPTY INT8_C(1)
174 #define BMI2_W_PARTIAL_READ INT8_C(2)
176 /*! @name Bit wise to define information */
177 #define BMI2_I_MIN_VALUE UINT8_C(1)
178 #define BMI2_I_MAX_VALUE UINT8_C(2)
180 /*! @name BMI2 register addresses */
181 #define BMI2_CHIP_ID_ADDR UINT8_C(0x00)
182 #define BMI2_STATUS_ADDR UINT8_C(0x03)
183 #define BMI2_AUX_X_LSB_ADDR UINT8_C(0x04)
184 #define BMI2_ACC_X_LSB_ADDR UINT8_C(0x0C)
185 #define BMI2_GYR_X_LSB_ADDR UINT8_C(0x12)
186 #define BMI2_EVENT_ADDR UINT8_C(0x1B)
187 #define BMI2_INT_STATUS_0_ADDR UINT8_C(0x1C)
188 #define BMI2_INT_STATUS_1_ADDR UINT8_C(0x1D)
189 #define BMI2_SC_OUT_0_ADDR UINT8_C(0x1E)
190 #define BMI2_SYNC_COMMAND_ADDR UINT8_C(0x1E)
191 #define BMI2_GYR_CAS_GPIO0_ADDR UINT8_C(0x1E)
192 #define BMI2_INTERNAL_STATUS_ADDR UINT8_C(0x21)
193 #define BMI2_FIFO_LENGTH_0_ADDR UINT8_C(0X24)
194 #define BMI2_FIFO_DATA_ADDR UINT8_C(0X26)
195 #define BMI2_FEAT_PAGE_ADDR UINT8_C(0x2F)
196 #define BMI2_FEATURES_REG_ADDR UINT8_C(0x30)
197 #define BMI2_ACC_CONF_ADDR UINT8_C(0x40)
198 #define BMI2_GYR_CONF_ADDR UINT8_C(0x42)
199 #define BMI2_AUX_CONF_ADDR UINT8_C(0x44)
200 #define BMI2_FIFO_DOWNS_ADDR UINT8_C(0X45)
201 #define BMI2_FIFO_WTM_0_ADDR UINT8_C(0X46)
202 #define BMI2_FIFO_WTM_1_ADDR UINT8_C(0X47)
203 #define BMI2_FIFO_CONFIG_0_ADDR UINT8_C(0X48)
204 #define BMI2_FIFO_CONFIG_1_ADDR UINT8_C(0X49)
205 #define BMI2_AUX_DEV_ID_ADDR UINT8_C(0x4B)
206 #define BMI2_AUX_IF_CONF_ADDR UINT8_C(0x4C)
207 #define BMI2_AUX_RD_ADDR UINT8_C(0x4D)
208 #define BMI2_AUX_WR_ADDR UINT8_C(0x4E)
209 #define BMI2_AUX_WR_DATA_ADDR UINT8_C(0x4F)
210 #define BMI2_INT1_IO_CTRL_ADDR UINT8_C(0x53)
211 #define BMI2_INT2_IO_CTRL_ADDR UINT8_C(0x54)
212 #define BMI2_INT_LATCH_ADDR UINT8_C(0x55)
213 #define BMI2_INT1_MAP_FEAT_ADDR UINT8_C(0x56)
214 #define BMI2_INT2_MAP_FEAT_ADDR UINT8_C(0x57)
215 #define BMI2_INT_MAP_DATA_ADDR UINT8_C(0x58)
216 #define BMI2_INIT_CTRL_ADDR UINT8_C(0x59)
217 #define BMI2_INIT_ADDR_0 UINT8_C(0x5B)
218 #define BMI2_INIT_ADDR_1 UINT8_C(0x5C)
219 #define BMI2_INIT_DATA_ADDR UINT8_C(0x5E)
220 #define BMI2_AUX_IF_TRIM UINT8_C(0x68)
221 #define BMI2_GYR_CRT_CONF_ADDR UINT8_C(0X69)
222 #define BMI2_NVM_CONF_ADDR UINT8_C(0x6A)
223 #define BMI2_IF_CONF_ADDR UINT8_C(0X6B)
224 #define BMI2_ACC_SELF_TEST_ADDR UINT8_C(0X6D)
225 #define BMI2_GYR_SELF_TEST_AXES_ADDR UINT8_C(0x6E)
226 #define BMI2_SELF_TEST_MEMS_ADDR UINT8_C(0X6F)
227 #define BMI2_NV_CONF_ADDR UINT8_C(0x70)
228 #define BMI2_ACC_OFF_COMP_0_ADDR UINT8_C(0X71)
229 #define BMI2_GYR_OFF_COMP_3_ADDR UINT8_C(0X74)
230 #define BMI2_GYR_OFF_COMP_6_ADDR UINT8_C(0X77)
231 #define BMI2_GYR_USR_GAIN_0_ADDR UINT8_C(0X78)
232 #define BMI2_PWR_CONF_ADDR UINT8_C(0x7C)
233 #define BMI2_PWR_CTRL_ADDR UINT8_C(0x7D)
234 #define BMI2_CMD_REG_ADDR UINT8_C(0x7E)
236 /*! @name BMI2 I2C address */
237 #define BMI2_I2C_PRIM_ADDR UINT8_C(0x68)
238 #define BMI2_I2C_SEC_ADDR UINT8_C(0x69)
240 /*! @name BMI2 Commands */
241 #define BMI2_G_TRIGGER_CMD UINT8_C(0x02)
242 #define BMI2_USR_GAIN_CMD UINT8_C(0x03)
243 #define BMI2_NVM_PROG_CMD UINT8_C(0xA0)
244 #define BMI2_SOFT_RESET_CMD UINT8_C(0xB6)
245 #define BMI2_FIFO_FLUSH_CMD UINT8_C(0xB0)
247 /*! @name BMI2 sensor data bytes */
249 #define BMI2_ACC_GYR_NUM_BYTES UINT8_C(6)
250 #define BMI2_AUX_NUM_BYTES UINT8_C(8)
251 #define BMI2_CRT_CONFIG_FILE_SIZE UINT16_C(2048)
252 #define BMI2_FEAT_SIZE_IN_BYTES UINT8_C(16)
253 #define BMI2_ACC_CONFIG_LENGTH UINT8_C(2)
255 /*! @name BMI2 configuration load status */
256 #define BMI2_CONFIG_LOAD_SUCCESS UINT8_C(1)
258 /*! @name To define BMI2 pages */
259 #define BMI2_PAGE_0 UINT8_C(0)
260 #define BMI2_PAGE_1 UINT8_C(1)
261 #define BMI2_PAGE_2 UINT8_C(2)
262 #define BMI2_PAGE_3 UINT8_C(3)
263 #define BMI2_PAGE_4 UINT8_C(4)
264 #define BMI2_PAGE_5 UINT8_C(5)
265 #define BMI2_PAGE_6 UINT8_C(6)
266 #define BMI2_PAGE_7 UINT8_C(7)
268 /*! @name Array Parameter DefinItions */
269 #define BMI2_SENSOR_TIME_LSB_BYTE UINT8_C(0)
270 #define BMI2_SENSOR_TIME_XLSB_BYTE UINT8_C(1)
271 #define BMI2_SENSOR_TIME_MSB_BYTE UINT8_C(2)
273 /*! @name Mask definitions for Gyro CRT */
274 #define BMI2_GYR_RDY_FOR_DL_MASK UINT8_C(0x08)
275 #define BMI2_GYR_CRT_RUNNING_MASK UINT8_C(0x04)
277 /*! @name mask definition for status register */
278 #define BMI2_AUX_BUSY_MASK UINT8_C(0x04)
279 #define BMI2_CMD_RDY_MASK UINT8_C(0x10)
280 #define BMI2_DRDY_AUX_MASK UINT8_C(0x20)
281 #define BMI2_DRDY_GYR_MASK UINT8_C(0x40)
282 #define BMI2_DRDY_ACC_MASK UINT8_C(0x80)
284 /*! @name Mask definitions for SPI read/write address */
285 #define BMI2_SPI_RD_MASK UINT8_C(0x80)
286 #define BMI2_SPI_WR_MASK UINT8_C(0x7F)
288 /*! @name Mask definitions for power configuration register */
289 #define BMI2_ADV_POW_EN_MASK UINT8_C(0x01)
291 /*! @name Mask definitions for initialization control register */
292 #define BMI2_CONF_LOAD_EN_MASK UINT8_C(0x01)
294 /*! @name Mask definitions for power control register */
295 #define BMI2_AUX_EN_MASK UINT8_C(0x01)
296 #define BMI2_GYR_EN_MASK UINT8_C(0x02)
297 #define BMI2_ACC_EN_MASK UINT8_C(0x04)
298 #define BMI2_TEMP_EN_MASK UINT8_C(0x08)
300 /*! @name Mask definitions for sensor event flags */
301 #define BMI2_EVENT_FLAG_MASK UINT8_C(0x1C)
303 /*! @name Mask definitions to switch page */
304 #define BMI2_SWITCH_PAGE_EN_MASK UINT8_C(0x07)
306 /*! @name Mask definitions of NVM register */
307 #define BMI2_NV_ACC_OFFSET_MASK UINT8_C(0x08)
309 /*! @name Mask definition for config version */
310 #define BMI2_CONFIG_MAJOR_MASK UINT16_C(0x3C0)
311 #define BMI2_CONFIG_MINOR_MASK UINT8_C(0x3F)
313 /*! @name mask and bit position for activity recognition settings */
314 #define BMI2_ACT_RECG_POST_PROS_EN_DIS_MASK UINT8_C(0x01)
315 #define BMI2_ACT_RECG_BUFF_SIZE_MASK UINT8_C(0x0F)
316 #define BMI2_ACT_RECG_MIN_SEG_CONF_MASK UINT8_C(0x0F)
318 /*! @name mask and bit position for activity recognition hc settings */
319 #define BMI2_HC_ACT_RECG_SEGMENT_SIZE_MASK UINT8_C(0x03)
320 #define BMI2_HC_ACT_RECG_PP_EN_MASK UINT8_C(0x01)
321 #define BMI2_HC_ACT_RECG_MIN_GDI_THRES_MASK UINT16_C(0xFFFF)
322 #define BMI2_HC_ACT_RECG_MAX_GDI_THRES_MASK UINT16_C(0xFFFF)
323 #define BMI2_HC_ACT_RECG_BUF_SIZE_MASK UINT16_C(0xFFFF)
324 #define BMI2_HC_ACT_RECG_MIN_SEG_CONF_MASK UINT16_C(0xFFFF)
326 #define BMI2_GYRO_CROSS_AXES_SENSE_MASK UINT8_C(0x7F)
327 #define BMI2_GYRO_CROSS_AXES_SENSE_SIGN_BIT_MASK UINT8_C(0x40)
329 /*! @name Bit position definitions for Gyro CRT */
330 #define BMI2_GYR_RDY_FOR_DL_POS UINT8_C(0x03)
331 #define BMI2_GYR_CRT_RUNNING_POS UINT8_C(0x02)
333 /*! @name Bit position for status register*/
334 #define BMI2_AUX_BUSY_POS UINT8_C(0x02)
335 #define BMI2_CMD_RDY_POS UINT8_C(0x04)
336 #define BMI2_DRDY_AUX_POS UINT8_C(0x05)
337 #define BMI2_DRDY_GYR_POS UINT8_C(0x06)
338 #define BMI2_DRDY_ACC_POS UINT8_C(0x07)
340 /*! @name Bit position definitions for power control register */
341 #define BMI2_GYR_EN_POS UINT8_C(0x01)
342 #define BMI2_ACC_EN_POS UINT8_C(0x02)
343 #define BMI2_TEMP_EN_POS UINT8_C(0x03)
345 /*! @name Bit position definitions for sensor event flags */
346 #define BMI2_EVENT_FLAG_POS UINT8_C(0x02)
348 /*! @name Bit position definitions of NVM register */
349 #define BMI2_NV_ACC_OFFSET_POS UINT8_C(0x03)
351 /*! @name Bit position for major version from config */
352 #define BMI2_CONFIG_MAJOR_POS UINT8_C(0x06)
354 /*! @name Accelerometer and Gyroscope Filter/Noise performance modes */
355 /* Power optimized mode */
356 #define BMI2_POWER_OPT_MODE UINT8_C(0)
358 /* Performance optimized */
359 #define BMI2_PERF_OPT_MODE UINT8_C(1)
361 /*! @name index for config major minor information */
362 #define BMI2_CONFIG_INFO_LOWER UINT8_C(52)
363 #define BMI2_CONFIG_INFO_HIGHER UINT8_C(53)
365 /*! @name Sensor status */
366 #define BMI2_DRDY_ACC UINT8_C(0x80)
367 #define BMI2_DRDY_GYR UINT8_C(0x40)
368 #define BMI2_DRDY_AUX UINT8_C(0x20)
369 #define BMI2_CMD_RDY UINT8_C(0x10)
370 #define BMI2_AUX_BUSY UINT8_C(0x04)
372 /*! @name Macro to define accelerometer configuration value for FOC */
373 #define BMI2_FOC_ACC_CONF_VAL UINT8_C(0xB7)
375 /*! @name Macro to define gyroscope configuration value for FOC */
376 #define BMI2_FOC_GYR_CONF_VAL UINT8_C(0xB6)
378 /*! @name Macro to define X Y and Z axis for an array */
379 #define BMI2_X_AXIS UINT8_C(0)
380 #define BMI2_Y_AXIS UINT8_C(1)
381 #define BMI2_Z_AXIS UINT8_C(2)
383 /******************************************************************************/
384 /*! @name Sensor Macro Definitions */
385 /******************************************************************************/
386 /*! @name Macros to define BMI2 sensor/feature types */
387 #define BMI2_ACCEL UINT8_C(0)
388 #define BMI2_GYRO UINT8_C(1)
389 #define BMI2_AUX UINT8_C(2)
390 #define BMI2_SIG_MOTION UINT8_C(3)
391 #define BMI2_ANY_MOTION UINT8_C(4)
392 #define BMI2_NO_MOTION UINT8_C(5)
393 #define BMI2_STEP_DETECTOR UINT8_C(6)
394 #define BMI2_STEP_COUNTER UINT8_C(7)
395 #define BMI2_STEP_ACTIVITY UINT8_C(8)
396 #define BMI2_GYRO_GAIN_UPDATE UINT8_C(9)
397 #define BMI2_TILT UINT8_C(10)
398 #define BMI2_UP_HOLD_TO_WAKE UINT8_C(11)
399 #define BMI2_GLANCE_DETECTOR UINT8_C(12)
400 #define BMI2_WAKE_UP UINT8_C(13)
401 #define BMI2_ORIENTATION UINT8_C(14)
402 #define BMI2_HIGH_G UINT8_C(15)
403 #define BMI2_LOW_G UINT8_C(16)
404 #define BMI2_FLAT UINT8_C(17)
405 #define BMI2_EXT_SENS_SYNC UINT8_C(18)
406 #define BMI2_WRIST_GESTURE UINT8_C(19)
407 #define BMI2_WRIST_WEAR_WAKE_UP UINT8_C(20)
408 #define BMI2_WRIST_WEAR_WAKE_UP_WH UINT8_C(21)
409 #define BMI2_WRIST_GESTURE_WH UINT8_C(22)
410 #define BMI2_PRIMARY_OIS UINT8_C(23)
411 #define BMI2_FREE_FALL_DET UINT8_C(24)
412 #define BMI2_SINGLE_TAP UINT8_C(25)
413 #define BMI2_DOUBLE_TAP UINT8_C(26)
414 #define BMI2_TRIPLE_TAP UINT8_C(27)
415 #define BMI2_TAP UINT8_C(28)
417 /* Non virtual sensor features */
418 #define BMI2_STEP_COUNTER_PARAMS UINT8_C(29)
419 #define BMI2_TAP_DETECTOR_1 UINT8_C(30)
420 #define BMI2_TAP_DETECTOR_2 UINT8_C(31)
421 #define BMI2_TEMP UINT8_C(32)
422 #define BMI2_ACCEL_SELF_TEST UINT8_C(33)
423 #define BMI2_GYRO_SELF_OFF UINT8_C(34)
424 #define BMI2_ACTIVITY_RECOGNITION UINT8_C(35)
425 #define BMI2_MAX_BURST_LEN UINT8_C(36)
426 #define BMI2_SENS_MAX_NUM UINT8_C(37)
427 #define BMI2_AXIS_MAP UINT8_C(38)
428 #define BMI2_NVM_STATUS UINT8_C(39)
429 #define BMI2_VFRM_STATUS UINT8_C(40)
430 #define BMI2_GYRO_CROSS_SENSE UINT8_C(41)
431 #define BMI2_CRT_GYRO_SELF_TEST UINT8_C(42)
432 #define BMI2_ABORT_CRT_GYRO_SELF_TEST UINT8_C(43)
433 #define BMI2_NVM_PROG_PREP UINT8_C(44)
434 #define BMI2_ACTIVITY_RECOGNITION_SETTINGS UINT8_C(45)
435 #define BMI2_OIS_OUTPUT UINT8_C(46)
436 #define BMI2_CONFIG_ID UINT8_C(47)
438 /*! @name Bit wise for selecting BMI2 sensors/features */
439 #define BMI2_ACCEL_SENS_SEL (1)
440 #define BMI2_GYRO_SENS_SEL (1 << BMI2_GYRO)
441 #define BMI2_AUX_SENS_SEL (1 << BMI2_AUX)
442 #define BMI2_TEMP_SENS_SEL ((uint64_t)1 << BMI2_TEMP)
443 #define BMI2_ANY_MOT_SEL (1 << BMI2_ANY_MOTION)
444 #define BMI2_NO_MOT_SEL (1 << BMI2_NO_MOTION)
445 #define BMI2_TILT_SEL (1 << BMI2_TILT)
446 #define BMI2_ORIENT_SEL (1 << BMI2_ORIENTATION)
447 #define BMI2_SIG_MOTION_SEL (1 << BMI2_SIG_MOTION)
448 #define BMI2_STEP_DETECT_SEL (1 << BMI2_STEP_DETECTOR)
449 #define BMI2_STEP_COUNT_SEL (1 << BMI2_STEP_COUNTER)
450 #define BMI2_STEP_ACT_SEL (1 << BMI2_STEP_ACTIVITY)
451 #define BMI2_GYRO_GAIN_UPDATE_SEL (1 << BMI2_GYRO_GAIN_UPDATE)
452 #define BMI2_UP_HOLD_TO_WAKE_SEL (1 << BMI2_UP_HOLD_TO_WAKE)
453 #define BMI2_GLANCE_DET_SEL (1 << BMI2_GLANCE_DETECTOR)
454 #define BMI2_WAKE_UP_SEL (1 << BMI2_WAKE_UP)
455 #define BMI2_TAP_SEL (1 << BMI2_TAP)
456 #define BMI2_HIGH_G_SEL (1 << BMI2_HIGH_G)
457 #define BMI2_LOW_G_SEL (1 << BMI2_LOW_G)
458 #define BMI2_FLAT_SEL (1 << BMI2_FLAT)
459 #define BMI2_EXT_SENS_SEL (1 << BMI2_EXT_SENS_SYNC)
460 #define BMI2_SINGLE_TAP_SEL (1 << BMI2_SINGLE_TAP)
461 #define BMI2_DOUBLE_TAP_SEL (1 << BMI2_DOUBLE_TAP)
462 #define BMI2_TRIPLE_TAP_SEL (1 << BMI2_TRIPLE_TAP)
463 #define BMI2_GYRO_SELF_OFF_SEL ((uint64_t)1 << BMI2_GYRO_SELF_OFF)
464 #define BMI2_WRIST_GEST_SEL (1 << BMI2_WRIST_GESTURE)
465 #define BMI2_WRIST_WEAR_WAKE_UP_SEL (1 << BMI2_WRIST_WEAR_WAKE_UP)
466 #define BMI2_ACTIVITY_RECOGNITION_SEL ((uint64_t)1 << BMI2_ACTIVITY_RECOGNITION)
467 #define BMI2_ACCEL_SELF_TEST_SEL ((uint64_t)1 << BMI2_ACCEL_SELF_TEST)
468 #define BMI2_WRIST_GEST_W_SEL (1 << BMI2_WRIST_GESTURE_WH)
469 #define BMI2_WRIST_WEAR_WAKE_UP_WH_SEL (1 << BMI2_WRIST_WEAR_WAKE_UP_WH)
470 #define BMI2_PRIMARY_OIS_SEL (1 << BMI2_PRIMARY_OIS)
471 #define BMI2_FREE_FALL_DET_SEL (1 << BMI2_FREE_FALL_DET)
473 /*! @name Mask definitions for BMI2 wake-up feature configuration for bmi260 */
474 #define BMI2_WAKEUP_SENSITIVITY_MASK UINT8_C(0x0E)
475 #define BMI2_WAKEUP_SINGLE_TAP_EN_MASK UINT8_C(0x01)
476 #define BMI2_WAKEUP_DOUBLE_TAP_EN_MASK UINT8_C(0x02)
477 #define BMI2_WAKEUP_TRIPLE_TAP_EN_MASK UINT8_C(0x04)
478 #define BMI2_WAKEUP_DATA_REG_EN_MASK UINT8_C(0x08)
479 #define BMI2_WAKEUP_AXIS_SEL_MASK UINT8_C(0x03)
481 /*! @name Bit position definitions for BMI2 wake-up feature configuration for bmi260 */
482 #define BMI2_WAKEUP_SENSITIVITY_POS UINT8_C(0x01)
483 #define BMI2_WAKEUP_DOUBLE_TAP_EN_POS UINT8_C(0x01)
484 #define BMI2_WAKEUP_TRIPLE_TAP_EN_POS UINT8_C(0x02)
485 #define BMI2_WAKEUP_DATA_REG_EN_POS UINT8_C(0x03)
487 /*! @name Mask definitions for BMI2 tap feature configuration for bmi260t */
488 #define BMI2_TAP_SENSITIVITY_MASK UINT8_C(0x0E)
489 #define BMI2_TAP_SINGLE_TAP_EN_MASK UINT8_C(0x01)
490 #define BMI2_TAP_DOUBLE_TAP_EN_MASK UINT8_C(0x02)
491 #define BMI2_TAP_TRIPLE_TAP_EN_MASK UINT8_C(0x04)
492 #define BMI2_TAP_DATA_REG_EN_MASK UINT8_C(0x08)
493 #define BMI2_TAP_AXIS_SEL_MASK UINT8_C(0x03)
495 /*! @name Bit position definitions for BMI2 tap feature configuration for bmi260t */
496 #define BMI2_TAP_SENSITIVITY_POS UINT8_C(0x01)
497 #define BMI2_TAP_DOUBLE_TAP_EN_POS UINT8_C(0x01)
498 #define BMI2_TAP_TRIPLE_TAP_EN_POS UINT8_C(0x02)
499 #define BMI2_TAP_DATA_REG_EN_POS UINT8_C(0x03)
501 /*! @name Mask definitions for BMI2 wake-up feature configuration for other than bmi261 */
502 #define BMI2_WAKE_UP_SENSITIVITY_MASK UINT16_C(0x000E)
503 #define BMI2_WAKE_UP_SINGLE_TAP_EN_MASK UINT16_C(0x0010)
505 /*! @name Bit position definitions for BMI2 wake-up feature configuration for other than bmi261 */
506 #define BMI2_WAKE_UP_SENSITIVITY_POS UINT8_C(0x01)
507 #define BMI2_WAKE_UP_SINGLE_TAP_EN_POS UINT8_C(0x04)
509 /*! @name Offsets from feature start address for BMI2 feature enable/disable */
510 #define BMI2_ANY_MOT_FEAT_EN_OFFSET UINT8_C(0x03)
511 #define BMI2_NO_MOT_FEAT_EN_OFFSET UINT8_C(0x03)
512 #define BMI2_SIG_MOT_FEAT_EN_OFFSET UINT8_C(0x0A)
513 #define BMI2_STEP_COUNT_FEAT_EN_OFFSET UINT8_C(0x01)
514 #define BMI2_GYR_USER_GAIN_FEAT_EN_OFFSET UINT8_C(0x05)
515 #define BMI2_HIGH_G_FEAT_EN_OFFSET UINT8_C(0x03)
516 #define BMI2_LOW_G_FEAT_EN_OFFSET UINT8_C(0x03)
517 #define BMI2_TILT_FEAT_EN_OFFSET UINT8_C(0x00)
519 /*! @name Mask definitions for BMI2 feature enable/disable */
520 #define BMI2_ANY_NO_MOT_EN_MASK UINT8_C(0x80)
521 #define BMI2_TILT_FEAT_EN_MASK UINT8_C(0x01)
522 #define BMI2_ORIENT_FEAT_EN_MASK UINT8_C(0x01)
523 #define BMI2_SIG_MOT_FEAT_EN_MASK UINT8_C(0x01)
524 #define BMI2_STEP_DET_FEAT_EN_MASK UINT8_C(0x08)
525 #define BMI2_STEP_COUNT_FEAT_EN_MASK UINT8_C(0x10)
526 #define BMI2_STEP_ACT_FEAT_EN_MASK UINT8_C(0x20)
527 #define BMI2_GYR_USER_GAIN_FEAT_EN_MASK UINT8_C(0x08)
528 #define BMI2_UP_HOLD_TO_WAKE_FEAT_EN_MASK UINT8_C(0x01)
529 #define BMI2_GLANCE_FEAT_EN_MASK UINT8_C(0x01)
530 #define BMI2_WAKE_UP_FEAT_EN_MASK UINT8_C(0x01)
531 #define BMI2_TAP_FEAT_EN_MASK UINT8_C(0x01)
532 #define BMI2_HIGH_G_FEAT_EN_MASK UINT8_C(0x80)
533 #define BMI2_LOW_G_FEAT_EN_MASK UINT8_C(0x10)
534 #define BMI2_FLAT_FEAT_EN_MASK UINT8_C(0x01)
535 #define BMI2_EXT_SENS_SYNC_FEAT_EN_MASK UINT8_C(0x01)
536 #define BMI2_GYR_SELF_OFF_CORR_FEAT_EN_MASK UINT8_C(0x02)
537 #define BMI2_WRIST_GEST_FEAT_EN_MASK UINT8_C(0x20)
538 #define BMI2_WRIST_WEAR_WAKE_UP_FEAT_EN_MASK UINT8_C(0x10)
539 #define BMI2_ACTIVITY_RECOG_EN_MASK UINT8_C(0x01)
540 #define BMI2_ACC_SELF_TEST_FEAT_EN_MASK UINT8_C(0x02)
541 #define BMI2_GYRO_SELF_TEST_CRT_EN_MASK UINT8_C(0x01)
542 #define BMI2_ABORT_FEATURE_EN_MASK UINT8_C(0x02)
543 #define BMI2_NVM_PREP_FEATURE_EN_MASK UINT8_C(0x04)
544 #define BMI2_FREE_FALL_DET_FEAT_EN_MASK UINT8_C(0x01)
545 #define BMI2_WRIST_GEST_WH_FEAT_EN_MASK UINT8_C(0x02)
547 /*! @name Bit position definitions for BMI2 feature enable/disable */
548 #define BMI2_ANY_NO_MOT_EN_POS UINT8_C(0x07)
549 #define BMI2_STEP_DET_FEAT_EN_POS UINT8_C(0x03)
550 #define BMI2_STEP_COUNT_FEAT_EN_POS UINT8_C(0x04)
551 #define BMI2_STEP_ACT_FEAT_EN_POS UINT8_C(0x05)
552 #define BMI2_GYR_USER_GAIN_FEAT_EN_POS UINT8_C(0x03)
553 #define BMI2_HIGH_G_FEAT_EN_POS UINT8_C(0x07)
554 #define BMI2_LOW_G_FEAT_EN_POS UINT8_C(0x04)
555 #define BMI2_GYR_SELF_OFF_CORR_FEAT_EN_POS UINT8_C(0x01)
556 #define BMI2_WRIST_GEST_FEAT_EN_POS UINT8_C(0x05)
557 #define BMI2_WRIST_WEAR_WAKE_UP_FEAT_EN_POS UINT8_C(0x04)
558 #define BMI2_ACC_SELF_TEST_FEAT_EN_POS UINT8_C(0x01)
559 #define BMI2_ABORT_FEATURE_EN_POS UINT8_C(0x1)
560 #define BMI2_NVM_PREP_FEATURE_EN_POS UINT8_C(0x02)
561 #define BMI2_WRIST_GEST_WH_FEAT_EN_POS UINT8_C(0x01)
563 /*! Primary OIS low pass filter configuration position and mask */
564 #define BMI2_LP_FILTER_EN_MASK UINT8_C(0x01)
566 #define BMI2_LP_FILTER_CONFIG_POS UINT8_C(0x01)
567 #define BMI2_LP_FILTER_CONFIG_MASK UINT8_C(0x06)
569 #define BMI2_PRIMARY_OIS_GYR_EN_POS UINT8_C(0x06)
570 #define BMI2_PRIMARY_OIS_GYR_EN_MASK UINT8_C(0x40)
572 #define BMI2_PRIMARY_OIS_ACC_EN_POS UINT8_C(0x07)
573 #define BMI2_PRIMARY_OIS_ACC_EN_MASK UINT8_C(0x80)
575 /*! @name Mask definitions for BMI2 any and no-motion feature configuration */
576 #define BMI2_ANY_NO_MOT_DUR_MASK UINT16_C(0x1FFF)
577 #define BMI2_ANY_NO_MOT_X_SEL_MASK UINT16_C(0x2000)
578 #define BMI2_ANY_NO_MOT_Y_SEL_MASK UINT16_C(0x4000)
579 #define BMI2_ANY_NO_MOT_Z_SEL_MASK UINT16_C(0x8000)
580 #define BMI2_ANY_NO_MOT_THRES_MASK UINT16_C(0x07FF)
581 #define BMI2_ANY_MOT_INT_MASK UINT8_C(0x40)
583 /*! @name Mask definitions for BMI2 no-motion interrupt mapping */
584 #define BMI2_NO_MOT_INT_MASK UINT8_C(0x20)
586 /*! @name Bit position definitions for BMI2 any and no-motion feature
589 #define BMI2_ANY_NO_MOT_X_SEL_POS UINT8_C(0x0D)
590 #define BMI2_ANY_NO_MOT_Y_SEL_POS UINT8_C(0x0E)
591 #define BMI2_ANY_NO_MOT_Z_SEL_POS UINT8_C(0x0F)
593 /*! @name Mask definitions for BMI2 orientation feature configuration */
594 #define BMI2_ORIENT_UP_DOWN_MASK UINT16_C(0x0002)
595 #define BMI2_ORIENT_SYMM_MODE_MASK UINT16_C(0x000C)
596 #define BMI2_ORIENT_BLOCK_MODE_MASK UINT16_C(0x0030)
597 #define BMI2_ORIENT_THETA_MASK UINT16_C(0x0FC0)
598 #define BMI2_ORIENT_HYST_MASK UINT16_C(0x07FF)
600 /*! @name Bit position definitions for BMI2 orientation feature configuration */
601 #define BMI2_ORIENT_UP_DOWN_POS UINT8_C(0x01)
602 #define BMI2_ORIENT_SYMM_MODE_POS UINT8_C(0x02)
603 #define BMI2_ORIENT_BLOCK_MODE_POS UINT8_C(0x04)
604 #define BMI2_ORIENT_THETA_POS UINT8_C(0x06)
606 /*! @name Mask definitions for BMI2 sig-motion feature configuration */
607 #define BMI2_SIG_MOT_PARAM_1_MASK UINT16_C(0xFFFF)
608 #define BMI2_SIG_MOT_PARAM_2_MASK UINT16_C(0xFFFF)
609 #define BMI2_SIG_MOT_PARAM_3_MASK UINT16_C(0xFFFF)
610 #define BMI2_SIG_MOT_PARAM_4_MASK UINT16_C(0xFFFF)
611 #define BMI2_SIG_MOT_PARAM_5_MASK UINT16_C(0xFFFF)
613 /*! @name Mask definitions for BMI2 parameter configurations */
614 #define BMI2_STEP_COUNT_PARAMS_MASK UINT16_C(0xFFFF)
616 /*! @name Mask definitions for BMI2 step-counter/detector feature configuration */
617 #define BMI2_STEP_COUNT_WM_LEVEL_MASK UINT16_C(0x03FF)
618 #define BMI2_STEP_COUNT_RST_CNT_MASK UINT16_C(0x0400)
619 #define BMI2_STEP_BUFFER_SIZE_MASK UINT16_C(0XFF00)
620 #define BMI2_STEP_COUNT_INT_MASK UINT8_C(0x02)
621 #define BMI2_STEP_ACT_INT_MASK UINT8_C(0x04)
623 /*! @name Bit position definitions for BMI2 step-counter/detector feature
626 #define BMI2_STEP_COUNT_RST_CNT_POS UINT8_C(0x0A)
627 #define BMI2_STEP_BUFFER_SIZE_POS UINT8_C(0X08)
629 /*! @name Mask definitions for BMI2 gyroscope user gain feature
632 #define BMI2_GYR_USER_GAIN_RATIO_X_MASK UINT16_C(0x07FF)
633 #define BMI2_GYR_USER_GAIN_RATIO_Y_MASK UINT16_C(0x07FF)
634 #define BMI2_GYR_USER_GAIN_RATIO_Z_MASK UINT16_C(0x07FF)
636 /*! @name Mask definitions for BMI2 gyroscope user gain saturation status */
637 #define BMI2_GYR_USER_GAIN_SAT_STAT_X_MASK UINT8_C(0x01)
638 #define BMI2_GYR_USER_GAIN_SAT_STAT_Y_MASK UINT8_C(0x02)
639 #define BMI2_GYR_USER_GAIN_SAT_STAT_Z_MASK UINT8_C(0x04)
640 #define BMI2_G_TRIGGER_STAT_MASK UINT8_C(0x38)
642 /*! @name Bit position definitions for BMI2 gyroscope user gain saturation status */
643 #define BMI2_GYR_USER_GAIN_SAT_STAT_Y_POS UINT8_C(0x01)
644 #define BMI2_GYR_USER_GAIN_SAT_STAT_Z_POS UINT8_C(0x02)
645 #define BMI2_G_TRIGGER_STAT_POS UINT8_C(0x03)
647 /*! @name Mask definitions for MSB values of BMI2 gyroscope compensation */
648 #define BMI2_GYR_OFF_COMP_MSB_X_MASK UINT8_C(0x03)
649 #define BMI2_GYR_OFF_COMP_MSB_Y_MASK UINT8_C(0x0C)
650 #define BMI2_GYR_OFF_COMP_MSB_Z_MASK UINT8_C(0x30)
652 /*! @name Bit positions for MSB values of BMI2 gyroscope compensation */
653 #define BMI2_GYR_OFF_COMP_MSB_Y_POS UINT8_C(0x02)
654 #define BMI2_GYR_OFF_COMP_MSB_Z_POS UINT8_C(0x04)
656 /*! @name Mask definitions for MSB values of BMI2 gyroscope compensation from user input */
657 #define BMI2_GYR_OFF_COMP_MSB_MASK UINT16_C(0x0300)
658 #define BMI2_GYR_OFF_COMP_LSB_MASK UINT16_C(0x00FF)
660 /*! @name Mask definitions for BMI2 orientation status */
661 #define BMI2_ORIENT_DETECT_MASK UINT8_C(0x03)
662 #define BMI2_ORIENT_FACE_UP_DWN_MASK UINT8_C(0x04)
664 /*! @name Bit position definitions for BMI2 orientation status */
665 #define BMI2_ORIENT_FACE_UP_DWN_POS UINT8_C(0x02)
667 /*! @name Mask definitions for NVM-VFRM error status */
668 #define BMI2_NVM_LOAD_ERR_STATUS_MASK UINT8_C(0x01)
669 #define BMI2_NVM_PROG_ERR_STATUS_MASK UINT8_C(0x02)
670 #define BMI2_NVM_ERASE_ERR_STATUS_MASK UINT8_C(0x04)
671 #define BMI2_NVM_END_EXCEED_STATUS_MASK UINT8_C(0x08)
672 #define BMI2_NVM_PRIV_ERR_STATUS_MASK UINT8_C(0x10)
673 #define BMI2_VFRM_LOCK_ERR_STATUS_MASK UINT8_C(0x20)
674 #define BMI2_VFRM_WRITE_ERR_STATUS_MASK UINT8_C(0x40)
675 #define BMI2_VFRM_FATAL_ERR_STATUS_MASK UINT8_C(0x80)
677 /*! @name Bit positions for NVM-VFRM error status */
678 #define BMI2_NVM_PROG_ERR_STATUS_POS UINT8_C(0x01)
679 #define BMI2_NVM_ERASE_ERR_STATUS_POS UINT8_C(0x02)
680 #define BMI2_NVM_END_EXCEED_STATUS_POS UINT8_C(0x03)
681 #define BMI2_NVM_PRIV_ERR_STATUS_POS UINT8_C(0x04)
682 #define BMI2_VFRM_LOCK_ERR_STATUS_POS UINT8_C(0x05)
683 #define BMI2_VFRM_WRITE_ERR_STATUS_POS UINT8_C(0x06)
684 #define BMI2_VFRM_FATAL_ERR_STATUS_POS UINT8_C(0x07)
686 /*! @name Mask definitions for accelerometer self-test status */
687 #define BMI2_ACC_SELF_TEST_DONE_MASK UINT8_C(0x01)
688 #define BMI2_ACC_X_OK_MASK UINT8_C(0x02)
689 #define BMI2_ACC_Y_OK_MASK UINT8_C(0x04)
690 #define BMI2_ACC_Z_OK_MASK UINT8_C(0x08)
692 /*! @name Bit Positions for accelerometer self-test status */
693 #define BMI2_ACC_X_OK_POS UINT8_C(0x01)
694 #define BMI2_ACC_Y_OK_POS UINT8_C(0x02)
695 #define BMI2_ACC_Z_OK_POS UINT8_C(0x03)
697 /*! @name Mask definitions for BMI2 high-g feature configuration */
698 #define BMI2_HIGH_G_THRES_MASK UINT16_C(0x7FFF)
699 #define BMI2_HIGH_G_HYST_MASK UINT16_C(0x0FFF)
700 #define BMI2_HIGH_G_X_SEL_MASK UINT16_C(0x1000)
701 #define BMI2_HIGH_G_Y_SEL_MASK UINT16_C(0x2000)
702 #define BMI2_HIGH_G_Z_SEL_MASK UINT16_C(0x4000)
703 #define BMI2_HIGH_G_DUR_MASK UINT16_C(0x0FFF)
705 /*! @name Bit position definitions for BMI2 high-g feature configuration */
706 #define BMI2_HIGH_G_X_SEL_POS UINT8_C(0x0C)
707 #define BMI2_HIGH_G_Y_SEL_POS UINT8_C(0x0D)
708 #define BMI2_HIGH_G_Z_SEL_POS UINT8_C(0x0E)
710 /*! @name Mask definitions for BMI2 low-g feature configuration */
711 #define BMI2_LOW_G_THRES_MASK UINT16_C(0x7FFF)
712 #define BMI2_LOW_G_HYST_MASK UINT16_C(0x0FFF)
713 #define BMI2_LOW_G_DUR_MASK UINT16_C(0x0FFF)
715 /*! @name Mask definitions for BMI2 free-fall detection feature configuration */
716 #define BMI2_FREE_FALL_ACCEL_SETT_MASK UINT16_C(0xFFFF)
718 /*! @name Mask definitions for BMI2 flat feature configuration */
719 #define BMI2_FLAT_THETA_MASK UINT16_C(0x007E)
720 #define BMI2_FLAT_BLOCK_MASK UINT16_C(0x0180)
721 #define BMI2_FLAT_HYST_MASK UINT16_C(0x003F)
722 #define BMI2_FLAT_HOLD_TIME_MASK UINT16_C(0x3FC0)
724 /*! @name Bit position definitions for BMI2 flat feature configuration */
725 #define BMI2_FLAT_THETA_POS UINT8_C(0x01)
726 #define BMI2_FLAT_BLOCK_POS UINT8_C(0x07)
727 #define BMI2_FLAT_HOLD_TIME_POS UINT8_C(0x06)
729 /*! @name Mask definitions for BMI2 wrist gesture configuration */
730 #define BMI2_WRIST_GEST_WEAR_ARM_MASK UINT16_C(0x0010)
732 /*! @name Bit position definitions for wrist gesture configuration */
733 #define BMI2_WRIST_GEST_WEAR_ARM_POS UINT8_C(0x04)
735 /*! @name Mask definitions for BMI2 wrist gesture wh configuration */
736 #define BMI2_WRIST_GEST_WH_DEVICE_POS_MASK UINT16_C(0x0001)
737 #define BMI2_WRIST_GEST_WH_INT UINT8_C(0x10)
738 #define BMI2_WRIST_GEST_WH_START_ADD UINT8_C(0x08)
740 /*! @name Mask definitions for BMI2 wrist wear wake-up configuration */
741 #define BMI2_WRIST_WAKE_UP_WH_INT_MASK UINT8_C(0x08)
743 /*! @name Mask definition for BMI2 wrist wear wake-up configuration for wearable variant */
744 #define BMI2_WRIST_WAKE_UP_ANGLE_LR_MASK UINT16_C(0x00FF)
745 #define BMI2_WRIST_WAKE_UP_ANGLE_LL_MASK UINT16_C(0xFF00)
746 #define BMI2_WRIST_WAKE_UP_ANGLE_PD_MASK UINT16_C(0x00FF)
747 #define BMI2_WRIST_WAKE_UP_ANGLE_PU_MASK UINT16_C(0xFF00)
748 #define BMI2_WRIST_WAKE_UP_MIN_DUR_MOVED_MASK UINT16_C(0x00FF)
749 #define BMI2_WRIST_WAKE_UP_MIN_DUR_QUITE_MASK UINT16_C(0xFF00)
751 /*! @name Bit position definition for BMI2 wrist wear wake-up configuration for wearable variant */
752 #define BMI2_WRIST_WAKE_UP_ANGLE_LL_POS UINT16_C(0x0008)
753 #define BMI2_WRIST_WAKE_UP_ANGLE_PU_POS UINT16_C(0x0008)
754 #define BMI2_WRIST_WAKE_UP_MIN_DUR_QUITE_POS UINT16_C(0x0008)
756 /*! @name Macros to define values of BMI2 axis and its sign for re-map
759 #define BMI2_MAP_X_AXIS UINT8_C(0x00)
760 #define BMI2_MAP_Y_AXIS UINT8_C(0x01)
761 #define BMI2_MAP_Z_AXIS UINT8_C(0x02)
762 #define BMI2_MAP_POSITIVE UINT8_C(0x00)
763 #define BMI2_MAP_NEGATIVE UINT8_C(0x01)
765 /*! @name Mask definitions of BMI2 axis re-mapping */
766 #define BMI2_X_AXIS_MASK UINT8_C(0x03)
767 #define BMI2_X_AXIS_SIGN_MASK UINT8_C(0x04)
768 #define BMI2_Y_AXIS_MASK UINT8_C(0x18)
769 #define BMI2_Y_AXIS_SIGN_MASK UINT8_C(0x20)
770 #define BMI2_Z_AXIS_MASK UINT8_C(0xC0)
771 #define BMI2_Z_AXIS_SIGN_MASK UINT8_C(0x01)
773 /*! @name Bit position definitions of BMI2 axis re-mapping */
774 #define BMI2_X_AXIS_SIGN_POS UINT8_C(0x02)
775 #define BMI2_Y_AXIS_POS UINT8_C(0x03)
776 #define BMI2_Y_AXIS_SIGN_POS UINT8_C(0x05)
777 #define BMI2_Z_AXIS_POS UINT8_C(0x06)
779 /*! @name Macros to define polarity */
780 #define BMI2_NEG_SIGN UINT8_C(1)
781 #define BMI2_POS_SIGN UINT8_C(0)
783 /*! @name Macro to define related to CRT */
784 #define BMI2_CRT_READY_FOR_DOWNLOAD_US UINT16_C(2000)
785 #define BMI2_CRT_READY_FOR_DOWNLOAD_RETRY UINT8_C(100)
787 #define BMI2_CRT_WAIT_RUNNING_US UINT16_C(10000)
788 #define BMI2_CRT_WAIT_RUNNING_RETRY_EXECUTION UINT8_C(200)
790 #define BMI2_CRT_MIN_BURST_WORD_LENGTH UINT8_C(2)
791 #define BMI2_CRT_MAX_BURST_WORD_LENGTH UINT16_C(255)
793 #define BMI2_ACC_FOC_2G_REF UINT16_C(16384)
794 #define BMI2_ACC_FOC_4G_REF UINT16_C(8192)
795 #define BMI2_ACC_FOC_8G_REF UINT16_C(4096)
796 #define BMI2_ACC_FOC_16G_REF UINT16_C(2048)
798 #define BMI2_GYRO_FOC_NOISE_LIMIT_NEGATIVE INT8_C(-20)
799 #define BMI2_GYRO_FOC_NOISE_LIMIT_POSITIVE INT8_C(20)
801 /* reference value with positive and negative noise range in lsb */
802 #define BMI2_ACC_2G_MAX_NOISE_LIMIT (BMI2_ACC_FOC_2G_REF + UINT16_C(255))
803 #define BMI2_ACC_2G_MIN_NOISE_LIMIT (BMI2_ACC_FOC_2G_REF - UINT16_C(255))
804 #define BMI2_ACC_4G_MAX_NOISE_LIMIT (BMI2_ACC_FOC_4G_REF + UINT16_C(255))
805 #define BMI2_ACC_4G_MIN_NOISE_LIMIT (BMI2_ACC_FOC_4G_REF - UINT16_C(255))
806 #define BMI2_ACC_8G_MAX_NOISE_LIMIT (BMI2_ACC_FOC_8G_REF + UINT16_C(255))
807 #define BMI2_ACC_8G_MIN_NOISE_LIMIT (BMI2_ACC_FOC_8G_REF - UINT16_C(255))
808 #define BMI2_ACC_16G_MAX_NOISE_LIMIT (BMI2_ACC_FOC_16G_REF + UINT16_C(255))
809 #define BMI2_ACC_16G_MIN_NOISE_LIMIT (BMI2_ACC_FOC_16G_REF - UINT16_C(255))
811 #define BMI2_FOC_SAMPLE_LIMIT UINT8_C(128)
813 /*! @name Bit wise selection of BMI2 sensors */
814 #define BMI2_MAIN_SENSORS \
815 (BMI2_ACCEL_SENS_SEL | BMI2_GYRO_SENS_SEL \
816 | BMI2_AUX_SENS_SEL | BMI2_TEMP_SENS_SEL)
818 /*! @name Maximum number of BMI2 main sensors */
819 #define BMI2_MAIN_SENS_MAX_NUM UINT8_C(4)
821 /*! @name Macro to specify the number of step counter parameters */
822 #define BMI2_STEP_CNT_N_PARAMS UINT8_C(25)
824 /*! @name Macro to specify the number of free-fall accel setting parameters */
825 #define BMI2_FREE_FALL_ACCEL_SET_PARAMS UINT8_C(7)
827 #define BMI2_SELECT_GYRO_SELF_TEST UINT8_C(0)
828 #define BMI2_SELECT_CRT UINT8_C(1)
830 /*! @name Macro for NVM enable */
831 #define BMI2_NVM_UNLOCK_ENABLE UINT8_C(0x02)
832 #define BMI2_NVM_UNLOCK_DISABLE UINT8_C(0x00)
834 /*! @name macro to select between gyro self test and CRT */
835 #define BMI2_GYRO_SELF_TEST_SEL UINT8_C(0)
836 #define BMI2_CRT_SEL UINT8_C(1)
838 /******************************************************************************/
839 /*! @name Accelerometer Macro Definitions */
840 /******************************************************************************/
841 /*! @name Accelerometer Bandwidth parameters */
842 #define BMI2_ACC_OSR4_AVG1 UINT8_C(0x00)
843 #define BMI2_ACC_OSR2_AVG2 UINT8_C(0x01)
844 #define BMI2_ACC_NORMAL_AVG4 UINT8_C(0x02)
845 #define BMI2_ACC_CIC_AVG8 UINT8_C(0x03)
846 #define BMI2_ACC_RES_AVG16 UINT8_C(0x04)
847 #define BMI2_ACC_RES_AVG32 UINT8_C(0x05)
848 #define BMI2_ACC_RES_AVG64 UINT8_C(0x06)
849 #define BMI2_ACC_RES_AVG128 UINT8_C(0x07)
851 /*! @name Accelerometer Output Data Rate */
852 #define BMI2_ACC_ODR_0_78HZ UINT8_C(0x01)
853 #define BMI2_ACC_ODR_1_56HZ UINT8_C(0x02)
854 #define BMI2_ACC_ODR_3_12HZ UINT8_C(0x03)
855 #define BMI2_ACC_ODR_6_25HZ UINT8_C(0x04)
856 #define BMI2_ACC_ODR_12_5HZ UINT8_C(0x05)
857 #define BMI2_ACC_ODR_25HZ UINT8_C(0x06)
858 #define BMI2_ACC_ODR_50HZ UINT8_C(0x07)
859 #define BMI2_ACC_ODR_100HZ UINT8_C(0x08)
860 #define BMI2_ACC_ODR_200HZ UINT8_C(0x09)
861 #define BMI2_ACC_ODR_400HZ UINT8_C(0x0A)
862 #define BMI2_ACC_ODR_800HZ UINT8_C(0x0B)
863 #define BMI2_ACC_ODR_1600HZ UINT8_C(0x0C)
865 /*! @name Accelerometer G Range */
866 #define BMI2_ACC_RANGE_2G UINT8_C(0x00)
867 #define BMI2_ACC_RANGE_4G UINT8_C(0x01)
868 #define BMI2_ACC_RANGE_8G UINT8_C(0x02)
869 #define BMI2_ACC_RANGE_16G UINT8_C(0x03)
871 /*! @name Mask definitions for accelerometer configuration register */
872 #define BMI2_ACC_RANGE_MASK UINT8_C(0x03)
873 #define BMI2_ACC_ODR_MASK UINT8_C(0x0F)
874 #define BMI2_ACC_BW_PARAM_MASK UINT8_C(0x70)
875 #define BMI2_ACC_FILTER_PERF_MODE_MASK UINT8_C(0x80)
877 /*! @name Bit position definitions for accelerometer configuration register */
878 #define BMI2_ACC_BW_PARAM_POS UINT8_C(0x04)
879 #define BMI2_ACC_FILTER_PERF_MODE_POS UINT8_C(0x07)
881 /*! @name Self test macro to define range */
882 #define BMI2_ACC_SELF_TEST_RANGE UINT8_C(16)
884 /*! @name Self test macro to show resulting minimum and maximum difference
885 * signal of the axes in mg
887 #define BMI2_ST_ACC_X_SIG_MIN_DIFF INT16_C(16000)
888 #define BMI2_ST_ACC_Y_SIG_MIN_DIFF INT16_C(-15000)
889 #define BMI2_ST_ACC_Z_SIG_MIN_DIFF INT16_C(10000)
891 /*! @name Mask definitions for accelerometer self-test */
892 #define BMI2_ACC_SELF_TEST_EN_MASK UINT8_C(0x01)
893 #define BMI2_ACC_SELF_TEST_SIGN_MASK UINT8_C(0x04)
894 #define BMI2_ACC_SELF_TEST_AMP_MASK UINT8_C(0x08)
896 /*! @name Bit Positions for accelerometer self-test */
897 #define BMI2_ACC_SELF_TEST_SIGN_POS UINT8_C(0x02)
898 #define BMI2_ACC_SELF_TEST_AMP_POS UINT8_C(0x03)
900 /*! @name MASK definition for gyro self test status */
901 #define BMI2_GYR_ST_AXES_DONE_MASK UINT8_C(0X01)
902 #define BMI2_GYR_AXIS_X_OK_MASK UINT8_C(0x02)
903 #define BMI2_GYR_AXIS_Y_OK_MASK UINT8_C(0x04)
904 #define BMI2_GYR_AXIS_Z_OK_MASK UINT8_C(0x08)
906 /*! @name Bit position for gyro self test status */
907 #define BMI2_GYR_AXIS_X_OK_POS UINT8_C(0x01)
908 #define BMI2_GYR_AXIS_Y_OK_POS UINT8_C(0x02)
909 #define BMI2_GYR_AXIS_Z_OK_POS UINT8_C(0x03)
911 /******************************************************************************/
912 /*! @name Gyroscope Macro Definitions */
913 /******************************************************************************/
914 /*! @name Gyroscope Bandwidth parameters */
915 #define BMI2_GYR_OSR4_MODE UINT8_C(0x00)
916 #define BMI2_GYR_OSR2_MODE UINT8_C(0x01)
917 #define BMI2_GYR_NORMAL_MODE UINT8_C(0x02)
918 #define BMI2_GYR_CIC_MODE UINT8_C(0x03)
920 /*! @name Gyroscope Output Data Rate */
921 #define BMI2_GYR_ODR_25HZ UINT8_C(0x06)
922 #define BMI2_GYR_ODR_50HZ UINT8_C(0x07)
923 #define BMI2_GYR_ODR_100HZ UINT8_C(0x08)
924 #define BMI2_GYR_ODR_200HZ UINT8_C(0x09)
925 #define BMI2_GYR_ODR_400HZ UINT8_C(0x0A)
926 #define BMI2_GYR_ODR_800HZ UINT8_C(0x0B)
927 #define BMI2_GYR_ODR_1600HZ UINT8_C(0x0C)
928 #define BMI2_GYR_ODR_3200HZ UINT8_C(0x0D)
930 /*! @name Gyroscope OIS Range */
931 #define BMI2_GYR_OIS_250 UINT8_C(0x00)
932 #define BMI2_GYR_OIS_2000 UINT8_C(0x01)
934 /*! @name Gyroscope Angular Rate Measurement Range */
935 #define BMI2_GYR_RANGE_2000 UINT8_C(0x00)
936 #define BMI2_GYR_RANGE_1000 UINT8_C(0x01)
937 #define BMI2_GYR_RANGE_500 UINT8_C(0x02)
938 #define BMI2_GYR_RANGE_250 UINT8_C(0x03)
939 #define BMI2_GYR_RANGE_125 UINT8_C(0x04)
941 /*! @name Mask definitions for gyroscope configuration register */
942 #define BMI2_GYR_RANGE_MASK UINT8_C(0x07)
943 #define BMI2_GYR_OIS_RANGE_MASK UINT8_C(0x08)
944 #define BMI2_GYR_ODR_MASK UINT8_C(0x0F)
945 #define BMI2_GYR_BW_PARAM_MASK UINT8_C(0x30)
946 #define BMI2_GYR_NOISE_PERF_MODE_MASK UINT8_C(0x40)
947 #define BMI2_GYR_FILTER_PERF_MODE_MASK UINT8_C(0x80)
949 /*! @name Bit position definitions for gyroscope configuration register */
950 #define BMI2_GYR_OIS_RANGE_POS UINT8_C(0x03)
951 #define BMI2_GYR_BW_PARAM_POS UINT8_C(0x04)
952 #define BMI2_GYR_NOISE_PERF_MODE_POS UINT8_C(0x06)
953 #define BMI2_GYR_FILTER_PERF_MODE_POS UINT8_C(0x07)
955 /******************************************************************************/
956 /*! @name Auxiliary Macro Definitions */
957 /******************************************************************************/
958 /*! @name Auxiliary Output Data Rate */
959 #define BMI2_AUX_ODR_RESERVED UINT8_C(0x00)
960 #define BMI2_AUX_ODR_0_78HZ UINT8_C(0x01)
961 #define BMI2_AUX_ODR_1_56HZ UINT8_C(0x02)
962 #define BMI2_AUX_ODR_3_12HZ UINT8_C(0x03)
963 #define BMI2_AUX_ODR_6_25HZ UINT8_C(0x04)
964 #define BMI2_AUX_ODR_12_5HZ UINT8_C(0x05)
965 #define BMI2_AUX_ODR_25HZ UINT8_C(0x06)
966 #define BMI2_AUX_ODR_50HZ UINT8_C(0x07)
967 #define BMI2_AUX_ODR_100HZ UINT8_C(0x08)
968 #define BMI2_AUX_ODR_200HZ UINT8_C(0x09)
969 #define BMI2_AUX_ODR_400HZ UINT8_C(0x0A)
970 #define BMI2_AUX_ODR_800HZ UINT8_C(0x0B)
972 /*! @name Macro to define burst read lengths for both manual and auto modes */
973 #define BMI2_AUX_READ_LEN_0 UINT8_C(0x00)
974 #define BMI2_AUX_READ_LEN_1 UINT8_C(0x01)
975 #define BMI2_AUX_READ_LEN_2 UINT8_C(0x02)
976 #define BMI2_AUX_READ_LEN_3 UINT8_C(0x03)
978 /*! @name Mask definitions for auxiliary interface configuration register */
979 #define BMI2_AUX_SET_I2C_ADDR_MASK UINT8_C(0xFE)
980 #define BMI2_AUX_MAN_MODE_EN_MASK UINT8_C(0x80)
981 #define BMI2_AUX_FCU_WR_EN_MASK UINT8_C(0x40)
982 #define BMI2_AUX_MAN_READ_BURST_MASK UINT8_C(0x0C)
983 #define BMI2_AUX_READ_BURST_MASK UINT8_C(0x03)
984 #define BMI2_AUX_ODR_EN_MASK UINT8_C(0x0F)
985 #define BMI2_AUX_OFFSET_READ_OUT_MASK UINT8_C(0xF0)
987 /*! @name Bit positions for auxiliary interface configuration register */
988 #define BMI2_AUX_SET_I2C_ADDR_POS UINT8_C(0x01)
989 #define BMI2_AUX_MAN_MODE_EN_POS UINT8_C(0x07)
990 #define BMI2_AUX_FCU_WR_EN_POS UINT8_C(0x06)
991 #define BMI2_AUX_MAN_READ_BURST_POS UINT8_C(0x02)
992 #define BMI2_AUX_OFFSET_READ_OUT_POS UINT8_C(0x04)
994 /******************************************************************************/
995 /*! @name FIFO Macro Definitions */
996 /******************************************************************************/
997 /*! @name Macros to define virtual FIFO frame mode */
998 #define BMI2_FIFO_VIRT_FRM_MODE UINT8_C(0x03)
1000 /*! @name FIFO Header Mask definitions */
1001 #define BMI2_FIFO_HEADER_ACC_FRM UINT8_C(0x84)
1002 #define BMI2_FIFO_HEADER_AUX_FRM UINT8_C(0x90)
1003 #define BMI2_FIFO_HEADER_GYR_FRM UINT8_C(0x88)
1004 #define BMI2_FIFO_HEADER_GYR_ACC_FRM UINT8_C(0x8C)
1005 #define BMI2_FIFO_HEADER_AUX_ACC_FRM UINT8_C(0x94)
1006 #define BMI2_FIFO_HEADER_AUX_GYR_FRM UINT8_C(0x98)
1007 #define BMI2_FIFO_HEADER_ALL_FRM UINT8_C(0x9C)
1008 #define BMI2_FIFO_HEADER_SENS_TIME_FRM UINT8_C(0x44)
1009 #define BMI2_FIFO_HEADER_SKIP_FRM UINT8_C(0x40)
1010 #define BMI2_FIFO_HEADER_INPUT_CFG_FRM UINT8_C(0x48)
1011 #define BMI2_FIFO_HEAD_OVER_READ_MSB UINT8_C(0x80)
1012 #define BMI2_FIFO_VIRT_ACT_RECOG_FRM UINT8_C(0xC8)
1014 /*! @name BMI2 sensor selection for header-less frames */
1015 #define BMI2_FIFO_HEAD_LESS_ACC_FRM UINT8_C(0x40)
1016 #define BMI2_FIFO_HEAD_LESS_AUX_FRM UINT8_C(0x20)
1017 #define BMI2_FIFO_HEAD_LESS_GYR_FRM UINT8_C(0x80)
1018 #define BMI2_FIFO_HEAD_LESS_GYR_AUX_FRM UINT8_C(0xA0)
1019 #define BMI2_FIFO_HEAD_LESS_GYR_ACC_FRM UINT8_C(0xC0)
1020 #define BMI2_FIFO_HEAD_LESS_AUX_ACC_FRM UINT8_C(0x60)
1021 #define BMI2_FIFO_HEAD_LESS_ALL_FRM UINT8_C(0xE0)
1023 /*! @name Mask definitions for FIFO frame content configuration */
1024 #define BMI2_FIFO_STOP_ON_FULL UINT16_C(0x0001)
1025 #define BMI2_FIFO_TIME_EN UINT16_C(0x0002)
1026 #define BMI2_FIFO_TAG_INT1 UINT16_C(0x0300)
1027 #define BMI2_FIFO_TAG_INT2 UINT16_C(0x0C00)
1028 #define BMI2_FIFO_HEADER_EN UINT16_C(0x1000)
1029 #define BMI2_FIFO_AUX_EN UINT16_C(0x2000)
1030 #define BMI2_FIFO_ACC_EN UINT16_C(0x4000)
1031 #define BMI2_FIFO_GYR_EN UINT16_C(0x8000)
1032 #define BMI2_FIFO_ALL_EN UINT16_C(0xE000)
1034 /*! @name FIFO sensor data lengths */
1035 #define BMI2_FIFO_ACC_LENGTH UINT8_C(6)
1036 #define BMI2_FIFO_GYR_LENGTH UINT8_C(6)
1037 #define BMI2_FIFO_AUX_LENGTH UINT8_C(8)
1038 #define BMI2_FIFO_ACC_AUX_LENGTH UINT8_C(14)
1039 #define BMI2_FIFO_GYR_AUX_LENGTH UINT8_C(14)
1040 #define BMI2_FIFO_ACC_GYR_LENGTH UINT8_C(12)
1041 #define BMI2_FIFO_ALL_LENGTH UINT8_C(20)
1042 #define BMI2_SENSOR_TIME_LENGTH UINT8_C(3)
1043 #define BMI2_FIFO_CONFIG_LENGTH UINT8_C(2)
1044 #define BMI2_FIFO_WM_LENGTH UINT8_C(2)
1045 #define BMI2_MAX_VALUE_FIFO_FILTER UINT8_C(1)
1046 #define BMI2_FIFO_DATA_LENGTH UINT8_C(2)
1047 #define BMI2_FIFO_LENGTH_MSB_BYTE UINT8_C(1)
1048 #define BMI2_FIFO_INPUT_CFG_LENGTH UINT8_C(4)
1049 #define BMI2_FIFO_SKIP_FRM_LENGTH UINT8_C(1)
1051 /*! @name FIFO sensor virtual data lengths: sensor data plus sensor time */
1052 #define BMI2_FIFO_VIRT_ACC_LENGTH UINT8_C(9)
1053 #define BMI2_FIFO_VIRT_GYR_LENGTH UINT8_C(9)
1054 #define BMI2_FIFO_VIRT_AUX_LENGTH UINT8_C(11)
1055 #define BMI2_FIFO_VIRT_ACC_AUX_LENGTH UINT8_C(17)
1056 #define BMI2_FIFO_VIRT_GYR_AUX_LENGTH UINT8_C(17)
1057 #define BMI2_FIFO_VIRT_ACC_GYR_LENGTH UINT8_C(15)
1058 #define BMI2_FIFO_VIRT_ALL_LENGTH UINT8_C(23)
1060 /*! @name FIFO sensor virtual data lengths: activity recognition */
1061 #define BMI2_FIFO_VIRT_ACT_DATA_LENGTH UINT8_C(6)
1062 #define BMI2_FIFO_VIRT_ACT_TIME_LENGTH UINT8_C(4)
1063 #define BMI2_FIFO_VIRT_ACT_TYPE_LENGTH UINT8_C(1)
1064 #define BMI2_FIFO_VIRT_ACT_STAT_LENGTH UINT8_C(1)
1066 /*! @name BMI2 FIFO data filter modes */
1067 #define BMI2_FIFO_UNFILTERED_DATA UINT8_C(0)
1068 #define BMI2_FIFO_FILTERED_DATA UINT8_C(1)
1070 /*! @name FIFO frame masks */
1071 #define BMI2_FIFO_LSB_CONFIG_CHECK UINT8_C(0x00)
1072 #define BMI2_FIFO_MSB_CONFIG_CHECK UINT8_C(0x80)
1073 #define BMI2_FIFO_TAG_INTR_MASK UINT8_C(0xFF)
1075 /*! @name BMI2 Mask definitions of FIFO configuration registers */
1076 #define BMI2_FIFO_CONFIG_0_MASK UINT16_C(0x0003)
1077 #define BMI2_FIFO_CONFIG_1_MASK UINT16_C(0xFF00)
1079 /*! @name FIFO self wake-up mask definition */
1080 #define BMI2_FIFO_SELF_WAKE_UP_MASK UINT8_C(0x02)
1082 /*! @name FIFO down sampling mask definition */
1083 #define BMI2_ACC_FIFO_DOWNS_MASK UINT8_C(0x70)
1084 #define BMI2_GYR_FIFO_DOWNS_MASK UINT8_C(0x07)
1086 /*! @name FIFO down sampling bit positions */
1087 #define BMI2_ACC_FIFO_DOWNS_POS UINT8_C(0x04)
1089 /*! @name FIFO filter mask definition */
1090 #define BMI2_ACC_FIFO_FILT_DATA_MASK UINT8_C(0x80)
1091 #define BMI2_GYR_FIFO_FILT_DATA_MASK UINT8_C(0x08)
1093 /*! @name FIFO filter bit positions */
1094 #define BMI2_ACC_FIFO_FILT_DATA_POS UINT8_C(0x07)
1095 #define BMI2_GYR_FIFO_FILT_DATA_POS UINT8_C(0x03)
1097 /*! @name FIFO byte counter mask definition */
1098 #define BMI2_FIFO_BYTE_COUNTER_MSB_MASK UINT8_C(0x3F)
1100 /*! @name FIFO self wake-up bit positions */
1101 #define BMI2_FIFO_SELF_WAKE_UP_POS UINT8_C(0x01)
1103 /*! @name Mask Definitions for Virtual FIFO frames */
1104 #define BMI2_FIFO_VIRT_FRM_MODE_MASK UINT8_C(0xC0)
1105 #define BMI2_FIFO_VIRT_PAYLOAD_MASK UINT8_C(0x3C)
1107 /*! @name Bit Positions for Virtual FIFO frames */
1108 #define BMI2_FIFO_VIRT_FRM_MODE_POS UINT8_C(0x06)
1109 #define BMI2_FIFO_VIRT_PAYLOAD_POS UINT8_C(0x02)
1111 /******************************************************************************/
1112 /*! @name Interrupt Macro Definitions */
1113 /******************************************************************************/
1114 /*! @name BMI2 Interrupt Modes */
1116 #define BMI2_INT_NON_LATCH UINT8_C(0)
1118 /* Permanently latched */
1119 #define BMI2_INT_LATCH UINT8_C(1)
1121 /*! @name BMI2 Interrupt Pin Behavior */
1122 #define BMI2_INT_PUSH_PULL UINT8_C(0)
1123 #define BMI2_INT_OPEN_DRAIN UINT8_C(1)
1125 /*! @name BMI2 Interrupt Pin Level */
1126 #define BMI2_INT_ACTIVE_LOW UINT8_C(0)
1127 #define BMI2_INT_ACTIVE_HIGH UINT8_C(1)
1129 /*! @name BMI2 Interrupt Output Enable */
1130 #define BMI2_INT_OUTPUT_DISABLE UINT8_C(0)
1131 #define BMI2_INT_OUTPUT_ENABLE UINT8_C(1)
1133 /*! @name BMI2 Interrupt Input Enable */
1134 #define BMI2_INT_INPUT_DISABLE UINT8_C(0)
1135 #define BMI2_INT_INPUT_ENABLE UINT8_C(1)
1137 /*! @name Mask definitions for interrupt pin configuration */
1138 #define BMI2_INT_LATCH_MASK UINT8_C(0x01)
1139 #define BMI2_INT_LEVEL_MASK UINT8_C(0x02)
1140 #define BMI2_INT_OPEN_DRAIN_MASK UINT8_C(0x04)
1141 #define BMI2_INT_OUTPUT_EN_MASK UINT8_C(0x08)
1142 #define BMI2_INT_INPUT_EN_MASK UINT8_C(0x10)
1144 /*! @name Bit position definitions for interrupt pin configuration */
1145 #define BMI2_INT_LEVEL_POS UINT8_C(0x01)
1146 #define BMI2_INT_OPEN_DRAIN_POS UINT8_C(0x02)
1147 #define BMI2_INT_OUTPUT_EN_POS UINT8_C(0x03)
1148 #define BMI2_INT_INPUT_EN_POS UINT8_C(0x04)
1150 /*! @name Mask definitions for data interrupt mapping */
1151 #define BMI2_FFULL_INT UINT8_C(0x01)
1152 #define BMI2_FWM_INT UINT8_C(0x02)
1153 #define BMI2_DRDY_INT UINT8_C(0x04)
1154 #define BMI2_ERR_INT UINT8_C(0x08)
1156 /*! @name Mask definitions for data interrupt status bits */
1157 #define BMI2_FFULL_INT_STATUS_MASK UINT16_C(0x0100)
1158 #define BMI2_FWM_INT_STATUS_MASK UINT16_C(0x0200)
1159 #define BMI2_ERR_INT_STATUS_MASK UINT16_C(0x0400)
1160 #define BMI2_AUX_DRDY_INT_MASK UINT16_C(0x2000)
1161 #define BMI2_GYR_DRDY_INT_MASK UINT16_C(0x4000)
1162 #define BMI2_ACC_DRDY_INT_MASK UINT16_C(0x8000)
1164 /*! @name Maximum number of interrupt pins */
1165 #define BMI2_INT_PIN_MAX_NUM UINT8_C(2)
1167 /*! @name Macro for mapping feature interrupts */
1168 #define BMI2_FEAT_BIT_DISABLE UINT8_C(0)
1169 #define BMI2_FEAT_BIT0 UINT8_C(1)
1170 #define BMI2_FEAT_BIT1 UINT8_C(2)
1171 #define BMI2_FEAT_BIT2 UINT8_C(3)
1172 #define BMI2_FEAT_BIT3 UINT8_C(4)
1173 #define BMI2_FEAT_BIT4 UINT8_C(5)
1174 #define BMI2_FEAT_BIT5 UINT8_C(6)
1175 #define BMI2_FEAT_BIT6 UINT8_C(7)
1176 #define BMI2_FEAT_BIT7 UINT8_C(8)
1177 #define BMI2_FEAT_BIT_MAX UINT8_C(9)
1179 /******************************************************************************/
1180 /*! @name OIS Interface Macro Definitions */
1181 /******************************************************************************/
1182 /*! @name Mask definitions for interface configuration register */
1183 #define BMI2_OIS_IF_EN_MASK UINT8_C(0x10)
1184 #define BMI2_AUX_IF_EN_MASK UINT8_C(0x20)
1186 /*! @name Bit positions for OIS interface enable */
1187 #define BMI2_OIS_IF_EN_POS UINT8_C(0x04)
1188 #define BMI2_AUX_IF_EN_POS UINT8_C(0x05)
1190 /******************************************************************************/
1191 /*! @name Macro Definitions for Axes re-mapping */
1192 /******************************************************************************/
1193 /*! @name Macros for the user-defined values of axes and their polarities */
1194 #define BMI2_X UINT8_C(0x01)
1195 #define BMI2_NEG_X UINT8_C(0x09)
1196 #define BMI2_Y UINT8_C(0x02)
1197 #define BMI2_NEG_Y UINT8_C(0x0A)
1198 #define BMI2_Z UINT8_C(0x04)
1199 #define BMI2_NEG_Z UINT8_C(0x0C)
1200 #define BMI2_AXIS_MASK UINT8_C(0x07)
1201 #define BMI2_AXIS_SIGN UINT8_C(0x08)
1203 /******************************************************************************/
1204 /*! @name Macro Definitions for offset and gain compensation */
1205 /******************************************************************************/
1206 /*! @name Mask definitions of gyroscope offset compensation registers */
1207 #define BMI2_GYR_GAIN_EN_MASK UINT8_C(0x80)
1208 #define BMI2_GYR_OFF_COMP_EN_MASK UINT8_C(0x40)
1210 /*! @name Bit positions of gyroscope offset compensation registers */
1211 #define BMI2_GYR_OFF_COMP_EN_POS UINT8_C(0x06)
1213 /*! @name Mask definitions of gyroscope user-gain registers */
1214 #define BMI2_GYR_USR_GAIN_X_MASK UINT8_C(0x7F)
1215 #define BMI2_GYR_USR_GAIN_Y_MASK UINT8_C(0x7F)
1216 #define BMI2_GYR_USR_GAIN_Z_MASK UINT8_C(0x7F)
1218 /*! @name Bit positions of gyroscope offset compensation registers */
1219 #define BMI2_GYR_GAIN_EN_POS UINT8_C(0x07)
1221 /******************************************************************************/
1222 /*! @name Macro Definitions for internal status */
1223 /******************************************************************************/
1224 #define BMI2_NOT_INIT UINT8_C(0x00)
1225 #define BMI2_INIT_OK UINT8_C(0x01)
1226 #define BMI2_INIT_ERR UINT8_C(0x02)
1227 #define BMI2_DRV_ERR UINT8_C(0x03)
1228 #define BMI2_SNS_STOP UINT8_C(0x04)
1229 #define BMI2_NVM_ERROR UINT8_C(0x05)
1230 #define BMI2_START_UP_ERROR UINT8_C(0x06)
1231 #define BMI2_COMPAT_ERROR UINT8_C(0x07)
1232 #define BMI2_VFM_SKIPPED UINT8_C(0x10)
1233 #define BMI2_AXES_MAP_ERROR UINT8_C(0x20)
1234 #define BMI2_ODR_50_HZ_ERROR UINT8_C(0x40)
1235 #define BMI2_ODR_HIGH_ERROR UINT8_C(0x80)
1237 /******************************************************************************/
1238 /*! @name error status form gyro gain update status. */
1239 /******************************************************************************/
1240 #define BMI2_G_TRIGGER_NO_ERROR UINT8_C(0x00)
1242 #define BMI2_G_TRIGGER_PRECON_ERROR UINT8_C(0x01)
1243 #define BMI2_G_TRIGGER_DL_ERROR UINT8_C(0x02)
1244 #define BMI2_G_TRIGGER_ABORT_ERROR UINT8_C(0x03)
1246 /******************************************************************************/
1247 /*! @name Variant specific features selection macros */
1248 /******************************************************************************/
1249 #define BMI2_CRT_RTOSK_ENABLE UINT8_C(0x01)
1250 #define BMI2_GYRO_CROSS_SENS_ENABLE UINT8_C(0x02)
1251 #define BMI2_GYRO_USER_GAIN_ENABLE UINT8_C(0x08)
1252 #define BMI2_NO_FEATURE_ENABLE UINT8_C(0x00)
1253 #define BMI2_CRT_IN_FIFO_NOT_REQ UINT8_C(0x10)
1254 #define BMI2_MAXIMUM_FIFO_VARIANT UINT8_C(0x20)
1256 /*! Pull-up configuration for ASDA */
1257 #define BMI2_ASDA_PUPSEL_OFF UINT8_C(0x00)
1258 #define BMI2_ASDA_PUPSEL_40K UINT8_C(0x01)
1259 #define BMI2_ASDA_PUPSEL_10K UINT8_C(0x02)
1260 #define BMI2_ASDA_PUPSEL_2K UINT8_C(0x03)
1262 /******************************************************************************/
1263 /*! @name Function Pointers */
1264 /******************************************************************************/
1267 * @brief Bus communication function pointer which should be mapped to
1268 * the platform specific read functions of the user
1270 * @param[in] reg_addr : Register address from which data is read.
1271 * @param[out] reg_data : Pointer to data buffer where read data is stored.
1272 * @param[in] len : Number of bytes of data to be read.
1273 * @param[in, out] intf_ptr : Void pointer that can enable the linking of descriptors
1274 * for interface related call backs.
1276 * retval = BMA4_INTF_RET_SUCCESS -> Success
1277 * retval != BMA4_INTF_RET_SUCCESS -> Failure
1280 typedef BMI2_INTF_RETURN_TYPE (*bmi2_read_fptr_t
)(uint8_t reg_addr
, uint8_t *reg_data
, uint32_t len
, void *intf_ptr
);
1283 * @brief Bus communication function pointer which should be mapped to
1284 * the platform specific write functions of the user
1286 * @param[in] reg_addr : Register address to which the data is written.
1287 * @param[in] reg_data : Pointer to data buffer in which data to be written
1289 * @param[in] len : Number of bytes of data to be written.
1290 * @param[in, out] intf_ptr : Void pointer that can enable the linking of descriptors
1291 * for interface related call backs
1293 * retval = BMA4_INTF_RET_SUCCESS -> Success
1294 * retval != BMA4_INTF_RET_SUCCESS -> Failure
1297 typedef BMI2_INTF_RETURN_TYPE (*bmi2_write_fptr_t
)(uint8_t reg_addr
, const uint8_t *reg_data
, uint32_t len
,
1301 * @brief Delay function pointer which should be mapped to
1302 * delay function of the user
1304 * @param[in] period : Delay in microseconds.
1305 * @param[in, out] intf_ptr : Void pointer that can enable the linking of descriptors
1306 * for interface related call backs
1309 typedef void (*bmi2_delay_fptr_t
)(uint32_t period
, void *intf_ptr
);
1312 * @brief To get the configurations for wake_up feature, since wakeup feature is different for bmi260 and bmi261.
1314 * @param[out] wake_up : Void pointer to store bmi2_wake_up_config structure.
1315 * @param[in, out] bmi2_dev : Void pointer to store bmi2_dev structure.
1317 * @return Result of API execution status
1319 * @retval BMI2_OK - Success.
1320 * @retval BMI2_E_COM_FAIL - Error: Communication fail
1321 * @retval BMI2_E_NULL_PTR - Error: Null pointer error
1322 * @retval BMI2_E_INVALID_PAGE - Error: Invalid Page
1325 typedef int8_t (*bmi2_wake_up_fptr_t
)(void *wake_up
, void *bmi2_dev
);
1328 * @brief To get the configurations for tap feature.
1330 * @param[out] tap : Void pointer to store bmi2_tap_config structure.
1331 * @param[in, out] bmi2_dev : Void pointer to store bmi2_dev structure.
1333 * @return Result of API execution status
1335 * @retval BMI2_OK - Success.
1336 * @retval BMI2_E_COM_FAIL - Error: Communication fail
1337 * @retval BMI2_E_NULL_PTR - Error: Null pointer error
1338 * @retval BMI2_E_INVALID_PAGE - Error: Invalid Page
1341 typedef int8_t (*bmi2_tap_fptr_t
)(void *tap
, void *bmi2_dev
);
1343 /******************************************************************************/
1344 /*! @name Enum Declarations */
1345 /******************************************************************************/
1346 /*! @name Enum to define BMI2 sensor interfaces */
1353 /*! @name Enum to define BMI2 sensor configuration errors for accelerometer
1356 enum bmi2_sensor_config_error
{
1363 /*! @name Enum to define interrupt lines */
1364 enum bmi2_hw_int_pin
{
1372 /*! @name Enum for the position of the wearable device */
1373 enum bmi2_wear_arm_pos
{
1378 /*! @name Enum to display type of activity recognition */
1379 enum bmi2_act_recog_type
{
1389 /*! @name Enum to display activity recognition status */
1390 enum bmi2_act_recog_stat
{
1395 /******************************************************************************/
1396 /*! @name Structure Declarations */
1397 /******************************************************************************/
1398 /*! @name Structure to store the compensated user-gain data of gyroscope */
1399 struct bmi2_gyro_user_gain_data
1411 /*! @name Structure to store the re-mapped axis */
1414 /*! Re-mapped x-axis */
1417 /*! Re-mapped y-axis */
1420 /*! Re-mapped z-axis */
1424 /*! @name Structure to store the value of re-mapped axis and its sign */
1425 struct bmi2_axes_remap
1427 /*! Re-mapped x-axis */
1430 /*! Re-mapped y-axis */
1433 /*! Re-mapped z-axis */
1436 /*! Re-mapped x-axis sign */
1437 uint8_t x_axis_sign
;
1439 /*! Re-mapped y-axis sign */
1440 uint8_t y_axis_sign
;
1442 /*! Re-mapped z-axis sign */
1443 uint8_t z_axis_sign
;
1446 /*! @name Structure to define the type of sensor and its interrupt pin */
1447 struct bmi2_sens_int_config
1449 /*! Defines the type of sensor */
1452 /*! Type of interrupt pin */
1453 enum bmi2_hw_int_pin hw_int_pin
;
1456 /*! @name Structure to define output for activity recognition */
1457 struct bmi2_act_recog_output
1460 uint32_t time_stamp
;
1462 /*! current activity */
1465 /*! previous activity */
1469 /*! @name Structure to define FIFO frame configuration */
1470 struct bmi2_fifo_frame
1472 /*! Pointer to FIFO data */
1475 /*! Number of user defined bytes of FIFO to be read */
1478 /*! Defines header/header-less mode */
1479 uint8_t header_enable
;
1481 /*! Enables type of data to be streamed - accelerometer, auxiliary or
1484 uint16_t data_enable
;
1486 /*! To index accelerometer bytes */
1487 uint16_t acc_byte_start_idx
;
1489 /*! To index activity output bytes */
1490 uint16_t act_recog_byte_start_idx
;
1492 /*! To index auxiliary bytes */
1493 uint16_t aux_byte_start_idx
;
1495 /*! To index gyroscope bytes */
1496 uint16_t gyr_byte_start_idx
;
1498 /*! FIFO sensor time */
1499 uint32_t sensor_time
;
1501 /*! Skipped frame count */
1502 uint8_t skipped_frame_count
;
1504 /*! Type of data interrupt to be mapped */
1505 uint8_t data_int_map
;
1507 /*! Water-mark level for water-mark interrupt */
1510 /*! Accelerometer frame length */
1511 uint8_t acc_frm_len
;
1513 /*! Gyroscope frame length */
1514 uint8_t gyr_frm_len
;
1516 /*! Auxiliary frame length */
1517 uint8_t aux_frm_len
;
1519 /*! Accelerometer and gyroscope frame length */
1520 uint8_t acc_gyr_frm_len
;
1522 /*! Accelerometer and auxiliary frame length */
1523 uint8_t acc_aux_frm_len
;
1525 /*! Gyroscope and auxiliary frame length */
1526 uint8_t aux_gyr_frm_len
;
1528 /*! Accelerometer, Gyroscope and auxiliary frame length */
1529 uint8_t all_frm_len
;
1532 /*! @name Structure to define Interrupt pin configuration */
1533 struct bmi2_int_pin_cfg
1535 /*! Configure level of interrupt pin */
1538 /*! Configure behavior of interrupt pin */
1541 /*! Output enable for interrupt pin */
1544 /*! Input enable for interrupt pin */
1548 /*! @name Structure to define interrupt pin type, mode and configurations */
1549 struct bmi2_int_pin_config
1551 /*! Interrupt pin type: INT1 or INT2 or BOTH */
1554 /*! Latched or non-latched mode*/
1557 /*! Structure to define Interrupt pin configuration */
1558 struct bmi2_int_pin_cfg pin_cfg
[BMI2_INT_PIN_MAX_NUM
];
1561 /*! @name Structure to define an array of 8 auxiliary data bytes */
1562 struct bmi2_aux_fifo_data
1564 /*! Auxiliary data */
1567 /*! Sensor time for virtual frames */
1568 uint32_t virt_sens_time
;
1571 /*! @name Structure to define accelerometer and gyroscope sensor axes and
1572 * sensor time for virtual frames
1574 struct bmi2_sens_axes_data
1576 /*! Data in x-axis */
1579 /*! Data in y-axis */
1582 /*! Data in z-axis */
1585 /*! Sensor time for virtual frames */
1586 uint32_t virt_sens_time
;
1589 /*! @name Structure to define gyroscope saturation status of user gain */
1590 struct bmi2_gyr_user_gain_status
1592 /*! Status in x-axis */
1595 /*! Status in y-axis */
1598 /*! Status in z-axis */
1601 /*! G trigger status */
1602 uint8_t g_trigger_status
;
1605 /*! @name Structure to store the status of gyro self test result */
1606 struct bmi2_gyro_self_test_status
1608 /*! gyro self test axes done */
1609 uint8_t gyr_st_axes_done
: 1;
1611 /*! status of gyro X-axis self test */
1612 uint8_t gyr_axis_x_ok
: 1;
1614 /*! status of gyro Y-axis self test */
1615 uint8_t gyr_axis_y_ok
: 1;
1617 /*! status of gyro Z-axis self test */
1618 uint8_t gyr_axis_z_ok
: 1;
1621 /*! @name Structure to define NVM error status */
1622 struct bmi2_nvm_err_status
1624 /*! NVM load action error */
1627 /*! NVM program action error */
1630 /*! NVM erase action error */
1631 uint8_t erase_error
;
1633 /*! NVM program limit exceeded */
1634 uint8_t exceed_error
;
1636 /*! NVM privilege error */
1637 uint8_t privil_error
;
1640 /*! @name Structure to define VFRM error status */
1641 struct bmi2_vfrm_err_status
1643 /*! VFRM lock acquire error */
1646 /*! VFRM write error */
1647 uint8_t write_error
;
1649 /*! VFRM fatal err */
1650 uint8_t fatal_error
;
1653 /*! @name Structure to define accelerometer self test feature status */
1654 struct bmi2_acc_self_test_status
1656 /*! Accelerometer test completed */
1657 uint8_t acc_self_test_done
;
1659 /*! Bit is set to 1 when accelerometer X-axis test passed */
1662 /*! Bit is set to 1 when accelerometer y-axis test passed */
1665 /*! Bit is set to 1 when accelerometer z-axis test passed */
1669 /*! @name Structure to define orientation output */
1670 struct bmi2_orientation_output
1672 /*! Orientation portrait landscape */
1673 uint8_t portrait_landscape
;
1675 /*! Orientation face-up down */
1676 uint8_t faceup_down
;
1679 /*! @name Structure to define OIS output */
1680 struct bmi2_ois_output
1682 /*! OIS accel x axis */
1685 /*! OIS accel y axis */
1688 /*! OIS accel z axis */
1691 /*! ois gyro x axis */
1694 /*! OIS gyro y axis */
1697 /*! OIS gyro z axis */
1701 /*! @name Union to define BMI2 sensor data */
1702 union bmi2_sens_data
1704 /*! Accelerometer axes data */
1705 struct bmi2_sens_axes_data acc
;
1707 /*! Gyroscope axes data */
1708 struct bmi2_sens_axes_data gyr
;
1710 /*! Auxiliary sensor data */
1711 uint8_t aux_data
[BMI2_AUX_NUM_BYTES
];
1713 /*! Step counter output */
1714 uint32_t step_counter_output
;
1716 /*! Step activity output */
1717 uint8_t activity_output
;
1719 /*! Orientation output */
1720 struct bmi2_orientation_output orient_output
;
1722 /*! High-g output */
1723 uint8_t high_g_output
;
1725 /*! Gyroscope user gain saturation status */
1726 struct bmi2_gyr_user_gain_status gyro_user_gain_status
;
1728 /*! NVM error status */
1729 struct bmi2_nvm_err_status nvm_status
;
1731 /*! Virtual frame error status */
1732 struct bmi2_vfrm_err_status vfrm_status
;
1734 /*! Wrist gesture output */
1735 uint8_t wrist_gesture_output
;
1737 /*! Gyroscope cross sense value of z axis */
1738 int16_t correction_factor_zx
;
1740 /*! Accelerometer self test feature status */
1741 struct bmi2_acc_self_test_status accel_self_test_output
;
1744 struct bmi2_ois_output ois_output
;
1747 /*! @name Structure to define type of sensor and their respective data */
1748 struct bmi2_sensor_data
1750 /*! Defines the type of sensor */
1753 /*! Defines various sensor data */
1754 union bmi2_sens_data sens_data
;
1757 /*! @name Structure to define accelerometer configuration */
1758 struct bmi2_accel_config
1760 /*! Output data rate in Hz */
1763 /*! Bandwidth parameter */
1766 /*! Filter performance mode */
1767 uint8_t filter_perf
;
1773 /*! @name Structure to define gyroscope configuration */
1774 struct bmi2_gyro_config
1776 /*! Output data rate in Hz */
1779 /*! Bandwidth parameter */
1782 /*! Filter performance mode */
1783 uint8_t filter_perf
;
1788 /*! Gyroscope Range */
1791 /*! Selects noise performance */
1795 /*! @name Structure to define auxiliary sensor configuration */
1796 struct bmi2_aux_config
1798 /*! Enable/Disable auxiliary interface */
1801 /*! Manual or Auto mode*/
1804 /*! Enables FCU write command on auxiliary interface */
1805 uint8_t fcu_write_en
;
1807 /*! Read burst length for manual mode */
1808 uint8_t man_rd_burst
;
1810 /*! Read burst length for data mode */
1811 uint8_t aux_rd_burst
;
1813 /*! Output data rate */
1816 /*! Read-out offset */
1819 /*! I2c address of auxiliary sensor */
1820 uint8_t i2c_device_addr
;
1822 /*! Read address of auxiliary sensor */
1826 /*! @name Structure to define any-motion configuration */
1827 struct bmi2_any_motion_config
1829 /*! Duration in 50Hz samples(20msec) */
1832 /*! Acceleration slope threshold */
1835 /*! To select per x-axis */
1838 /*! To select per y-axis */
1841 /*! To select per z-axis */
1845 /*! @name Structure to define no-motion configuration */
1846 struct bmi2_no_motion_config
1848 /*! Duration in 50Hz samples(20msec) */
1851 /*! Acceleration slope threshold */
1854 /*! To select per x-axis */
1857 /*! To select per y-axis */
1860 /*! To select per z-axis */
1864 /*! @name Structure to define sig-motion configuration */
1865 struct bmi2_sig_motion_config
1868 uint16_t block_size
;
1883 /*! @name Structure to define step counter/detector/activity configuration */
1884 struct bmi2_step_config
1886 /*! Water-mark level */
1887 uint16_t watermark_level
;
1889 /*! Reset counter */
1890 uint16_t reset_counter
;
1892 /*! Step buffer size */
1893 uint8_t step_buffer_size
;
1896 /*! @name Structure to define gyroscope user gain configuration */
1897 struct bmi2_gyro_user_gain_config
1899 /*! Gain update value for x-axis */
1902 /*! Gain update value for y-axis */
1905 /*! Gain update value for z-axis */
1909 /*! @name Structure to define wake-up configuration */
1910 struct bmi2_wake_up_config
1912 /*! Wake-up sensitivity for bmi261 */
1913 uint16_t sensitivity
;
1915 /*! Tap feature for BMI261
1916 * For Single tap, single_tap_en = 1
1917 * For Double tap, single_tap_en = 0
1919 uint16_t single_tap_en
;
1921 /*! Enable -> Filtered tap data, Disable -> Unfiltered data */
1922 uint16_t data_reg_en
;
1924 /*! Scaling factor of threshold */
1925 uint16_t tap_sens_thres
;
1927 /*! Maximum duration between each taps */
1928 uint16_t max_gest_dur
;
1930 /*! Minimum quite time between the two gesture detection */
1931 uint16_t quite_time_after_gest
;
1934 uint16_t wait_for_timeout
;
1936 /*! Axis selection */
1940 /*! @name Structure to define tap configuration */
1941 struct bmi2_tap_config
1943 /*! Tap sensitivity */
1944 uint16_t sensitivity
;
1947 * For Single tap, single_tap_en = 1
1948 * For Double tap, single_tap_en = 0
1950 uint16_t single_tap_en
;
1952 /*! Enable -> Filtered tap data, Disable -> Unfiltered data */
1953 uint16_t data_reg_en
;
1955 /*! Scaling factor of threshold */
1956 uint16_t tap_sens_thres
;
1958 /*! Maximum duration between each taps */
1959 uint16_t max_gest_dur
;
1961 /*! Minimum quite time between the two gesture detection */
1962 uint16_t quite_time_after_gest
;
1965 uint16_t wait_for_timeout
;
1967 /*! Axis selection */
1971 /*! @name Structure to define orientation configuration */
1972 struct bmi2_orient_config
1974 /*! Upside/down detection */
1977 /*! Symmetrical, high or low Symmetrical */
1980 /*! Blocking mode */
1983 /*! Threshold angle */
1986 /*! Acceleration hysteresis for orientation detection */
1987 uint16_t hysteresis
;
1990 /*! @name Structure to define high-g configuration */
1991 struct bmi2_high_g_config
1993 /*! Acceleration threshold */
1997 uint16_t hysteresis
;
1999 /*! To select per x-axis */
2002 /*! To select per y-axis */
2005 /*! To select per z-axis */
2008 /*! Duration interval */
2012 /*! @name Structure to define low-g configuration */
2013 struct bmi2_low_g_config
2015 /*! Acceleration threshold */
2019 uint16_t hysteresis
;
2021 /*! Duration interval */
2025 /*! @name Structure to define flat configuration */
2026 struct bmi2_flat_config
2028 /*! Theta angle for flat detection */
2031 /*! Blocking mode */
2034 /*! Hysteresis for theta flat detection */
2035 uint16_t hysteresis
;
2037 /*! Holds the duration in 50Hz samples(20msec) */
2041 /*! @name Structure to define wrist gesture configuration */
2042 struct bmi2_wrist_gest_config
2044 /*! Wearable arm (left or right) */
2045 uint16_t wearable_arm
;
2047 /*! Sine of the minimum tilt angle in portrait down direction of the device when wrist is rolled
2048 * away from user. The configuration parameter is scaled by 2048 i.e. 2048 * sin(angle).
2049 * Range is 1448 to 1774. Default value is 1774. */
2050 uint16_t min_flick_peak
;
2052 /*! Value of minimum time difference between wrist roll-out and roll-in movement during flick gesture.
2053 * Range is 3 to 5 samples at 50Hz. Default value is 4 (i.e. 0.08 seconds). */
2054 uint16_t min_flick_samples
;
2056 /*! Maximum time within which gesture movement has to be completed. Range is 150 to 250 samples at 50Hz.
2057 * Default value is 200 (i.e. 4 seconds). */
2058 uint16_t max_duration
;
2061 /*! @name Structure to define wrist wear wake-up configuration */
2062 struct bmi2_wrist_wear_wake_up_config
2064 /*! Cosine of min expected attitude change of the device within 1 second time window when
2065 * moving within focus position.
2066 * The parameter is scaled by 2048 i.e. 2048 * cos(angle). Range is 1024 to 1774.
2067 * Default is 1448. */
2068 uint16_t min_angle_focus
;
2070 /*! Cosine of min expected attitude change of the device within 1 second time window when
2071 * moving from non-focus to focus position.
2072 * The parameter is scaled by 2048 i.e. 2048 * cos(angle). Range is 1448 to 1856.
2073 * Default value is 1774. */
2074 uint16_t min_angle_nonfocus
;
2076 /*! Sine of the max allowed downward tilt angle in landscape right direction of the device,
2077 * when it is in focus position
2078 * (i.e. user is able to comfortably look at the dial of wear device).
2079 * The configuration parameter is scaled by 2048 i.e. 2048 * sin(angle). Range is 700 to 1024.
2080 * Default value is 1024. */
2081 uint16_t max_tilt_lr
;
2083 /*! Sine of the max allowed downward tilt angle in landscape left direction of the device,
2084 * when it is in focus position
2085 * (i.e. user is able to comfortably look at the dial of wear device).
2086 * The configuration parameter is scaled by 2048 i.e. 2048 * sin(angle). Range is 700 to
2087 * 1024. Default value is 700. */
2088 uint16_t max_tilt_ll
;
2090 /*! Sine of the max allowed backward tilt angle in portrait down direction of the device,
2091 * when it is in focus position
2092 * (i.e. user is able to comfortably look at the dial of wear device).
2093 * The configuration parameter is scaled by 2048 i.e. 2048 * sin(angle). Range is 0 to179.
2094 * Default value is 179. */
2095 uint16_t max_tilt_pd
;
2097 /*! Sine of the maximum allowed forward tilt angle in portrait up direction of the
2098 * device, when it is in focus position
2099 * (i.e. user is able to comfortably look at the dial of wear device).
2100 * The configuration parameter is scaled by 2048 i.e. 2048 * sin(angle). Range is 1774 to 1978.
2101 * Default value is 1925. */
2102 uint16_t max_tilt_pu
;
2105 /*! @name Structure to define wrist gesture configuration for wearable variant */
2106 struct bmi2_wrist_gest_w_config
2108 /*! Wearable arm (left or right) */
2109 uint8_t device_position
;
2111 /*! Minimum threshold for flick peak on y-axis */
2112 uint16_t min_flick_peak_y_threshold
;
2114 /*! Minimum threshold for flick peak on z-axis */
2115 uint16_t min_flick_peak_z_threshold
;
2117 /*! Maximum expected value of positive gravitational acceleration on x-axis
2118 * when arm is in focus pose */
2119 uint16_t gravity_bounds_x_pos
;
2121 /*! Maximum expected value of negative gravitational acceleration on x-axis
2122 * when arm is in focus pose */
2123 uint16_t gravity_bounds_x_neg
;
2125 /*! Maximum expected value of negative gravitational acceleration on y-axis
2126 * when arm is in focus pose */
2127 uint16_t gravity_bounds_y_neg
;
2129 /*! Maximum expected value of negative gravitational acceleration on z-axis
2130 * when arm is in focus pose */
2131 uint16_t gravity_bounds_z_neg
;
2133 /*! Exponential smoothing coefficient for adaptive peak threshold decay */
2134 uint16_t flick_peak_decay_coeff
;
2136 /*! Exponential smoothing coefficient for acceleration mean estimation */
2137 uint16_t lp_mean_filter_coeff
;
2139 /*! Maximum duration between 2 peaks of jiggle in samples @50Hz */
2140 uint16_t max_duration_jiggle_peaks
;
2143 /*! @name Structure to define wrist wear wake-up configuration for wearable configuration */
2144 struct bmi2_wrist_wear_wake_up_wh_config
2146 /*! Cosine of min expected attitude change of the device within 1 second time window when
2147 * moving within focus position.
2148 * The parameter is scaled by 2048 i.e. 2048 * cos(angle). Range is 1024 to 1774.
2149 * Default is 1448. */
2150 uint16_t min_angle_focus
;
2152 /*! Cosine of min expected attitude change of the device within 1 second time window when
2153 * moving from non-focus to focus position.
2154 * The parameter is scaled by 2048 i.e. 2048 * cos(angle). Range is 1448 to 1856.
2155 * Default value is 1774. */
2156 uint16_t min_angle_nonfocus
;
2158 /*! Sine of the max allowed downward tilt angle in landscape right direction of the device,
2159 * when it is in focus position (i.e. user is able to comfortably look at the dial of wear device).
2160 * The configuration parameter is scaled by 256 i.e. 256 * sin(angle). Range is 88 to 128.
2161 * Default value is 128. */
2164 /*! Sine of the max allowed downward tilt angle in landscape left direction of the device,
2165 * when it is in focus position (i.e. user is able to comfortably look at the dial of wear device).
2166 * The configuration parameter is scaled by 256 i.e. 256 * sin(angle). Range is 88 to 128.
2167 * Default value is 128. */
2170 /*! Sine of the max allowed backward tilt angle in portrait down direction of the device,
2171 * when it is in focus position (i.e. user is able to comfortably look at the dial of wear device).
2172 * The configuration parameter is scaled by 256 i.e. 256 * sin(angle). Range is 0 to 179.
2173 * Default value is 22. */
2176 /*! Sine of the maximum allowed forward tilt angle in portrait up direction of the device,
2177 * when it is in focus position (i.e. user is able to comfortably look at the dial of wear device).
2178 * The configuration parameter is scaled by 256 i.e. 256 * sin(angle). Range is 222 to 247.
2179 * Default value is 241. */
2182 /*! Minimum duration the arm should be moved while performing gesture. Range: 1 to 10,
2183 * resolution = 20 ms.
2184 * Default 2(40 ms)*/
2185 uint8_t min_dur_mov
;
2187 /*! Minimum duration the arm should be static between two consecutive gestures. Range: 1 to
2188 * 10, resolution = 20 ms
2189 * Default 2(40 ms)*/
2190 uint8_t min_dur_quite
;
2193 /*! @name Structure to define primary OIS configuration */
2194 struct bmi2_primary_ois_config
2196 uint8_t lp_filter_enable
;
2198 uint8_t lp_filter_config
;
2200 uint8_t primary_ois_reserved
;
2202 uint8_t primary_ois_gyro_en
;
2204 uint8_t primary_ois_accel_en
;
2207 /*! @name Structure to configure free-fall detection settings */
2208 struct bmi2_free_fall_det_config
2210 /*! free-fall accel settings */
2211 uint16_t freefall_accel_settings
[BMI2_FREE_FALL_ACCEL_SET_PARAMS
];
2214 /*! @name Union to define the sensor configurations */
2215 union bmi2_sens_config_types
2217 /*! Accelerometer configuration */
2218 struct bmi2_accel_config acc
;
2220 /*! Gyroscope configuration */
2221 struct bmi2_gyro_config gyr
;
2223 /*! Auxiliary configuration */
2224 struct bmi2_aux_config aux
;
2226 /*! Any-motion configuration */
2227 struct bmi2_any_motion_config any_motion
;
2229 /*! No-motion configuration */
2230 struct bmi2_no_motion_config no_motion
;
2232 /*! Sig_motion configuration */
2233 struct bmi2_sig_motion_config sig_motion
;
2235 /*! Step counter parameter configuration */
2236 uint16_t step_counter_params
[BMI2_STEP_CNT_N_PARAMS
];
2238 /*! Step counter/detector/activity configuration */
2239 struct bmi2_step_config step_counter
;
2241 /*! Gyroscope user gain configuration */
2242 struct bmi2_gyro_user_gain_config gyro_gain_update
;
2244 /*! Wake-up configuration */
2245 struct bmi2_wake_up_config tap
;
2247 /*! Tap configuration */
2248 struct bmi2_tap_config tap_conf
;
2250 /*! Orientation configuration */
2251 struct bmi2_orient_config orientation
;
2253 /*! High-g configuration */
2254 struct bmi2_high_g_config high_g
;
2256 /*! Low-g configuration */
2257 struct bmi2_low_g_config low_g
;
2259 /*! Flat configuration */
2260 struct bmi2_flat_config flat
;
2262 /*! Wrist gesture configuration */
2263 struct bmi2_wrist_gest_config wrist_gest
;
2265 /*! Wrist wear wake-up configuration */
2266 struct bmi2_wrist_wear_wake_up_config wrist_wear_wake_up
;
2268 /*! Wrist gesture configuration for wearable variant */
2269 struct bmi2_wrist_gest_w_config wrist_gest_w
;
2271 /*! Wrist wear wake-up configuration for wearable variant */
2272 struct bmi2_wrist_wear_wake_up_wh_config wrist_wear_wake_up_wh
;
2274 /*! Primary OIS configuration */
2275 struct bmi2_primary_ois_config primary_ois
;
2277 /* Free-fall detection configurations */
2278 struct bmi2_free_fall_det_config free_fall_det
;
2281 /*! @name Structure to define the type of the sensor and its configurations */
2282 struct bmi2_sens_config
2284 /*! Defines the type of sensor */
2287 /*! Defines various sensor configurations */
2288 union bmi2_sens_config_types cfg
;
2291 /*! @name Structure to define the feature configuration */
2292 struct bmi2_feature_config
2294 /*! Defines the type of sensor */
2297 /*! Page to where the feature is mapped */
2300 /*! Address of the feature */
2304 /*! @name Structure to define the feature interrupt configurations */
2307 /*! Defines the type of sensor */
2310 /*! Defines the feature interrupt */
2311 uint8_t sens_map_int
;
2314 /*! @name Structure to define BMI2 sensor configurations */
2317 /*! Chip id of BMI2 */
2320 /*! The interface pointer is used to enable the user
2321 * to link their interface descriptors for reference during the
2322 * implementation of the read and write interfaces to the
2327 /*! To store warnings */
2330 /*! Type of Interface */
2331 enum bmi2_intf intf
;
2333 /*! To store interface pointer error */
2334 BMI2_INTF_RETURN_TYPE intf_rslt
;
2336 /*! For switching from I2C to SPI */
2339 /*! Resolution for FOC */
2342 /*! User set read/write length */
2343 uint16_t read_write_len
;
2345 /*! Pointer to the configuration data buffer address */
2346 const uint8_t *config_file_ptr
;
2348 /*! To define maximum page number */
2351 /*! To define maximum number of input sensors/features */
2354 /*! To define maximum number of output sensors/features */
2357 /*! Indicate manual enable for auxiliary communication */
2360 /*! Defines manual read burst length for auxiliary communication */
2361 uint8_t aux_man_rd_burst_len
;
2363 /*! Array of feature input configuration structure */
2364 const struct bmi2_feature_config
*feat_config
;
2366 /*! Array of feature output configuration structure */
2367 const struct bmi2_feature_config
*feat_output
;
2369 /*! Structure to maintain a copy of the re-mapped axis */
2370 struct bmi2_axes_remap remap
;
2372 /*! Flag to hold enable status of sensors */
2373 uint64_t sens_en_stat
;
2375 /*! Read function pointer */
2376 bmi2_read_fptr_t read
;
2378 /*! Write function pointer */
2379 bmi2_write_fptr_t write
;
2381 /*! Delay function pointer */
2382 bmi2_delay_fptr_t delay_us
;
2384 /*! To store the gyroscope cross sensitivity value */
2385 int16_t gyr_cross_sens_zx
;
2387 /* gyro enable status, used as a flag in CRT enabling and aborting */
2388 uint8_t gyro_en
: 1;
2390 /* advance power saving mode status, used as a flag in CRT enabling and aborting */
2393 /* used as a flag to enable variant specific features like crt */
2394 uint16_t variant_feature
;
2396 /* To store hold the size of config file */
2397 uint16_t config_size
;
2399 /*! Function pointer to get wakeup configurations */
2400 bmi2_wake_up_fptr_t get_wakeup_config
;
2402 /*! Function pointer to set wakeup configurations */
2403 bmi2_wake_up_fptr_t set_wakeup_config
;
2405 /*! Function pointer to get tap configurations */
2406 bmi2_tap_fptr_t get_tap_config
;
2408 /*! Function pointer to set tap configurations */
2409 bmi2_tap_fptr_t set_tap_config
;
2411 /*! Array of feature interrupts configuration structure */
2412 struct bmi2_map_int
*map_int
;
2414 /*! To define maximum number of interrupts */
2415 uint8_t sens_int_map
;
2418 /*! @name Structure to enable an accel axis for foc */
2419 struct bmi2_accel_foc_g_value
2421 /*! '0' to disable x axis and '1' to enable x axis */
2424 /*! '0' to disable y axis and '1' to enable y axis */
2427 /*! '0' to disable z axis and '1' to enable z axis */
2430 /*! '0' for positive input and '1' for negative input */
2434 /*! @name Structure to configure activity recognition settings */
2435 struct bmi2_act_recg_sett
2437 /*! Activity recognition register 1 */
2438 uint8_t act_rec_1
: 1;
2440 /*! Activity recognition register 2 */
2443 /*! Activity recognition register 3 */
2446 /*! Activity recognition register 4 */
2447 uint8_t act_rec_4
: 4;
2449 /*! Activity recognition register 5 */
2450 uint8_t act_rec_5
: 4;
2453 /*! @name Structure to configure activity recognition settings for bmi270hc */
2454 struct bmi2_hc_act_recg_sett
2456 /*! Static segment size for activity classification. */
2457 uint8_t segment_size
;
2459 /*! Enable/Disable post processing of the activity detected */
2462 /*! Minimum threshold of the Gini's diversity index (GDI) */
2463 uint16_t min_gdi_thres
;
2465 /*! Maximum threshold of the Gini's diversity index (GDI) */
2466 uint16_t max_gdi_thres
;
2468 /*! Buffer size for post processing of the activity detected */
2471 /*! Minimum segments belonging to a certain activity type */
2472 uint16_t min_seg_conf
;
2475 #endif /* BMI2_DEFS_H_ */