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.
39 /******************************************************************************/
41 /*! @name Header Files */
42 /******************************************************************************/
45 /***************************************************************************/
48 ****************************************************************************/
50 /*! @name Structure to define the difference in accelerometer values */
51 struct bmi2_selftest_delta_limit
63 /*! @name Structure to store temporary accelerometer/gyroscope values */
64 struct bmi2_foc_temp_value
76 /*! @name Structure to store accelerometer data deviation from ideal value */
77 struct bmi2_offset_delta
89 /*! @name Structure to store accelerometer offset values */
90 struct bmi2_accel_offset
102 /******************************************************************************/
104 /*! Local Function Prototypes
105 ******************************************************************************/
108 * @brief This internal API writes the configuration file.
110 * @param[in] dev : Structure instance of bmi2_dev.
112 * @return Result of API execution status
113 * @retval 0 -> Success
114 * @retval < 0 -> Fail
116 static int8_t write_config_file(struct bmi2_dev
*dev
);
119 * @brief This internal API enables/disables the loading of the configuration
122 * @param[in] enable : To enable/disable configuration load.
123 * @param[in] dev : Structure instance of bmi2_dev.
125 * @return Result of API execution status
126 * @retval 0 -> Success
127 * @retval < 0 -> Fail
129 static int8_t set_config_load(uint8_t enable
, struct bmi2_dev
*dev
);
132 * @brief This internal API loads the configuration file.
134 * @param[in] config_data : Pointer to the configuration file.
135 * @param[in] index : Variable to define array index.
136 * @param[in] dev : Structure instance of bmi2_dev.
138 * @return Result of API execution status
139 * @retval 0 -> Success
140 * @retval < 0 -> Fail
142 static int8_t upload_file(const uint8_t *config_data
, uint16_t index
, uint16_t write_len
, struct bmi2_dev
*dev
);
145 * @brief This internal API sets accelerometer configurations like ODR,
146 * bandwidth, performance mode and g-range.
148 * @param[in,out] config : Structure instance of bmi2_accel_config.
149 * @param[in,out] dev : Structure instance of bmi2_dev.
151 * @return Result of API execution status
152 * @retval 0 -> Success
153 * @retval < 0 -> Fail
155 static int8_t set_accel_config(struct bmi2_accel_config
*config
, struct bmi2_dev
*dev
);
158 * @brief This internal API validates bandwidth and performance mode of the
159 * accelerometer set by the user.
161 * @param[in, out] bandwidth : Pointer to bandwidth value set by the user.
162 * @param[in, out] perf_mode : Pointer to performance mode set by the user.
163 * @param[in, out] dev : Structure instance of bmi2_dev.
165 * @note dev->info contains two warnings: BMI2_I_MIN_VALUE and BMI2_I_MAX_VALUE
167 * @return Result of API execution status
168 * @retval 0 -> Success
169 * @retval < 0 -> Fail
171 static int8_t validate_bw_perf_mode(uint8_t *bandwidth
, uint8_t *perf_mode
, struct bmi2_dev
*dev
);
174 * @brief This internal API validates ODR and range of the accelerometer set by
177 * @param[in, out] odr : Pointer to ODR value set by the user.
178 * @param[in, out] range : Pointer to range value set by the user.
179 * @param[in, out] dev : Structure instance of bmi2_dev.
181 * @note dev->info contains two warnings: BMI2_I_MIN_VALUE and BMI2_I_MAX_VALUE
183 * @return Result of API execution status
184 * @retval 0 -> Success
185 * @retval < 0 -> Fail
187 static int8_t validate_odr_range(uint8_t *odr
, uint8_t *range
, struct bmi2_dev
*dev
);
190 * @brief This internal API sets gyroscope configurations like ODR, bandwidth,
191 * low power/high performance mode, performance mode and range.
193 * @param[in,out] config : Structure instance of bmi2_gyro_config.
194 * @param[in,out] dev : Structure instance of bmi2_dev.
196 * @return Result of API execution status
197 * @retval 0 -> Success
198 * @retval < 0 -> Fail
200 static int8_t set_gyro_config(struct bmi2_gyro_config
*config
, struct bmi2_dev
*dev
);
203 * @brief This internal API validates bandwidth, performance mode, low power/
204 * high performance mode, ODR, and range set by the user.
206 * @param[in] config : Structure instance of bmi2_gyro_config.
207 * @param[in] dev : Structure instance of bmi2_dev.
209 * @note dev->info contains two warnings: BMI2_I_MIN_VALUE and BMI2_I_MAX_VALUE
211 * @return Result of API execution status
212 * @retval 0 -> Success
213 * @retval < 0 -> Fail
215 static int8_t validate_gyro_config(struct bmi2_gyro_config
*config
, struct bmi2_dev
*dev
);
218 * @brief This internal API shows the error status when illegal sensor
219 * configuration is set.
221 * @param[in] dev : Structure instance of bmi2_dev.
223 * @return Result of API execution status
224 * @retval 0 -> Success
225 * @retval < 0 -> Fail
227 static int8_t cfg_error_status(struct bmi2_dev
*dev
);
230 * @brief This internal API:
231 * 1) Enables/Disables auxiliary interface.
232 * 2) Sets auxiliary interface configurations like I2C address, manual/auto
233 * mode enable, manual burst read length, AUX burst read length and AUX read
235 * 3)It maps/un-maps data interrupts to that of hardware interrupt line.
237 * @param[in] config : Structure instance of bmi2_aux_config.
238 * @param[in, out] dev : Structure instance of bmi2_dev.
240 * @return Result of API execution status
241 * @retval 0 -> Success
242 * @retval < 0 -> Fail
244 static int8_t set_aux_config(struct bmi2_aux_config
*config
, struct bmi2_dev
*dev
);
247 * @brief This internal API sets gyroscope user-gain configurations like gain
248 * update value for x, y and z-axis.
250 * @param[in] config : Structure instance of bmi2_gyro_user_gain_config.
251 * @param[in] dev : Structure instance of bmi2_dev.
254 *----------------------------------------------------------------------------
255 * bmi2_gyro_user_gain_config|
256 * Structure parameters | Description
257 *--------------------------|--------------------------------------------------
258 * ratio_x | Gain update value for x-axis
259 * -------------------------|---------------------------------------------------
260 * ratio_y | Gain update value for y-axis
261 * -------------------------|---------------------------------------------------
262 * ratio_z | Gain update value for z-axis
265 * @return Result of API execution status
266 * @retval 0 -> Success
267 * @retval < 0 -> Fail
269 static int8_t set_gyro_user_gain_config(const struct bmi2_gyro_user_gain_config
*config
, struct bmi2_dev
*dev
);
272 * @brief This internal API enables/disables auxiliary interface.
274 * @param[in] config : Structure instance of bmi2_aux_config.
275 * @param[in] dev : Structure instance of bmi2_dev.
277 * @return Result of API execution status
278 * @retval 0 -> Success
279 * @retval < 0 -> Fail
281 static int8_t set_aux_interface(const struct bmi2_aux_config
*config
, struct bmi2_dev
*dev
);
284 * @brief This internal API sets auxiliary configurations like manual/auto mode
285 * FCU write command enable and read burst length for both data and manual mode.
287 * @param[in] config : Structure instance of bmi2_aux_config.
288 * @param[in] dev : Structure instance of bmi2_dev.
290 * @note Auxiliary sensor should not be busy when configuring aux_i2c_addr,
291 * man_rd_burst_len, aux_rd_burst_len and aux_rd_addr.
293 * @return Result of API execution status
294 * @retval 0 -> Success
295 * @retval < 0 -> Fail
297 static int8_t config_aux_interface(const struct bmi2_aux_config
*config
, struct bmi2_dev
*dev
);
300 * @brief This internal API triggers read out offset and sets ODR of the
303 * @param[in] config : Structure instance of bmi2_aux_config.
304 * @param[in] dev : Structure instance of bmi2_dev.
306 * @return Result of API execution status
307 * @retval 0 -> Success
308 * @retval < 0 -> Fail
310 static int8_t config_aux(const struct bmi2_aux_config
*config
, struct bmi2_dev
*dev
);
313 * @brief This internal API validates auxiliary configuration set by the user.
315 * @param[in, out] config : Structure instance of bmi2_aux_config.
316 * @param[in, out] dev : Structure instance of bmi2_dev.
318 * @note dev->info contains two warnings: BMI2_I_MIN_VALUE and BMI2_I_MAX_VALUE
320 * @return Result of API execution status
321 * @retval 0 -> Success
322 * @retval < 0 -> Fail
324 static int8_t validate_aux_config(struct bmi2_aux_config
*config
, struct bmi2_dev
*dev
);
327 * @brief This internal API gets accelerometer configurations like ODR,
328 * bandwidth, performance mode and g-range.
330 * @param[out] config : Structure instance of bmi2_accel_config.
331 * @param[in] dev : Structure instance of bmi2_dev.
333 * @return Result of API execution status
334 * @retval 0 -> Success
335 * @retval < 0 -> Fail
337 static int8_t get_accel_config(struct bmi2_accel_config
*config
, struct bmi2_dev
*dev
);
340 * @brief This internal API gets gyroscope configurations like ODR, bandwidth,
341 * low power/ high performance mode, performance mode and range.
343 * @param[out] config : Structure instance of bmi2_gyro_config.
344 * @param[in] dev : Structure instance of bmi2_dev.
346 * @return Result of API execution status
347 * @retval 0 -> Success
348 * @retval < 0 -> Fail
350 static int8_t get_gyro_config(struct bmi2_gyro_config
*config
, struct bmi2_dev
*dev
);
353 * @brief This internal API:
354 * 1) Gets the status of auxiliary interface enable.
355 * 2) Gets auxiliary interface configurations like I2C address, manual/auto
356 * mode enable, manual burst read length, AUX burst read length and AUX read
358 * 3) Gets ODR and offset.
360 * @param[out] config : Structure instance of bmi2_aux_config.
361 * @param[in] dev : Structure instance of bmi2_dev.
363 * @return Result of API execution status
364 * @retval 0 -> Success
365 * @retval < 0 -> Fail
367 static int8_t get_aux_config(struct bmi2_aux_config
*config
, struct bmi2_dev
*dev
);
370 * @brief This internal API gets gyroscope user-gain configurations like gain
371 * update value for x, y and z-axis.
373 * @param[out] config : Structure instance of bmi2_gyro_user_gain_config.
374 * @param[in] dev : Structure instance of bmi2_dev.
377 *----------------------------------------------------------------------------
378 * bmi2_gyro_user_gain_config|
379 * Structure parameters | Description
380 *-------------------------|--------------------------------------------------
381 * ratio_x | Gain update value for x-axis
382 * ------------------------|---------------------------------------------------
383 * ratio_y | Gain update value for y-axis
384 * ------------------------|---------------------------------------------------
385 * ratio_z | Gain update value for z-axis
389 * @return Result of API execution status
390 * @retval 0 -> Success
391 * @retval < 0 -> Fail
393 static int8_t get_gyro_gain_update_config(struct bmi2_gyro_user_gain_config
*config
, struct bmi2_dev
*dev
);
396 * @brief This internal API gets the enable status of auxiliary interface.
398 * @param[out] config : Structure instance of bmi2_aux_config.
399 * @param[in] dev : Structure instance of bmi2_dev.
401 * @return Result of API execution status
402 * @retval 0 -> Success
403 * @retval < 0 -> Fail
405 static int8_t get_aux_interface(struct bmi2_aux_config
*config
, struct bmi2_dev
*dev
);
408 * @brief This internal API gets auxiliary configurations like manual/auto mode
409 * FCU write command enable and read burst length for both data and manual mode.
411 * @param[out] config : Structure instance of bmi2_aux_config.
412 * @param[in] dev : Structure instance of bmi2_dev.
414 * @return Result of API execution status
415 * @retval 0 -> Success
416 * @retval < 0 -> Fail
418 static int8_t get_aux_interface_config(struct bmi2_aux_config
*config
, struct bmi2_dev
*dev
);
421 * @brief This internal API gets read out offset and ODR of the auxiliary
424 * @param[out] config : Structure instance of bmi2_aux_config.
425 * @param[in] dev : Structure instance of bmi2_dev.
427 * @return Result of API execution status
428 * @retval 0 -> Success
429 * @retval < 0 -> Fail
431 static int8_t get_aux_cfg(struct bmi2_aux_config
*config
, struct bmi2_dev
*dev
);
434 * @brief This internal API gets the saturation status for the gyroscope user
437 * @param[out] user_gain_stat : Stores the saturation status of the axes.
438 * @param[in] dev : Structure instance of bmi2_dev.
440 * @return Result of API execution status
441 * @retval 0 -> Success
442 * @retval < 0 -> Fail
444 static int8_t get_gyro_gain_update_status(struct bmi2_gyr_user_gain_status
*user_gain
, struct bmi2_dev
*dev
);
447 * @brief This internal API is used to extract the output feature configuration
448 * details like page and start address from the look-up table.
450 * @param[out] feat_output : Structure that stores output feature
452 * @param[in] type : Type of feature or sensor.
453 * @param[in] dev : Structure instance of bmi2_dev.
455 * @return Returns the feature found flag.
457 * @retval BMI2_FALSE : Feature not found
458 * BMI2_TRUE : Feature found
460 static uint8_t extract_output_feat_config(struct bmi2_feature_config
*feat_output
,
462 const struct bmi2_dev
*dev
);
465 * @brief This internal API gets the cross sensitivity coefficient between
466 * gyroscope's X and Z axes.
468 * @param[out] cross_sense : Pointer to the stored cross sensitivity
470 * @param[in] dev : Structure instance of bmi2_dev.
472 * @return Result of API execution status
473 * @retval 0 -> Success
474 * @retval < 0 -> Fail
476 static int8_t get_gyro_cross_sense(int16_t *cross_sense
, struct bmi2_dev
*dev
);
479 * @brief This internal API gets the accelerometer data from the register.
481 * @param[out] data : Structure instance of sensor_data.
482 * @param[in] reg_addr : Register address where data is stored.
483 * @param[in] dev : Structure instance of bmi2_dev.
485 * @return Result of API execution status
486 * @retval 0 -> Success
487 * @retval < 0 -> Fail
489 static int8_t get_accel_sensor_data(struct bmi2_sens_axes_data
*data
, uint8_t reg_addr
, struct bmi2_dev
*dev
);
492 * @brief This internal API gets the gyroscope data from the register.
494 * @param[out] data : Structure instance of sensor_data.
495 * @param[in] reg_addr : Register address where data is stored.
496 * @param[in] dev : Structure instance of bmi2_dev.
498 * @return Result of API execution status
499 * @retval 0 -> Success
500 * @retval < 0 -> Fail
502 static int8_t get_gyro_sensor_data(struct bmi2_sens_axes_data
*data
, uint8_t reg_addr
, struct bmi2_dev
*dev
);
505 * @brief This internal API gets the accelerometer/gyroscope data.
507 * @param[out] data : Structure instance of sensor_data.
508 * @param[in] reg_data : Data stored in the register.
514 static void get_acc_gyr_data(struct bmi2_sens_axes_data
*data
, const uint8_t *reg_data
);
517 * @brief This internal API gets the re-mapped accelerometer/gyroscope data.
519 * @param[out] data : Structure instance of sensor_data.
520 * @param[in] dev : Structure instance of bmi2_dev.
526 static void get_remapped_data(struct bmi2_sens_axes_data
*data
, const struct bmi2_dev
*dev
);
529 * @brief This internal API reads the user-defined bytes of data from the given
530 * register address of auxiliary sensor in data mode.
532 * @param[out] aux_data : Pointer to the stored auxiliary data.
533 * @param[in] dev : Structure instance of bmi2_dev.
535 * @return Result of API execution status
536 * @retval 0 -> Success
537 * @retval < 0 -> Fail
539 static int8_t read_aux_data_mode(uint8_t *aux_data
, struct bmi2_dev
*dev
);
542 * @brief This internal API reads the user-defined bytes of data from the given
543 * register address of auxiliary sensor in manual mode.
545 * @param[in] reg_addr : AUX address from where data is read.
546 * @param[out] aux_data : Pointer to the stored auxiliary data.
547 * @param[in] len : Total bytes to be read.
548 * @param[in] burst_len : Bytes of data to be read in bursts.
549 * @param[in] dev : Structure instance of bmi2_dev.
551 * @return Result of API execution status
552 * @retval 0 -> Success
553 * @retval < 0 -> Fail
555 static int8_t read_aux_data(uint8_t reg_addr
, uint8_t *aux_data
, uint16_t len
, uint8_t burst_len
, struct bmi2_dev
*dev
);
558 * @brief This internal API checks the busy status of auxiliary sensor and sets
559 * the auxiliary register addresses when not busy.
561 * @param[in] reg_addr : Address in which AUX register address is
563 * @param[in] reg_data : Auxiliary register address to be set when AUX is
565 * @param[in] dev : Structure instance of bmi2_dev.
567 * @return Result of API execution status
568 * @retval 0 -> Success
569 * @retval < 0 -> Fail
571 static int8_t set_if_aux_not_busy(uint8_t reg_addr
, uint8_t reg_data
, struct bmi2_dev
*dev
);
574 * @brief his internal API maps the actual burst read length with that of the
575 * register value set by user.
577 * @param[out] len : Actual burst length.
578 * @param[in] dev : Structure instance of bmi2_dev.
580 * @return Result of API execution status
581 * @retval 0 -> Success
582 * @retval < 0 -> Fail
584 static int8_t map_read_len(uint8_t *len
, const struct bmi2_dev
*dev
);
587 * @brief This internal API writes AUX write address and the user-defined bytes
588 * of data to the AUX sensor in manual mode.
590 * @note Change of BMI2_AUX_WR_ADDR is only allowed if AUX is not busy.
592 * @param[in] reg_addr : AUX address in which data is to be written.
593 * @param[in] reg_data : Data to be written
594 * @param[in] dev : Structure instance of bmi2_dev.
596 * @note Change of BMI2_AUX_WR_ADDR is only allowed if AUX is not busy.
598 * @return Result of API execution status
599 * @retval 0 -> Success
600 * @retval < 0 -> Fail
602 static int8_t write_aux_data(uint8_t reg_addr
, uint8_t reg_data
, struct bmi2_dev
*dev
);
605 * @brief This internal API maps/unmaps feature interrupts to that of interrupt
608 * @param[in] int_pin : Interrupt pin selected.
609 * @param[in] feat_int : Type of feature interrupt to be mapped.
610 * @param[in] dev : Structure instance of bmi2_dev.
612 * @return Result of API execution status
613 * @retval 0 -> Success
614 * @retval < 0 -> Fail
616 static int8_t map_feat_int(uint8_t *reg_data_array
, enum bmi2_hw_int_pin int_pin
, uint8_t int_mask
);
619 * @brief This internal API computes the number of bytes of accelerometer FIFO
620 * data which is to be parsed in header-less mode.
622 * @param[out] start_idx : The start index for parsing data.
623 * @param[out] len : Number of bytes to be parsed.
624 * @param[in] acc_count : Number of accelerometer frames to be read.
625 * @param[in] fifo : Structure instance of bmi2_fifo_frame.
627 * @return Result of API execution status
628 * @retval 0 -> Success
629 * @retval < 0 -> Fail
631 static int8_t parse_fifo_accel_len(uint16_t *start_idx
,
633 const uint16_t *acc_count
,
634 const struct bmi2_fifo_frame
*fifo
);
637 * @brief This internal API is used to parse accelerometer data from the FIFO
638 * data in header mode.
640 * @param[out] acc : Structure instance of bmi2_sens_axes_data where
641 * the parsed accelerometer data bytes are stored.
642 * @param[in] accel_length : Number of accelerometer frames (x,y,z data).
643 * @param[in] fifo : Structure instance of bmi2_fifo_frame.
644 * @param[in] dev : Structure instance of bmi2_dev.
646 * @return Result of API execution status
647 * @retval 0 -> Success
648 * @retval < 0 -> Fail
650 static int8_t extract_accel_header_mode(struct bmi2_sens_axes_data
*acc
,
651 uint16_t *accel_length
,
652 struct bmi2_fifo_frame
*fifo
,
653 const struct bmi2_dev
*dev
);
656 * @brief This internal API is used to parse the accelerometer data from the
657 * FIFO data in both header and header-less mode. It updates the current data
660 * @param[in,out] acc : Structure instance of bmi2_sens_axes_data where
661 * where the parsed data bytes are stored.
662 * @param[in,out] idx : Index value of number of bytes parsed.
663 * @param[in,out] acc_idx : Index value of accelerometer data (x,y,z axes)
664 * frame to be parsed.
665 * @param[in] frame : Either data is enabled by user in header-less
666 * mode or header frame value in header mode.
667 * @param[in] fifo : Structure instance of bmi2_fifo_frame.
668 * @param[in] dev : Structure instance of bmi2_dev.
670 * @return Result of API execution status
671 * @retval 0 -> Success
672 * @retval < 0 -> Fail
674 static int8_t unpack_accel_frame(struct bmi2_sens_axes_data
*acc
,
678 const struct bmi2_fifo_frame
*fifo
,
679 const struct bmi2_dev
*dev
);
682 * @brief This internal API is used to parse accelerometer data from the FIFO
685 * @param[out] acc : Structure instance of bmi2_sens_axes_data
686 * where the parsed data bytes are stored.
687 * @param[in] data_start_index : Index value of the accelerometer data bytes
688 * which is to be parsed from the FIFO data.
689 * @param[in] fifo : Structure instance of bmi2_fifo_frame.
690 * @param[in] dev : Structure instance of bmi2_dev.
695 static void unpack_accel_data(struct bmi2_sens_axes_data
*acc
,
696 uint16_t data_start_index
,
697 const struct bmi2_fifo_frame
*fifo
,
698 const struct bmi2_dev
*dev
);
701 * @brief This internal API computes the number of bytes of gyroscope FIFO data
702 * which is to be parsed in header-less mode.
704 * @param[out] start_idx : The start index for parsing data.
705 * @param[out] len : Number of bytes to be parsed.
706 * @param[in] gyr_count : Number of gyroscope frames to be read.
707 * @param[in] frame : Either data enabled by user in header-less
708 * mode or header frame value in header mode.
709 * @param[in] fifo : Structure instance of bmi2_fifo_frame.
711 * @return Result of API execution status
712 * @retval 0 -> Success
713 * @retval < 0 -> Fail
715 static int8_t parse_fifo_gyro_len(uint16_t *start_idx
,
717 const uint16_t *gyr_count
,
718 const struct bmi2_fifo_frame
*fifo
);
721 * @brief This internal API is used to parse the gyroscope data from the FIFO
722 * data in both header and header-less mode It updates the current data byte to
725 * @param[in,out] gyr : Structure instance of bmi2_sens_axes_data.
726 * @param[in,out] idx : Index value of number of bytes parsed
727 * @param[in,out] gyr_idx : Index value of gyroscope data (x,y,z axes)
728 * frame to be parsed.
729 * @param[in] frame : Either data is enabled by user in header-less
730 * mode or header frame value in header mode.
731 * @param[in] fifo : Structure instance of bmi2_fifo_frame.
732 * @param[in] dev : Structure instance of bmi2_dev.
734 * @return Result of API execution status
735 * @retval 0 -> Success
736 * @retval < 0 -> Fail
738 static int8_t unpack_gyro_frame(struct bmi2_sens_axes_data
*gyr
,
742 const struct bmi2_fifo_frame
*fifo
,
743 const struct bmi2_dev
*dev
);
746 * @brief This internal API is used to parse gyroscope data from the FIFO data.
748 * @param[out] gyr : Structure instance of bmi2_sens_axes_data where
749 * the parsed gyroscope data bytes are stored.
750 * @param[in] data_start_index : Index value of the gyroscope data bytes
751 * which is to be parsed from the FIFO data.
752 * @param[in] fifo : Structure instance of bmi2_fifo_frame.
753 * @param[in] dev : Structure instance of bmi2_dev.
758 static void unpack_gyro_data(struct bmi2_sens_axes_data
*gyr
,
759 uint16_t data_start_index
,
760 const struct bmi2_fifo_frame
*fifo
,
761 const struct bmi2_dev
*dev
);
764 * @brief This internal API is used to parse the gyroscope data from the
765 * FIFO data in header mode.
767 * @param[out] gyr : Structure instance of bmi2_sens_axes_data where
768 * the parsed gyroscope data bytes are stored.
769 * @param[in] gyro_length : Number of gyroscope frames (x,y,z data).
770 * @param[in] fifo : Structure instance of bmi2_fifo_frame.
771 * @param[in] dev : Structure instance of bmi2_dev.
773 * @return Result of API execution status
774 * @retval 0 -> Success
775 * @retval < 0 -> Fail
777 static int8_t extract_gyro_header_mode(struct bmi2_sens_axes_data
*gyr
,
778 uint16_t *gyro_length
,
779 struct bmi2_fifo_frame
*fifo
,
780 const struct bmi2_dev
*dev
);
783 * @brief This API computes the number of bytes of auxiliary FIFO data
784 * which is to be parsed in header-less mode.
786 * @param[out] start_idx : The start index for parsing data.
787 * @param[out] len : Number of bytes to be parsed.
788 * @param[in] aux_count : Number of accelerometer frames to be read.
789 * @param[in] fifo : Structure instance of bmi2_fifo_frame.
791 * @return Result of API execution status
792 * @retval 0 -> Success
793 * @retval < 0 -> Fail
795 static int8_t parse_fifo_aux_len(uint16_t *start_idx
,
797 const uint16_t *aux_count
,
798 const struct bmi2_fifo_frame
*fifo
);
801 * @brief This API is used to parse auxiliary data from the FIFO data.
803 * @param[out] aux : Pointer to buffer where the parsed auxiliary data
805 * @param[in] aux_length : Number of auxiliary frames (x,y,z data).
806 * @param[in] fifo : Structure instance of bmi2_fifo_frame.
807 * @param[in] dev : Structure instance of bmi2_dev.
809 * @return Result of API execution status
810 * @retval 0 -> Success
811 * @retval < 0 -> Fail
813 static int8_t extract_aux_header_mode(struct bmi2_aux_fifo_data
*aux
,
814 uint16_t *aux_length
,
815 struct bmi2_fifo_frame
*fifo
,
816 const struct bmi2_dev
*dev
);
819 * @brief This API is used to parse the auxiliary data from the FIFO data in
820 * both header and header-less mode. It updates the current data byte to be
823 * @param[out] aux : Pointer to structure where the parsed auxiliary data
825 * @param[in,out] idx : Index value of number of bytes parsed
826 * @param[in,out] aux_idx : Index value of auxiliary data (x,y,z axes)
828 * @param[in] frame : Either data is enabled by user in header-less
829 * mode or header frame value in header mode.
830 * @param[in] fifo : Structure instance of bmi2_fifo_frame.
831 * @param[in] dev : Structure instance of bmi2_dev.
833 * @return Result of API execution status
834 * @retval 0 -> Success
835 * @retval < 0 -> Fail
837 static int8_t unpack_aux_frame(struct bmi2_aux_fifo_data
*aux
,
841 const struct bmi2_fifo_frame
*fifo
,
842 const struct bmi2_dev
*dev
);
845 * @brief This API is used to parse auxiliary data from the FIFO data.
847 * @param[out] aux : Pointer to structure where the parsed
848 * auxiliary data bytes are stored.
849 * @param[in] data_start_index : Index value of the auxiliary data bytes which
850 * is to be parsed from the FIFO data.
851 * @param[in] fifo : Structure instance of bmi2_fifo_frame.
856 static void unpack_aux_data(struct bmi2_aux_fifo_data
*aux
,
857 uint16_t data_start_index
,
858 const struct bmi2_fifo_frame
*fifo
);
861 * @brief This internal API is used to reset the FIFO related configurations
862 * in the FIFO frame structure for the next FIFO read.
864 * @param[in, out] fifo : Structure instance of bmi2_fifo_frame.
865 * @param[in] dev : Structure instance of bmi2_dev.
870 static void reset_fifo_frame_structure(struct bmi2_fifo_frame
*fifo
, const struct bmi2_dev
*dev
);
873 * @brief This internal API checks whether the FIFO data read is an empty frame.
874 * If empty frame, index is moved to the last byte.
876 * @param[in,out] data_index : The index of the current data to be parsed from
878 * @param[in] fifo : Structure instance of bmi2_fifo_frame.
880 * @return Result of API execution status
882 * @retval BMI2_OK - Success.
883 * @retval BMI2_W_FIFO_EMPTY - Warning : FIFO is empty
884 * @retval BMI2_W_PARTIAL_READ - Warning : There are more frames to be read
886 static int8_t check_empty_fifo(uint16_t *data_index
, const struct bmi2_fifo_frame
*fifo
);
889 * @brief This internal API is used to move the data index ahead of the
890 * current frame length parameter when unnecessary FIFO data appears while
891 * extracting the user specified data.
893 * @param[in,out] data_index : Index of the FIFO data which is to be
894 * moved ahead of the current frame length
895 * @param[in] current_frame_length : Number of bytes in the current frame.
896 * @param[in] fifo : Structure instance of bmi2_fifo_frame.
898 * @return Result of API execution status
899 * @retval 0 -> Success
900 * @retval < 0 -> Fail
902 static int8_t move_next_frame(uint16_t *data_index
, uint8_t current_frame_length
, const struct bmi2_fifo_frame
*fifo
);
905 * @brief This internal API is used to parse and store the sensor time from the
908 * @param[in,out] data_index : Index of the FIFO data which has the sensor time.
909 * @param[in] fifo : Structure instance of bmi2_fifo_frame.
911 * @return Result of API execution status
912 * @retval 0 -> Success
913 * @retval < 0 -> Fail
915 static int8_t unpack_sensortime_frame(uint16_t *data_index
, struct bmi2_fifo_frame
*fifo
);
918 * @brief This internal API is used to parse and store the skipped frame count
919 * from the FIFO data.
921 * @param[in,out] data_index : Index of the FIFO data which contains skipped
923 * @param[in] fifo : Structure instance of bmi2_fifo_frame.
925 * @return Result of API execution status
926 * @retval 0 -> Success
927 * @retval < 0 -> Fail
929 static int8_t unpack_skipped_frame(uint16_t *data_index
, struct bmi2_fifo_frame
*fifo
);
932 * @brief This internal API enables and configures the accelerometer which is
933 * needed for self-test operation. It also sets the amplitude for the self-test.
935 * @param[in] dev : Structure instance of bmi2_dev.
937 * @return Result of API execution status
938 * @retval 0 -> Success
939 * @retval < 0 -> Fail
941 static int8_t pre_self_test_config(struct bmi2_dev
*dev
);
944 * @brief This internal API performs the steps needed for self-test operation
945 * before reading the accelerometer self-test data.
947 * @param[in] sign : Selects sign of self-test excitation
948 * @param[in] dev : Structure instance of bmi2_dev.
951 * -------------|---------------
952 * BMI2_ENABLE | positive excitation
953 * BMI2_DISABLE | negative excitation
955 * @return Result of API execution status
956 * @retval 0 -> Success
957 * @retval < 0 -> Fail
959 static int8_t self_test_config(uint8_t sign
, struct bmi2_dev
*dev
);
962 * @brief This internal API enables or disables the accelerometer self-test
963 * feature in the sensor.
965 * @param[in] enable : Enables/ Disables self-test.
966 * @param[in] dev : Structure instance of bmi2_dev.
969 * -------------|---------------
970 * BMI2_ENABLE | Enables self-test
971 * BMI2_DISABLE | Disables self-test
973 * @return Result of API execution status
974 * @retval 0 -> Success
975 * @retval < 0 -> Fail
977 static int8_t set_accel_self_test_enable(uint8_t enable
, struct bmi2_dev
*dev
);
980 * @brief This internal API selects the sign for accelerometer self-test
983 * @param[in] sign : Selects sign of self-test excitation
984 * @param[in] dev : Structure instance of bmi2_dev.
987 * -------------|---------------
988 * BMI2_ENABLE | positive excitation
989 * BMI2_DISABLE | negative excitation
991 * @return Result of API execution status
992 * @retval 0 -> Success
993 * @retval < 0 -> Fail
995 static int8_t set_acc_self_test_sign(uint8_t sign
, struct bmi2_dev
*dev
);
998 * @brief This internal API sets the amplitude of the accelerometer self-test
999 * deflection in the sensor.
1001 * @param[in] amp : Select amplitude of the self-test deflection.
1002 * @param[in] dev : Structure instance of bmi2_dev.
1005 * -------------|---------------
1006 * BMI2_ENABLE | self-test amplitude is high
1007 * BMI2_DISABLE | self-test amplitude is low
1009 * @return Result of API execution status
1010 * @retval 0 -> Success
1011 * @retval < 0 -> Fail
1013 static int8_t set_accel_self_test_amp(uint8_t amp
, struct bmi2_dev
*dev
);
1016 * @brief This internal API reads the accelerometer data for x,y and z axis from
1017 * the sensor. The data units is in LSB format.
1019 * @param[out] accel : Buffer to store the acceleration value.
1020 * @param[in] dev : Structure instance of bmi2_dev.
1022 * @return Result of API execution status
1023 * @retval 0 -> Success
1024 * @retval < 0 -> Fail
1026 static int8_t read_accel_xyz(struct bmi2_sens_axes_data
*accel
, struct bmi2_dev
*dev
);
1029 * @brief This internal API converts LSB value of accelerometer axes to form
1030 * 'g' to 'mg' for self-test.
1032 * @param[in] acc_data_diff : Stores the acceleration value difference in g.
1033 * @param[out]acc_data_diff_mg : Stores the acceleration value difference in mg.
1034 * @param[in] dev : Structure instance of bmi2_dev.
1039 static void convert_lsb_g(const struct bmi2_selftest_delta_limit
*acc_data_diff
,
1040 struct bmi2_selftest_delta_limit
*acc_data_diff_mg
,
1041 const struct bmi2_dev
*dev
);
1044 * @brief This internal API is used to calculate the power of a value.
1046 * @param[in] base : base for power calculation.
1047 * @param[in] resolution : exponent for power calculation.
1049 * @return the calculated power
1050 * @retval the power value
1052 static int32_t power(int16_t base
, uint8_t resolution
);
1055 * @brief This internal API validates the accelerometer self-test data and
1056 * decides the result of self-test operation.
1058 * @param[in] accel_data_diff : Stores the acceleration value difference.
1060 * @return Result of API execution status
1061 * @retval 0 -> Success
1062 * @retval < 0 -> Fail
1064 static int8_t validate_self_test(const struct bmi2_selftest_delta_limit
*accel_data_diff
);
1067 * @brief This internal API gets the re-mapped x, y and z axes from the sensor.
1069 * @param[out] remap : Structure that stores local copy of re-mapped axes.
1070 * @param[in] dev : Structure instance of bmi2_dev.
1072 * @return Result of API execution status
1073 * @retval 0 -> Success
1074 * @retval < 0 -> Fail
1076 static int8_t get_remap_axes(struct bmi2_axes_remap
*remap
, struct bmi2_dev
*dev
);
1079 * @brief This internal API sets the re-mapped x, y and z axes in the sensor.
1081 * @param[in] remap : Structure that stores local copy of re-mapped axes.
1082 * @param[in] dev : Structure instance of bmi2_dev.
1084 * @return Result of API execution status
1085 * @retval 0 -> Success
1086 * @retval < 0 -> Fail
1088 static int8_t set_remap_axes(const struct bmi2_axes_remap
*remap
, struct bmi2_dev
*dev
);
1091 * @brief Interface to get max burst length
1093 * @param[in] max_burst_len : Pointer to store max burst length
1094 * @param[in] dev : Structure instance of bmi2_dev.
1096 * @return Result of API execution status
1097 * @retval 0 -> Success
1098 * @retval < 0 -> Fail
1100 static int8_t get_maxburst_len(uint8_t *max_burst_len
, struct bmi2_dev
*dev
);
1103 * @brief This internal API sets the max burst length.
1105 * @param[in] write_len_byte : read & write length
1106 * @param[in] dev : Structure instance of bmi2_dev.
1108 * @return Result of API execution status
1109 * @retval 0 -> Success
1110 * @retval < 0 -> Fail
1112 static int8_t set_maxburst_len(const uint16_t write_len_byte
, struct bmi2_dev
*dev
);
1115 * @brief This internal API parses virtual frame header from the FIFO data.
1117 * @param[in, out] frame_header : FIFO frame header.
1118 * @param[in, out] data_index : Index value of the FIFO data bytes
1119 * from which sensor frame header is to be parsed
1120 * @param[in] fifo : Structure instance of bmi2_fifo_frame.
1125 static void parse_if_virtual_header(uint8_t *frame_header
, uint16_t *data_index
, const struct bmi2_fifo_frame
*fifo
);
1128 * @brief This internal API gets sensor time from the accelerometer and
1129 * gyroscope virtual frames and updates in the data structure.
1131 * @param[out] sens : Sensor data structure
1132 * @param[in, out] idx : Index of FIFO from where the data is to retrieved.
1133 * @param[in] fifo : Structure instance of bmi2_fifo_frame.
1138 static void unpack_virt_sensor_time(struct bmi2_sens_axes_data
*sens
, uint16_t *idx
,
1139 const struct bmi2_fifo_frame
*fifo
);
1142 * @brief This internal API gets sensor time from the auxiliary virtual
1143 * frames and updates in the data structure.
1145 * @param[out] aux : Auxiliary sensor data structure
1146 * @param[in, out] idx : Index of FIFO from where the data is to retrieved.
1147 * @param[in] fifo : Structure instance of bmi2_fifo_frame.
1152 static void unpack_virt_aux_sensor_time(struct bmi2_aux_fifo_data
*aux
,
1154 const struct bmi2_fifo_frame
*fifo
);
1157 * @brief This internal API corrects the gyroscope cross-axis sensitivity
1158 * between the z and the x axis.
1160 * @param[in] dev : Structure instance of bmi2_dev.
1161 * @param[out] gyr_data : Structure instance of gyroscope data
1163 * @return Result of API execution status
1168 static void comp_gyro_cross_axis_sensitivity(struct bmi2_sens_axes_data
*gyr_data
, const struct bmi2_dev
*dev
);
1171 * @brief This internal API saves the configurations before performing FOC.
1173 * @param[out] acc_cfg : Accelerometer configuration value
1174 * @param[out] aps : Advance power mode value
1175 * @param[out] acc_en : Accelerometer enable value
1176 * @param[in] dev : Structure instance of bmi2_dev
1178 * @return Result of API execution status
1179 * @retval 0 -> Success
1180 * @retval < 0 -> Fail
1182 static int8_t save_accel_foc_config(struct bmi2_accel_config
*acc_cfg
,
1185 struct bmi2_dev
*dev
);
1188 * @brief This internal API performs Fast Offset Compensation for accelerometer.
1190 * @param[in] accel_g_value : This parameter selects the accel foc
1191 * axis to be performed
1193 * input format is {x, y, z, sign}. '1' to enable. '0' to disable
1195 * eg to choose x axis {1, 0, 0, 0}
1196 * eg to choose -x axis {1, 0, 0, 1}
1198 * @param[in] acc_cfg : Accelerometer configuration value
1199 * @param[in] dev : Structure instance of bmi2_dev.
1201 * @return Result of API execution status
1202 * @retval 0 -> Success
1203 * @retval < 0 -> Fail
1205 static int8_t perform_accel_foc(const struct bmi2_accel_foc_g_value
*accel_g_value
,
1206 const struct bmi2_accel_config
*acc_cfg
,
1207 struct bmi2_dev
*dev
);
1210 * @brief This internal sets configurations for performing accelerometer FOC.
1212 * @param[in] dev : Structure instance of bmi2_dev
1214 * @return Result of API execution status
1215 * @retval 0 -> Success
1216 * @retval < 0 -> Fail
1218 static int8_t set_accel_foc_config(struct bmi2_dev
*dev
);
1221 * @brief This internal API enables/disables the offset compensation for
1222 * filtered and un-filtered accelerometer data.
1224 * @param[in] offset_en : enables/disables offset compensation.
1225 * @param[in] dev : Structure instance of bmi2_dev
1227 * @return Result of API execution status
1228 * @retval 0 -> Success
1229 * @retval < 0 -> Fail
1231 static int8_t set_accel_offset_comp(uint8_t offset_en
, struct bmi2_dev
*dev
);
1234 * @brief This internal API converts the range value into accelerometer
1235 * corresponding integer value.
1237 * @param[in] range_in : Input range value.
1238 * @param[out] range_out : Stores the integer value of range.
1243 static void map_accel_range(uint8_t range_in
, uint8_t *range_out
);
1246 * @brief This internal API compensate the accelerometer data against gravity.
1248 * @param[in] lsb_per_g : LSB value pre 1g.
1249 * @param[in] g_val : G reference value of all axis.
1250 * @param[in] data : Accelerometer data
1251 * @param[out] comp_data : Stores the data that is compensated by taking the
1252 * difference in accelerometer data and lsb_per_g
1258 static void comp_for_gravity(uint16_t lsb_per_g
,
1259 const struct bmi2_accel_foc_g_value
*g_val
,
1260 const struct bmi2_sens_axes_data
*data
,
1261 struct bmi2_offset_delta
*comp_data
);
1264 * @brief This internal API scales the compensated accelerometer data according
1265 * to the offset register resolution.
1267 * @param[in] range : G-range of the accelerometer.
1268 * @param[out] comp_data : Data that is compensated by taking the
1269 * difference in accelerometer data and lsb_per_g
1271 * @param[out] data : Stores offset data
1276 static void scale_accel_offset(uint8_t range
, const struct bmi2_offset_delta
*comp_data
,
1277 struct bmi2_accel_offset
*data
);
1280 * @brief This internal API finds the bit position of 3.9mg according to given
1281 * range and resolution.
1283 * @param[in] range : G-range of the accelerometer.
1285 * @return Result of API execution status
1286 * @retval Bit position of 3.9mg
1288 static int8_t get_bit_pos_3_9mg(uint8_t range
);
1291 * @brief This internal API inverts the accelerometer offset data.
1293 * @param[out] offset_data : Stores the inverted offset data
1298 static void invert_accel_offset(struct bmi2_accel_offset
*offset_data
);
1301 * @brief This internal API writes the offset data in the offset compensation
1304 * @param[in] offset : offset data
1305 * @param[in] dev : Structure instance of bmi2_dev
1307 * @return Result of API execution status
1308 * @retval 0 -> Success
1309 * @retval < 0 -> Fail
1311 static int8_t write_accel_offset(const struct bmi2_accel_offset
*offset
, struct bmi2_dev
*dev
);
1314 * @brief This internal API restores the configurations saved before performing
1315 * accelerometer FOC.
1317 * @param[in] acc_cfg : Accelerometer configuration value
1318 * @param[in] acc_en : Accelerometer enable value
1319 * @param[in] aps : Advance power mode value
1320 * @param[in] dev : Structure instance of bmi2_dev
1322 * @return Result of API execution status
1323 * @retval 0 -> Success
1324 * @retval < 0 -> Fail
1326 static int8_t restore_accel_foc_config(struct bmi2_accel_config
*acc_cfg
,
1329 struct bmi2_dev
*dev
);
1332 * @brief This internal API saves the configurations before performing gyroscope
1335 * @param[out] gyr_cfg : Gyroscope configuration value
1336 * @param[out] gyr_en : Gyroscope enable value
1337 * @param[out] aps : Advance power mode value
1338 * @param[in] dev : Structure instance of bmi2_dev
1340 * @return Result of API execution status
1341 * @retval 0 -> Success
1342 * @retval < 0 -> Fail
1344 static int8_t save_gyro_config(struct bmi2_gyro_config
*gyr_cfg
, uint8_t *aps
, uint8_t *gyr_en
, struct bmi2_dev
*dev
);
1347 * @brief This internal sets configurations for performing gyroscope FOC.
1349 * @param[in] dev : Structure instance of bmi2_dev
1351 * @return Result of API execution status
1352 * @retval 0 -> Success
1353 * @retval < 0 -> Fail
1355 static int8_t set_gyro_foc_config(struct bmi2_dev
*dev
);
1358 * @brief This internal API inverts the gyroscope offset data.
1360 * @param[out] offset_data : Stores the inverted offset data
1365 static void invert_gyro_offset(struct bmi2_sens_axes_data
*offset_data
);
1368 * @brief This internal API restores the gyroscope configurations saved
1369 * before performing FOC.
1371 * @param[in] gyr_cfg : Gyroscope configuration value
1372 * @param[in] gyr_en : Gyroscope enable value
1373 * @param[in] aps : Advance power mode value
1374 * @param[in] dev : Structure instance of bmi2_dev
1376 * @return Result of API execution status
1377 * @retval 0 -> Success
1378 * @retval < 0 -> Fail
1380 static int8_t restore_gyro_config(struct bmi2_gyro_config
*gyr_cfg
, uint8_t aps
, uint8_t gyr_en
, struct bmi2_dev
*dev
);
1383 * @brief This internal API saturates the gyroscope data value before writing to
1384 * to 10 bit offset register.
1386 * @param[in, out] gyr_off : Gyroscope data to be stored in offset register
1391 static void saturate_gyro_data(struct bmi2_sens_axes_data
*gyr_off
);
1394 * @brief This internal API reads the gyroscope data for x, y and z axis from
1397 * @param[out] gyro : Buffer to store the gyroscope value.
1398 * @param[in] dev : Structure instance of bmi2_dev.
1400 * @return Result of API execution status
1401 * @retval 0 -> Success
1402 * @retval < 0 -> Fail
1404 static int8_t read_gyro_xyz(struct bmi2_sens_axes_data
*gyro
, struct bmi2_dev
*dev
);
1407 * @brief This internal API is used to check the boundary conditions.
1409 * @param[in] dev : Structure instance of bmi2_dev.
1410 * @param[in,out] val : Pointer to the value to be validated.
1411 * @param[in] min : minimum value.
1412 * @param[in] max : maximum value.
1414 * @return Result of API execution status
1415 * @retval 0 -> Success
1416 * @retval < 0 -> Fail
1418 static int8_t check_boundary_val(uint8_t *val
, uint8_t min
, uint8_t max
, struct bmi2_dev
*dev
);
1421 * @brief This internal API is used to validate the device pointer for
1424 * @param[in] dev : Structure instance of bmi2_dev.
1426 * @return Result of API execution status
1427 * @retval 0 -> Success
1428 * @retval < 0 -> Fail
1430 static int8_t null_ptr_check(const struct bmi2_dev
*dev
);
1433 * @brief This updates the result for CRT or gyro self-test.
1435 * @param[in] dev : Structure instance of bmi2_dev.
1437 * @return Result of API execution status
1438 * @retval 0 -> Success
1439 * @retval < 0 -> Fail
1441 static int8_t crt_gyro_st_update_result(struct bmi2_dev
*dev
);
1444 * @brief This function is to get the st_status status.
1446 * @param[in] *st_status: gets the crt running status
1447 * @param[in] dev : Structure instance of bmi2_dev
1449 * @return Result of API execution status
1450 * @retval 0 -> Success
1451 * @retval < 0 -> Fail
1453 static int8_t get_st_running(uint8_t *st_status
, struct bmi2_dev
*dev
);
1456 * @brief This function is to set crt bit to running.
1459 * @param[in] dev : Structure instance of bmi2_dev
1461 * @return Result of API execution status
1462 * @retval 0 -> Success
1463 * @retval < 0 -> Fail
1465 static int8_t set_st_running(uint8_t st_status
, struct bmi2_dev
*dev
);
1468 * @brief This function is to make the initial changes for CRT.
1469 * Disable the gyro, OIS, aps
1470 * Note: For the purpose of preparing CRT Gyro, OIS and APS are disabled
1472 * @param[in] dev : Structure instance of bmi2_dev
1474 * @return Result of API execution status
1475 * @retval 0 -> Success
1476 * @retval < 0 -> Fail
1478 static int8_t crt_prepare_setup(struct bmi2_dev
*dev
);
1480 static int8_t do_gtrigger_test(uint8_t gyro_st_crt
, struct bmi2_dev
*dev
);
1483 * @brief This function is to get the rdy for dl bit status
1484 * this will toggle from 0 to 1 and visevers according to the
1487 * @param[in] *rdy_for_dl: gets the rdy_for_dl status
1488 * @param[in] dev : Structure instance of bmi2_dev
1490 * @return Result of API execution status
1491 * @retval 0 -> Success
1492 * @retval < 0 -> Fail
1494 static int8_t get_rdy_for_dl(uint8_t *rdy_for_dl
, struct bmi2_dev
*dev
);
1497 * @brief This function is to write the config file in the given location for crt.
1498 * which inter checks the status of the rdy_for_dl bit and also the crt running, and
1499 * wirtes the given size.
1501 * @param[in] write_len: length of the words to be written
1502 * @param[in] config_file_size: length of the words to be written
1503 * @param[in] start_index: provide the start index from where config file has to written
1504 * @param[in] dev : Structure instance of bmi2_dev
1506 * @return Result of API execution status
1507 * @retval 0 -> Success
1508 * @retval < 0 -> Fail
1510 static int8_t write_crt_config_file(uint16_t write_len
,
1511 uint16_t config_file_size
,
1512 uint16_t start_index
,
1513 struct bmi2_dev
*dev
);
1516 * @brief This function is to check for rdy_for_dl bit to toggle for CRT process
1518 * @param[in] retry_complete: wait for given time to toggle
1519 * @param[in] download_ready: get the status for rdy_for_dl
1520 * @param[in] dev : Structure instance of bmi2_dev
1522 * @return Result of API execution status
1523 * @retval 0 -> Success
1524 * @retval < 0 -> Fail
1526 static int8_t wait_rdy_for_dl_toggle(uint8_t retry_complete
, uint8_t download_ready
, struct bmi2_dev
*dev
);
1529 * @brief This function is to wait till the CRT or gyro self-test process is completed
1531 * @param[in] retry_complete: wait for given time to complete the crt process
1532 * @param[in] dev : Structure instance of bmi2_dev
1534 * @return Result of API execution status
1535 * @retval 0 -> Success
1536 * @retval < 0 -> Fail
1538 static int8_t wait_st_running(uint8_t retry_complete
, struct bmi2_dev
*dev
);
1541 * @brief This function is to complete the crt process if max burst length is not zero
1542 * this checks for the crt status and rdy_for_dl bit to toggle
1544 * @param[in] last_byte_flag: to provide the last toggled state
1545 * @param[in] dev : Structure instance of bmi2_dev
1547 * @return Result of API execution status
1548 * @retval 0 -> Success
1549 * @retval < 0 -> Fail
1551 static int8_t process_crt_download(uint8_t last_byte_flag
, struct bmi2_dev
*dev
);
1554 * @brief This api is used to enable the gyro self-test or crt.
1556 * @param[in] dev : Structure instance of bmi2_dev.
1558 * @return Result of API execution status
1559 * @retval 0 -> Success
1560 * @retval < 0 -> Fail
1562 static int8_t select_self_test(uint8_t gyro_st_crt
, struct bmi2_dev
*dev
);
1565 * @brief This api is used to enable/disable abort.
1567 * @param[in] abort_enable : variable to enable the abort feature.
1568 * @param[in] dev : Structure instance of bmi2_dev.
1570 * @return Result of API execution status
1571 * @retval 0 -> Success
1572 * @retval < 0 -> Fail
1574 static int8_t abort_bmi2(uint8_t abort_enable
, struct bmi2_dev
*dev
);
1577 * @brief This api is use to wait till gyro self-test is completed and update the status of gyro
1580 * @param[in] dev : Structure instance of bmi2_dev.
1582 * @return Result of API execution status
1583 * @retval 0 -> Success
1584 * @retval < 0 -> Fail
1586 static int8_t gyro_self_test_completed(struct bmi2_gyro_self_test_status
*gyro_st_result
, struct bmi2_dev
*dev
);
1589 * @brief This api is used to trigger the preparation for system for NVM programming.
1591 * @param[out] nvm_prep : pointer to variable to store the status of nvm_prep_prog.
1592 * @param[in] dev : Structure instance of bmi2_dev.
1594 * @return Result of API execution status
1595 * @retval 0 -> Success
1596 * @retval < 0 -> Fail
1598 static int8_t set_nvm_prep_prog(uint8_t nvm_prep
, struct bmi2_dev
*dev
);
1601 * @brief This api validates accel foc position as per the range
1603 * @param[in] sens_list : Sensor type
1604 * @param[in] accel_g_axis : accel axis to foc. NA for gyro foc
1605 * @param[in] avg_foc_data : average value of sensor sample datas
1606 * @param[in] dev : Structure instance of bmi2_dev.
1608 * @return Result of API execution status
1609 * @retval 0 -> Success
1610 * @retval < 0 -> Fail
1612 static int8_t validate_foc_position(uint8_t sens_list
,
1613 const struct bmi2_accel_foc_g_value
*accel_g_axis
,
1614 struct bmi2_sens_axes_data avg_foc_data
,
1615 struct bmi2_dev
*dev
);
1618 * @brief This api validates accel foc axis given as input
1620 * @param[in] avg_foc_data : average value of sensor sample datas
1621 * @param[in] dev : Structure instance of bmi2_dev.
1623 * @return Result of API execution status
1624 * @retval 0 -> Success
1625 * @retval < 0 -> Fail
1627 static int8_t validate_foc_accel_axis(int16_t avg_foc_data
, struct bmi2_dev
*dev
);
1630 * @brief This api is used to verify the right position of the sensor before doing accel foc
1632 * @param[in] dev : Structure instance of bmi2_dev.
1633 * @param[in] sens_list: Sensor type
1634 * @param[in] accel_g_axis: Accel Foc axis and sign input
1636 * @return Result of API execution status
1637 * @retval 0 -> Success
1638 * @retval < 0 -> Fail
1640 static int8_t verify_foc_position(uint8_t sens_list
,
1641 const struct bmi2_accel_foc_g_value
*accel_g_axis
,
1642 struct bmi2_dev
*dev
);
1645 * @brief This API reads and provides average for 128 samples of sensor data for foc operation
1648 * @param[in] sens_list : Sensor type.
1649 * @param[in] bmi2_dev: Structure instance of bmi2_dev.
1650 * @param[in] temp_foc_data: to store data samples
1652 * @return Result of API execution status
1653 * @retval 0 -> Success
1654 * @retval < 0 -> Fail
1656 static int8_t get_average_of_sensor_data(uint8_t sens_list
,
1657 struct bmi2_foc_temp_value
*temp_foc_data
,
1658 struct bmi2_dev
*dev
);
1661 * @brief This internal api gets major and minor version for config file
1663 * @param[out] config_major : Pointer to store the major version
1664 * @param[out] config_minor : Pointer to store the minor version
1665 * @param[in] dev : Structure instance of bmi2_dev
1667 * @return Result of API execution status
1668 * @retval 0 -> Success
1669 * @retval < 0 -> Fail
1671 static int8_t extract_config_file(uint8_t *config_major
, uint8_t *config_minor
, struct bmi2_dev
*dev
);
1674 * @brief This internal API is used to map the interrupts to the sensor.
1676 * @param[in] map_int : Structure instance of bmi2_map_int.
1677 * @param[in] type : Type of feature or sensor.
1678 * @param[in] dev : Structure instance of bmi2_dev.
1683 static void extract_feat_int_map(struct bmi2_map_int
*map_int
, uint8_t type
, const struct bmi2_dev
*dev
);
1686 * @brief This internal API selects the sensors/features to be enabled or
1689 * @param[in] sens_list : Pointer to select the sensor.
1690 * @param[in] n_sens : Number of sensors selected.
1691 * @param[out] sensor_sel : Gets the selected sensor.
1693 * @return Result of API execution status
1694 * @retval 0 -> Success
1695 * @retval < 0 -> Fail
1697 static int8_t select_sensor(const uint8_t *sens_list
, uint8_t n_sens
, uint64_t *sensor_sel
);
1700 * @brief This internal API enables the selected sensor/features.
1702 * @param[in] sensor_sel : Selects the desired sensor.
1703 * @param[in, out] dev : Structure instance of bmi2_dev.
1705 * @return Result of API execution status
1706 * @retval 0 -> Success
1707 * @retval < 0 -> Fail
1709 static int8_t sensor_enable(uint64_t sensor_sel
, struct bmi2_dev
*dev
);
1712 * @brief This internal API disables the selected sensor/features.
1714 * @param[in] sensor_sel : Selects the desired sensor.
1715 * @param[in, out] dev : Structure instance of bmi2_dev.
1717 * @return Result of API execution status
1718 * @retval 0 -> Success
1719 * @retval < 0 -> Fail
1721 static int8_t sensor_disable(uint64_t sensor_sel
, struct bmi2_dev
*dev
);
1723 /******************************************************************************/
1724 /*! @name User Interface Definitions */
1725 /******************************************************************************/
1728 * @brief This API is the entry point for bmi2 sensor. It selects between
1729 * I2C/SPI interface, based on user selection. It reads and validates the
1730 * chip-id of the sensor.
1732 int8_t bmi2_sec_init(struct bmi2_dev
*dev
)
1734 /* Variable to define error */
1737 /* Variable to assign chip id */
1738 uint8_t chip_id
= 0;
1740 /* Structure to define the default values for axes re-mapping */
1741 struct bmi2_axes_remap axes_remap
= {
1742 .x_axis
= BMI2_MAP_X_AXIS
, .x_axis_sign
= BMI2_POS_SIGN
, .y_axis
= BMI2_MAP_Y_AXIS
,
1743 .y_axis_sign
= BMI2_POS_SIGN
, .z_axis
= BMI2_MAP_Z_AXIS
, .z_axis_sign
= BMI2_POS_SIGN
1746 /* Null-pointer check */
1747 rslt
= null_ptr_check(dev
);
1748 if (rslt
== BMI2_OK
)
1750 /* Perform soft-reset to bring all register values to their
1753 rslt
= bmi2_soft_reset(dev
);
1755 if (rslt
== BMI2_OK
)
1757 /* Read chip-id of the BMI2 sensor */
1758 rslt
= bmi2_get_regs(BMI2_CHIP_ID_ADDR
, &chip_id
, 1, dev
);
1760 if (rslt
== BMI2_OK
)
1762 /* Validate chip-id */
1763 if (chip_id
== dev
->chip_id
)
1765 /* Assign resolution to the structure */
1766 dev
->resolution
= 16;
1768 /* Set manual enable flag */
1769 dev
->aux_man_en
= 1;
1771 /* Set the default values for axis
1772 * re-mapping in the device structure
1774 dev
->remap
= axes_remap
;
1778 /* Storing the chip-id value read from
1779 * the register to identify the sensor
1781 dev
->chip_id
= chip_id
;
1782 rslt
= BMI2_E_DEV_NOT_FOUND
;
1792 * @brief This API reads the data from the given register address of bmi2
1795 * @note For most of the registers auto address increment applies, with the
1796 * exception of a few special registers, which trap the address. For e.g.,
1797 * Register address - 0x26, 0x5E.
1799 int8_t bmi2_get_regs(uint8_t reg_addr
, uint8_t *data
, uint16_t len
, struct bmi2_dev
*dev
)
1801 /* Variable to define error */
1804 /* Variable to define loop */
1807 /* Null-pointer check */
1808 rslt
= null_ptr_check(dev
);
1809 if ((rslt
== BMI2_OK
) && (data
!= NULL
))
1811 /* Variable to define temporary length */
1812 uint16_t temp_len
= len
+ dev
->dummy_byte
;
1814 /* Variable to define temporary buffer */
1815 uint8_t temp_buf
[temp_len
];
1817 /* Configuring reg_addr for SPI Interface */
1818 if (dev
->intf
== BMI2_SPI_INTF
)
1820 reg_addr
= (reg_addr
| BMI2_SPI_RD_MASK
);
1823 dev
->intf_rslt
= dev
->read(reg_addr
, temp_buf
, temp_len
, dev
->intf_ptr
);
1825 if (dev
->aps_status
== BMI2_ENABLE
)
1827 dev
->delay_us(450, dev
->intf_ptr
);
1831 dev
->delay_us(2, dev
->intf_ptr
);
1834 if (dev
->intf_rslt
== BMI2_INTF_RET_SUCCESS
)
1836 /* Read the data from the position next to dummy byte */
1839 data
[index
] = temp_buf
[index
+ dev
->dummy_byte
];
1845 rslt
= BMI2_E_COM_FAIL
;
1850 rslt
= BMI2_E_NULL_PTR
;
1857 * @brief This API writes data to the given register address of bmi2 sensor.
1859 int8_t bmi2_set_regs(uint8_t reg_addr
, const uint8_t *data
, uint16_t len
, struct bmi2_dev
*dev
)
1861 /* Variable to define error */
1864 /* Null-pointer check */
1865 rslt
= null_ptr_check(dev
);
1866 if ((rslt
== BMI2_OK
) && (data
!= NULL
))
1868 /* Configuring reg_addr for SPI Interface */
1869 if (dev
->intf
== BMI2_SPI_INTF
)
1871 reg_addr
= (reg_addr
& BMI2_SPI_WR_MASK
);
1874 dev
->intf_rslt
= dev
->write(reg_addr
, data
, len
, dev
->intf_ptr
);
1876 /* Delay for Low power mode of the sensor is 450 us */
1877 if (dev
->aps_status
== BMI2_ENABLE
)
1879 dev
->delay_us(450, dev
->intf_ptr
);
1881 /* Delay for Normal mode of the sensor is 2 us */
1884 dev
->delay_us(2, dev
->intf_ptr
);
1887 /* updating the advance power saver flag */
1888 if (reg_addr
== BMI2_PWR_CONF_ADDR
)
1890 if (*data
& BMI2_ADV_POW_EN_MASK
)
1892 dev
->aps_status
= BMI2_ENABLE
;
1896 dev
->aps_status
= BMI2_DISABLE
;
1900 if (dev
->intf_rslt
!= BMI2_INTF_RET_SUCCESS
)
1902 rslt
= BMI2_E_COM_FAIL
;
1907 rslt
= BMI2_E_NULL_PTR
;
1914 * @brief This API resets bmi2 sensor. All registers are overwritten with
1915 * their default values.
1917 int8_t bmi2_soft_reset(struct bmi2_dev
*dev
)
1919 /* Variable to define error */
1922 /* Variable to define soft reset value */
1923 uint8_t data
= BMI2_SOFT_RESET_CMD
;
1925 /* Variable to read the dummy byte */
1926 uint8_t dummy_read
= 0;
1928 /* Null-pointer check */
1929 rslt
= null_ptr_check(dev
);
1930 if (rslt
== BMI2_OK
)
1932 /* Reset bmi2 device */
1933 rslt
= bmi2_set_regs(BMI2_CMD_REG_ADDR
, &data
, 1, dev
);
1934 dev
->delay_us(2000, dev
->intf_ptr
);
1936 /* set APS flag as after soft reset the sensor is on advance power save mode */
1937 dev
->aps_status
= BMI2_ENABLE
;
1939 /* Performing a dummy read to bring interface back to SPI from
1940 * I2C after a soft-reset
1942 if ((rslt
== BMI2_OK
) && (dev
->intf
== BMI2_SPI_INTF
))
1944 rslt
= bmi2_get_regs(BMI2_CHIP_ID_ADDR
, &dummy_read
, 1, dev
);
1947 if (rslt
== BMI2_OK
)
1949 /* Write the configuration file */
1950 rslt
= bmi2_write_config_file(dev
);
1953 /* Reset the sensor status flag in the device structure */
1954 if (rslt
== BMI2_OK
)
1956 dev
->sens_en_stat
= 0;
1964 * @brief This API is used to get the config file major and minor version information.
1966 int8_t bmi2_get_config_file_version(uint8_t *config_major
, uint8_t *config_minor
, struct bmi2_dev
*dev
)
1968 /* Variable to define error */
1971 /* NULL pointer check */
1972 rslt
= null_ptr_check(dev
);
1973 if ((rslt
== BMI2_OK
) && (config_major
!= NULL
) && (config_minor
!= NULL
))
1975 /* Extract the config file identification from the dmr page and get the major and minor version */
1976 rslt
= extract_config_file(config_major
, config_minor
, dev
);
1980 rslt
= BMI2_E_NULL_PTR
;
1987 * @brief This API enables/disables the advance power save mode in the sensor.
1989 int8_t bmi2_set_adv_power_save(uint8_t enable
, struct bmi2_dev
*dev
)
1991 /* Variable to define error */
1994 /* Variable to store data */
1995 uint8_t reg_data
= 0;
1997 /* Null-pointer check */
1998 rslt
= null_ptr_check(dev
);
1999 if (rslt
== BMI2_OK
)
2001 rslt
= bmi2_get_regs(BMI2_PWR_CONF_ADDR
, ®_data
, 1, dev
);
2002 if (rslt
== BMI2_OK
)
2004 reg_data
= BMI2_SET_BIT_POS0(reg_data
, BMI2_ADV_POW_EN
, enable
);
2005 rslt
= bmi2_set_regs(BMI2_PWR_CONF_ADDR
, ®_data
, 1, dev
);
2007 if (rslt
!= BMI2_OK
)
2009 /* Return error if enable/disable APS fails */
2010 rslt
= BMI2_E_SET_APS_FAIL
;
2013 if (rslt
== BMI2_OK
)
2015 dev
->aps_status
= BMI2_GET_BIT_POS0(reg_data
, BMI2_ADV_POW_EN
);
2024 * @brief This API gets the status of advance power save mode in the sensor.
2026 int8_t bmi2_get_adv_power_save(uint8_t *aps_status
, struct bmi2_dev
*dev
)
2028 /* Variable to define error */
2031 /* Variable to store data */
2032 uint8_t reg_data
= 0;
2034 /* Null-pointer check */
2035 rslt
= null_ptr_check(dev
);
2036 if ((rslt
== BMI2_OK
) && (aps_status
!= NULL
))
2038 rslt
= bmi2_get_regs(BMI2_PWR_CONF_ADDR
, ®_data
, 1, dev
);
2039 if (rslt
== BMI2_OK
)
2041 *aps_status
= BMI2_GET_BIT_POS0(reg_data
, BMI2_ADV_POW_EN
);
2042 dev
->aps_status
= *aps_status
;
2047 rslt
= BMI2_E_NULL_PTR
;
2054 * @brief This API loads the configuration file into the bmi2 sensor.
2056 int8_t bmi2_write_config_file(struct bmi2_dev
*dev
)
2058 /* Variable to define error */
2061 /* Variable to know the load status */
2062 uint8_t load_status
= 0;
2064 /* Null-pointer check */
2065 rslt
= null_ptr_check(dev
);
2066 if ((rslt
== BMI2_OK
) && (dev
->config_size
!= 0))
2068 /* Bytes written are multiples of 2 */
2069 if ((dev
->read_write_len
% 2) != 0)
2071 dev
->read_write_len
= dev
->read_write_len
- 1;
2074 if (dev
->read_write_len
< 2)
2076 dev
->read_write_len
= 2;
2079 /* Write the configuration file */
2080 rslt
= write_config_file(dev
);
2081 if (rslt
== BMI2_OK
)
2083 /* Check the configuration load status */
2084 rslt
= bmi2_get_internal_status(&load_status
, dev
);
2086 /* Return error if loading not successful */
2087 if ((rslt
== BMI2_OK
) && (!(load_status
& BMI2_CONFIG_LOAD_SUCCESS
)))
2089 rslt
= BMI2_E_CONFIG_LOAD
;
2095 rslt
= BMI2_E_NULL_PTR
;
2102 * @brief This API sets:
2103 * 1) The input output configuration of the selected interrupt pin:
2105 * 2) The interrupt mode: permanently latched or non-latched.
2107 int8_t bmi2_set_int_pin_config(const struct bmi2_int_pin_config
*int_cfg
, struct bmi2_dev
*dev
)
2109 /* Variable to define error */
2112 /* Variable to define data array */
2113 uint8_t data_array
[3] = { 0 };
2115 /* Variable to store register data */
2116 uint8_t reg_data
= 0;
2118 /* Variable to define type of interrupt pin */
2119 uint8_t int_pin
= 0;
2121 /* Null-pointer check */
2122 rslt
= null_ptr_check(dev
);
2123 if ((rslt
== BMI2_OK
) && (int_cfg
!= NULL
))
2125 /* Copy the pin type to a local variable */
2126 int_pin
= int_cfg
->pin_type
;
2127 if ((int_pin
> BMI2_INT_NONE
) && (int_pin
< BMI2_INT_PIN_MAX
))
2129 /* Get the previous configuration data */
2130 rslt
= bmi2_get_regs(BMI2_INT1_IO_CTRL_ADDR
, data_array
, 3, dev
);
2131 if (rslt
== BMI2_OK
)
2133 /* Set interrupt pin 1 configuration */
2134 if ((int_pin
== BMI2_INT1
) || (int_pin
== BMI2_INT_BOTH
))
2136 /* Configure active low or high */
2137 reg_data
= BMI2_SET_BITS(data_array
[0], BMI2_INT_LEVEL
, int_cfg
->pin_cfg
[0].lvl
);
2139 /* Configure push-pull or open drain */
2140 reg_data
= BMI2_SET_BITS(reg_data
, BMI2_INT_OPEN_DRAIN
, int_cfg
->pin_cfg
[0].od
);
2142 /* Configure output enable */
2143 reg_data
= BMI2_SET_BITS(reg_data
, BMI2_INT_OUTPUT_EN
, int_cfg
->pin_cfg
[0].output_en
);
2145 /* Configure input enable */
2146 reg_data
= BMI2_SET_BITS(reg_data
, BMI2_INT_INPUT_EN
, int_cfg
->pin_cfg
[0].input_en
);
2148 /* Copy the data to be written in the respective array */
2149 data_array
[0] = reg_data
;
2152 /* Set interrupt pin 2 configuration */
2153 if ((int_pin
== BMI2_INT2
) || (int_pin
== BMI2_INT_BOTH
))
2155 /* Configure active low or high */
2156 reg_data
= BMI2_SET_BITS(data_array
[1], BMI2_INT_LEVEL
, int_cfg
->pin_cfg
[1].lvl
);
2158 /* Configure push-pull or open drain */
2159 reg_data
= BMI2_SET_BITS(reg_data
, BMI2_INT_OPEN_DRAIN
, int_cfg
->pin_cfg
[1].od
);
2161 /* Configure output enable */
2162 reg_data
= BMI2_SET_BITS(reg_data
, BMI2_INT_OUTPUT_EN
, int_cfg
->pin_cfg
[1].output_en
);
2164 /* Configure input enable */
2165 reg_data
= BMI2_SET_BITS(reg_data
, BMI2_INT_INPUT_EN
, int_cfg
->pin_cfg
[1].input_en
);
2167 /* Copy the data to be written in the respective array */
2168 data_array
[1] = reg_data
;
2171 /* Configure the interrupt mode */
2172 data_array
[2] = BMI2_SET_BIT_POS0(data_array
[2], BMI2_INT_LATCH
, int_cfg
->int_latch
);
2174 /* Set the configurations simultaneously as
2175 * INT1_IO_CTRL, INT2_IO_CTRL, and INT_LATCH lie
2176 * in consecutive addresses
2178 rslt
= bmi2_set_regs(BMI2_INT1_IO_CTRL_ADDR
, data_array
, 3, dev
);
2183 rslt
= BMI2_E_INVALID_INT_PIN
;
2188 rslt
= BMI2_E_NULL_PTR
;
2195 * @brief This API gets:
2196 * 1) The input output configuration of the selected interrupt pin:
2198 * 2) The interrupt mode: permanently latched or non-latched.
2200 int8_t bmi2_get_int_pin_config(struct bmi2_int_pin_config
*int_cfg
, struct bmi2_dev
*dev
)
2202 /* Variable to define error */
2205 /* Variable to define data array */
2206 uint8_t data_array
[3] = { 0 };
2208 /* Variable to define type of interrupt pin */
2209 uint8_t int_pin
= 0;
2211 /* Null-pointer check */
2212 rslt
= null_ptr_check(dev
);
2213 if ((rslt
== BMI2_OK
) && (int_cfg
!= NULL
))
2215 /* Copy the pin type to a local variable */
2216 int_pin
= int_cfg
->pin_type
;
2218 /* Get the previous configuration data */
2219 rslt
= bmi2_get_regs(BMI2_INT1_IO_CTRL_ADDR
, data_array
, 3, dev
);
2220 if (rslt
== BMI2_OK
)
2222 /* Get interrupt pin 1 configuration */
2223 if ((int_pin
== BMI2_INT1
) || (int_pin
== BMI2_INT_BOTH
))
2225 /* Get active low or high */
2226 int_cfg
->pin_cfg
[0].lvl
= BMI2_GET_BITS(data_array
[0], BMI2_INT_LEVEL
);
2228 /* Get push-pull or open drain */
2229 int_cfg
->pin_cfg
[0].od
= BMI2_GET_BITS(data_array
[0], BMI2_INT_OPEN_DRAIN
);
2231 /* Get output enable */
2232 int_cfg
->pin_cfg
[0].output_en
= BMI2_GET_BITS(data_array
[0], BMI2_INT_OUTPUT_EN
);
2234 /* Get input enable */
2235 int_cfg
->pin_cfg
[0].input_en
= BMI2_GET_BITS(data_array
[0], BMI2_INT_INPUT_EN
);
2238 /* Get interrupt pin 2 configuration */
2239 if ((int_pin
== BMI2_INT2
) || (int_pin
== BMI2_INT_BOTH
))
2241 /* Get active low or high */
2242 int_cfg
->pin_cfg
[1].lvl
= BMI2_GET_BITS(data_array
[1], BMI2_INT_LEVEL
);
2244 /* Get push-pull or open drain */
2245 int_cfg
->pin_cfg
[1].od
= BMI2_GET_BITS(data_array
[1], BMI2_INT_OPEN_DRAIN
);
2247 /* Get output enable */
2248 int_cfg
->pin_cfg
[1].output_en
= BMI2_GET_BITS(data_array
[1], BMI2_INT_OUTPUT_EN
);
2250 /* Get input enable */
2251 int_cfg
->pin_cfg
[1].input_en
= BMI2_GET_BITS(data_array
[1], BMI2_INT_INPUT_EN
);
2254 /* Get interrupt mode */
2255 int_cfg
->int_latch
= BMI2_GET_BIT_POS0(data_array
[2], BMI2_INT_LATCH
);
2260 rslt
= BMI2_E_NULL_PTR
;
2267 * @brief This API gets the interrupt status of both feature and data
2270 int8_t bmi2_get_int_status(uint16_t *int_status
, struct bmi2_dev
*dev
)
2272 /* Variable to define error */
2275 /* Array to store data */
2276 uint8_t data_array
[2] = { 0 };
2278 /* Null-pointer check */
2279 rslt
= null_ptr_check(dev
);
2280 if ((rslt
== BMI2_OK
) && (int_status
!= NULL
))
2282 /* Get the interrupt status */
2283 rslt
= bmi2_get_regs(BMI2_INT_STATUS_0_ADDR
, data_array
, 2, dev
);
2284 if (rslt
== BMI2_OK
)
2286 *int_status
= (uint16_t) data_array
[0] | ((uint16_t) data_array
[1] << 8);
2291 rslt
= BMI2_E_NULL_PTR
;
2298 * @brief This API selects the sensors/features to be enabled.
2300 int8_t bmi2_sensor_enable(const uint8_t *sens_list
, uint8_t n_sens
, struct bmi2_dev
*dev
)
2302 /* Variable to define error */
2305 /* Variable to select sensor */
2306 uint64_t sensor_sel
= 0;
2308 /* Null-pointer check */
2309 rslt
= null_ptr_check(dev
);
2310 if ((rslt
== BMI2_OK
) && (sens_list
!= NULL
))
2312 /* Get the selected sensors */
2313 rslt
= select_sensor(sens_list
, n_sens
, &sensor_sel
);
2314 if (rslt
== BMI2_OK
)
2316 /* Enable the selected sensors */
2317 rslt
= sensor_enable(sensor_sel
, dev
);
2322 rslt
= BMI2_E_NULL_PTR
;
2329 * @brief This API selects the sensors/features to be disabled.
2331 int8_t bmi2_sensor_disable(const uint8_t *sens_list
, uint8_t n_sens
, struct bmi2_dev
*dev
)
2333 /* Variable to define error */
2336 /* Variable to select sensor */
2337 uint64_t sensor_sel
= 0;
2339 /* Null-pointer check */
2340 rslt
= null_ptr_check(dev
);
2341 if ((rslt
== BMI2_OK
) && (sens_list
!= NULL
))
2343 /* Get the selected sensors */
2344 rslt
= select_sensor(sens_list
, n_sens
, &sensor_sel
);
2345 if (rslt
== BMI2_OK
)
2347 /* Disable the selected sensors */
2348 rslt
= sensor_disable(sensor_sel
, dev
);
2353 rslt
= BMI2_E_NULL_PTR
;
2360 * @brief This API sets the sensor/feature configuration.
2362 int8_t bmi2_set_sensor_config(struct bmi2_sens_config
*sens_cfg
, uint8_t n_sens
, struct bmi2_dev
*dev
)
2364 /* Variable to define error */
2367 /* Variable to define loop */
2370 /* Variable to get the status of advance power save */
2371 uint8_t aps_stat
= 0;
2373 /* Null-pointer check */
2374 rslt
= null_ptr_check(dev
);
2375 if ((rslt
== BMI2_OK
) && (sens_cfg
!= NULL
))
2377 /* Get status of advance power save mode */
2378 aps_stat
= dev
->aps_status
;
2380 for (loop
= 0; loop
< n_sens
; loop
++)
2382 /* Disable Advance power save if enabled for auxiliary
2383 * and feature configurations
2385 if (aps_stat
== BMI2_ENABLE
)
2387 /* Disable advance power save if
2390 rslt
= bmi2_set_adv_power_save(BMI2_DISABLE
, dev
);
2393 if (rslt
== BMI2_OK
)
2395 switch (sens_cfg
[loop
].type
)
2397 /* Set accelerometer configuration */
2399 rslt
= set_accel_config(&sens_cfg
[loop
].cfg
.acc
, dev
);
2402 /* Set gyroscope configuration */
2404 rslt
= set_gyro_config(&sens_cfg
[loop
].cfg
.gyr
, dev
);
2407 /* Set auxiliary configuration */
2409 rslt
= set_aux_config(&sens_cfg
[loop
].cfg
.aux
, dev
);
2412 /* Set gyroscope user gain configuration */
2413 case BMI2_GYRO_GAIN_UPDATE
:
2414 rslt
= set_gyro_user_gain_config(&sens_cfg
[loop
].cfg
.gyro_gain_update
, dev
);
2418 rslt
= BMI2_E_INVALID_SENSOR
;
2423 /* Return error if any of the set configurations fail */
2424 if (rslt
!= BMI2_OK
)
2430 /* Enable Advance power save if disabled while configuring and
2431 * not when already disabled
2433 if ((aps_stat
== BMI2_ENABLE
) && (rslt
== BMI2_OK
))
2435 rslt
= bmi2_set_adv_power_save(BMI2_ENABLE
, dev
);
2440 rslt
= BMI2_E_NULL_PTR
;
2447 * @brief This API gets the sensor/feature configuration.
2449 int8_t bmi2_get_sensor_config(struct bmi2_sens_config
*sens_cfg
, uint8_t n_sens
, struct bmi2_dev
*dev
)
2451 /* Variable to define error */
2454 /* Variable to define loop */
2457 /* Variable to get the status of advance power save */
2458 uint8_t aps_stat
= 0;
2460 /* Null-pointer check */
2461 rslt
= null_ptr_check(dev
);
2462 if ((rslt
== BMI2_OK
) && (sens_cfg
!= NULL
))
2464 /* Get status of advance power save mode */
2465 aps_stat
= dev
->aps_status
;
2466 for (loop
= 0; loop
< n_sens
; loop
++)
2468 /* Disable Advance power save if enabled for auxiliary
2469 * and feature configurations
2471 if ((sens_cfg
[loop
].type
>= BMI2_MAIN_SENS_MAX_NUM
) || (sens_cfg
[loop
].type
== BMI2_AUX
))
2474 if (aps_stat
== BMI2_ENABLE
)
2476 /* Disable advance power save if
2479 rslt
= bmi2_set_adv_power_save(BMI2_DISABLE
, dev
);
2483 if (rslt
== BMI2_OK
)
2485 switch (sens_cfg
[loop
].type
)
2487 /* Get accelerometer configuration */
2489 rslt
= get_accel_config(&sens_cfg
[loop
].cfg
.acc
, dev
);
2492 /* Get gyroscope configuration */
2494 rslt
= get_gyro_config(&sens_cfg
[loop
].cfg
.gyr
, dev
);
2497 /* Get auxiliary configuration */
2499 rslt
= get_aux_config(&sens_cfg
[loop
].cfg
.aux
, dev
);
2502 /* Get gyroscope user gain configuration */
2503 case BMI2_GYRO_GAIN_UPDATE
:
2504 rslt
= get_gyro_gain_update_config(&sens_cfg
[loop
].cfg
.gyro_gain_update
, dev
);
2508 rslt
= BMI2_E_INVALID_SENSOR
;
2513 /* Return error if any of the get configurations fail */
2514 if (rslt
!= BMI2_OK
)
2520 /* Enable Advance power save if disabled while configuring and
2521 * not when already disabled
2523 if ((aps_stat
== BMI2_ENABLE
) && (rslt
== BMI2_OK
))
2525 rslt
= bmi2_set_adv_power_save(BMI2_ENABLE
, dev
);
2530 rslt
= BMI2_E_NULL_PTR
;
2537 * @brief This API gets the sensor/feature data for accelerometer, gyroscope,
2538 * auxiliary sensor, step counter, high-g, gyroscope user-gain update,
2539 * orientation, gyroscope cross sensitivity and error status for NVM and VFRM.
2541 int8_t bmi2_get_sensor_data(struct bmi2_sensor_data
*sensor_data
, uint8_t n_sens
, struct bmi2_dev
*dev
)
2543 /* Variable to define error */
2546 /* Variable to define loop */
2549 /* Variable to get the status of advance power save */
2550 uint8_t aps_stat
= 0;
2552 /* Null-pointer check */
2553 rslt
= null_ptr_check(dev
);
2554 if ((rslt
== BMI2_OK
) && (sensor_data
!= NULL
))
2556 /* Get status of advance power save mode */
2557 aps_stat
= dev
->aps_status
;
2558 for (loop
= 0; loop
< n_sens
; loop
++)
2560 /* Disable Advance power save if enabled for feature
2563 if (sensor_data
[loop
].type
>= BMI2_MAIN_SENS_MAX_NUM
)
2565 if (aps_stat
== BMI2_ENABLE
)
2567 /* Disable advance power save if
2570 rslt
= bmi2_set_adv_power_save(BMI2_DISABLE
, dev
);
2574 if (rslt
== BMI2_OK
)
2576 switch (sensor_data
[loop
].type
)
2580 /* Get accelerometer data */
2581 rslt
= get_accel_sensor_data(&sensor_data
[loop
].sens_data
.acc
, BMI2_ACC_X_LSB_ADDR
, dev
);
2585 /* Get gyroscope data */
2586 rslt
= get_gyro_sensor_data(&sensor_data
[loop
].sens_data
.gyr
, BMI2_GYR_X_LSB_ADDR
, dev
);
2590 /* Get auxiliary sensor data in data mode */
2591 rslt
= read_aux_data_mode(sensor_data
[loop
].sens_data
.aux_data
, dev
);
2594 case BMI2_GYRO_CROSS_SENSE
:
2596 /* Get Gyroscope cross sense value of z axis */
2597 rslt
= get_gyro_cross_sense(&sensor_data
[loop
].sens_data
.correction_factor_zx
, dev
);
2600 case BMI2_GYRO_GAIN_UPDATE
:
2602 /* Get saturation status of gyroscope user gain update */
2603 rslt
= get_gyro_gain_update_status(&sensor_data
[loop
].sens_data
.gyro_user_gain_status
, dev
);
2606 rslt
= BMI2_E_INVALID_SENSOR
;
2610 /* Return error if any of the get sensor data fails */
2611 if (rslt
!= BMI2_OK
)
2617 /* Enable Advance power save if disabled while
2618 * configuring and not when already disabled
2620 if ((aps_stat
== BMI2_ENABLE
) && (rslt
== BMI2_OK
))
2622 rslt
= bmi2_set_adv_power_save(BMI2_ENABLE
, dev
);
2628 rslt
= BMI2_E_NULL_PTR
;
2635 * @brief This API sets the FIFO configuration in the sensor.
2637 int8_t bmi2_set_fifo_config(uint16_t config
, uint8_t enable
, struct bmi2_dev
*dev
)
2640 uint8_t data
[2] = { 0 };
2641 uint8_t max_burst_len
= 0;
2643 /* Variable to store data of FIFO configuration register 0 */
2644 uint8_t fifo_config_0
= (uint8_t)(config
& BMI2_FIFO_CONFIG_0_MASK
);
2646 /* Variable to store data of FIFO configuration register 1 */
2647 uint8_t fifo_config_1
= (uint8_t)((config
& BMI2_FIFO_CONFIG_1_MASK
) >> 8);
2649 rslt
= null_ptr_check(dev
);
2650 if (rslt
== BMI2_OK
)
2652 rslt
= bmi2_get_regs(BMI2_FIFO_CONFIG_0_ADDR
, data
, BMI2_FIFO_CONFIG_LENGTH
, dev
);
2653 if (rslt
== BMI2_OK
)
2655 /* Get data to set FIFO configuration register 0 */
2656 if (fifo_config_0
> 0)
2658 if (enable
== BMI2_ENABLE
)
2660 data
[0] = data
[0] | fifo_config_0
;
2664 data
[0] = data
[0] & (~fifo_config_0
);
2668 /* Get data to set FIFO configuration register 1 */
2669 if (enable
== BMI2_ENABLE
)
2671 data
[1] = data
[1] | fifo_config_1
;
2672 if (dev
->variant_feature
& BMI2_CRT_RTOSK_ENABLE
)
2675 /* Burst length is needed for CRT
2676 * FIFO enable will reset the default values
2677 * So configure the max burst length again.
2679 rslt
= get_maxburst_len(&max_burst_len
, dev
);
2680 if (rslt
== BMI2_OK
&& max_burst_len
== 0)
2682 rslt
= set_maxburst_len(BMI2_CRT_MIN_BURST_WORD_LENGTH
, dev
);
2688 data
[1] = data
[1] & (~fifo_config_1
);
2691 /* Set the FIFO configurations */
2692 if (rslt
== BMI2_OK
)
2694 rslt
= bmi2_set_regs(BMI2_FIFO_CONFIG_0_ADDR
, data
, 2, dev
);
2703 * @brief This API reads the FIFO configuration from the sensor.
2705 int8_t bmi2_get_fifo_config(uint16_t *fifo_config
, struct bmi2_dev
*dev
)
2707 /* Variable to define error */
2710 /* Array to store data */
2711 uint8_t data
[2] = { 0 };
2713 /* Null-pointer check */
2714 rslt
= null_ptr_check(dev
);
2715 if ((rslt
== BMI2_OK
) && (fifo_config
!= NULL
))
2717 /* Get the FIFO configuration value */
2718 rslt
= bmi2_get_regs(BMI2_FIFO_CONFIG_0_ADDR
, data
, BMI2_FIFO_CONFIG_LENGTH
, dev
);
2719 if (rslt
== BMI2_OK
)
2721 (*fifo_config
) = (uint16_t)((uint16_t) data
[0] & BMI2_FIFO_CONFIG_0_MASK
);
2722 (*fifo_config
) |= (uint16_t)(((uint16_t) data
[1] << 8) & BMI2_FIFO_CONFIG_1_MASK
);
2727 rslt
= BMI2_E_NULL_PTR
;
2734 * @brief This API reads the FIFO data.
2736 int8_t bmi2_read_fifo_data(struct bmi2_fifo_frame
*fifo
, struct bmi2_dev
*dev
)
2738 /* Variable to define error */
2741 /* Array to store FIFO configuration data */
2742 uint8_t config_data
[2] = { 0 };
2744 /* Variable to define FIFO address */
2745 uint8_t addr
= BMI2_FIFO_DATA_ADDR
;
2747 /* Null-pointer check */
2748 rslt
= null_ptr_check(dev
);
2749 if ((rslt
== BMI2_OK
) && (fifo
!= NULL
))
2751 /* Clear the FIFO data structure */
2752 reset_fifo_frame_structure(fifo
, dev
);
2754 /* Read FIFO data */
2755 rslt
= bmi2_get_regs(addr
, fifo
->data
, fifo
->length
, dev
);
2757 if (rslt
== BMI2_OK
)
2760 /* Get the set FIFO frame configurations */
2761 rslt
= bmi2_get_regs(BMI2_FIFO_CONFIG_0_ADDR
, config_data
, 2, dev
);
2762 if (rslt
== BMI2_OK
)
2764 /* Get FIFO header status */
2765 fifo
->header_enable
= (uint8_t)((config_data
[1]) & (BMI2_FIFO_HEADER_EN
>> 8));
2767 /* Get sensor enable status, of which the data is to be read */
2769 (uint16_t)(((config_data
[0]) | ((uint16_t) config_data
[1] << 8)) & BMI2_FIFO_ALL_EN
);
2774 rslt
= BMI2_E_COM_FAIL
;
2779 rslt
= BMI2_E_NULL_PTR
;
2786 * @brief This API parses and extracts the accelerometer frames from FIFO data
2787 * read by the "bmi2_read_fifo_data" API and stores it in the "accel_data"
2788 * structure instance.
2790 int8_t bmi2_extract_accel(struct bmi2_sens_axes_data
*accel_data
,
2791 uint16_t *accel_length
,
2792 struct bmi2_fifo_frame
*fifo
,
2793 const struct bmi2_dev
*dev
)
2795 /* Variable to define error */
2798 /* Variable to index the bytes */
2799 uint16_t data_index
= 0;
2801 /* Variable to index accelerometer frames */
2802 uint16_t accel_index
= 0;
2804 /* Variable to store the number of bytes to be read */
2805 uint16_t data_read_length
= 0;
2807 /* Variable to define the data enable byte */
2808 uint8_t data_enable
= 0;
2810 /* Null-pointer check */
2811 rslt
= null_ptr_check(dev
);
2812 if ((rslt
== BMI2_OK
) && (accel_data
!= NULL
) && (accel_length
!= NULL
) && (fifo
!= NULL
))
2814 /* Parsing the FIFO data in header-less mode */
2815 if (fifo
->header_enable
== 0)
2818 /* Get the number of accelerometer bytes to be read */
2819 rslt
= parse_fifo_accel_len(&data_index
, &data_read_length
, accel_length
, fifo
);
2821 /* Convert word to byte since all sensor enables are in a byte */
2822 data_enable
= (uint8_t)(fifo
->data_enable
>> 8);
2823 for (; (data_index
< data_read_length
) && (rslt
!= BMI2_W_FIFO_EMPTY
);)
2825 /* Unpack frame to get the accelerometer data */
2826 rslt
= unpack_accel_frame(accel_data
, &data_index
, &accel_index
, data_enable
, fifo
, dev
);
2828 if (rslt
!= BMI2_W_FIFO_EMPTY
)
2830 /* Check for the availability of next two bytes of FIFO data */
2831 rslt
= check_empty_fifo(&data_index
, fifo
);
2835 /* Update number of accelerometer frames to be read */
2836 (*accel_length
) = accel_index
;
2838 /* Update the accelerometer byte index */
2839 fifo
->acc_byte_start_idx
= data_index
;
2843 /* Parsing the FIFO data in header mode */
2844 rslt
= extract_accel_header_mode(accel_data
, accel_length
, fifo
, dev
);
2849 rslt
= BMI2_E_NULL_PTR
;
2856 * @brief This API parses and extracts the gyroscope frames from FIFO data
2857 * read by the "bmi2_read_fifo_data" API and stores it in the "gyro_data"
2858 * structure instance.
2860 int8_t bmi2_extract_gyro(struct bmi2_sens_axes_data
*gyro_data
,
2861 uint16_t *gyro_length
,
2862 struct bmi2_fifo_frame
*fifo
,
2863 const struct bmi2_dev
*dev
)
2865 /* Variable to define error */
2868 /* Variable to index the bytes */
2869 uint16_t data_index
= 0;
2871 /* Variable to index gyroscope frames */
2872 uint16_t gyro_index
= 0;
2874 /* Variable to store the number of bytes to be read */
2875 uint16_t data_read_length
= 0;
2877 /* Variable to define the data enable byte */
2878 uint8_t data_enable
= 0;
2880 /* Null-pointer check */
2881 rslt
= null_ptr_check(dev
);
2882 if ((rslt
== BMI2_OK
) && (gyro_data
!= NULL
) && (gyro_length
!= NULL
) && (fifo
!= NULL
))
2884 /* Parsing the FIFO data in header-less mode */
2885 if (fifo
->header_enable
== 0)
2887 /* Get the number of gyro bytes to be read */
2888 rslt
= parse_fifo_gyro_len(&data_index
, &data_read_length
, gyro_length
, fifo
);
2890 /* Convert word to byte since all sensor enables are in a byte */
2891 data_enable
= (uint8_t)(fifo
->data_enable
>> 8);
2892 for (; (data_index
< data_read_length
) && (rslt
!= BMI2_W_FIFO_EMPTY
);)
2894 /* Unpack frame to get gyroscope data */
2895 rslt
= unpack_gyro_frame(gyro_data
, &data_index
, &gyro_index
, data_enable
, fifo
, dev
);
2896 if (rslt
!= BMI2_W_FIFO_EMPTY
)
2898 /* Check for the availability of next two bytes of FIFO data */
2899 rslt
= check_empty_fifo(&data_index
, fifo
);
2903 /* Update number of gyroscope frames to be read */
2904 (*gyro_length
) = gyro_index
;
2906 /* Update the gyroscope byte index */
2907 fifo
->acc_byte_start_idx
= data_index
;
2911 /* Parsing the FIFO data in header mode */
2912 rslt
= extract_gyro_header_mode(gyro_data
, gyro_length
, fifo
, dev
);
2917 rslt
= BMI2_E_NULL_PTR
;
2924 * @brief This API parses and extracts the auxiliary frames from FIFO data
2925 * read by the "bmi2_read_fifo_data" API and stores it in "aux_data" buffer.
2927 int8_t bmi2_extract_aux(struct bmi2_aux_fifo_data
*aux
,
2928 uint16_t *aux_length
,
2929 struct bmi2_fifo_frame
*fifo
,
2930 const struct bmi2_dev
*dev
)
2932 /* Variable to define error */
2935 /* Variable to index the bytes */
2936 uint16_t data_index
= 0;
2938 /* Variable to index auxiliary frames */
2939 uint16_t aux_index
= 0;
2941 /* Variable to store the number of bytes to be read */
2942 uint16_t data_read_length
= 0;
2944 /* Variable to define the data enable byte */
2945 uint8_t data_enable
= 0;
2947 /* Null-pointer check */
2948 rslt
= null_ptr_check(dev
);
2949 if ((rslt
== BMI2_OK
) && (aux
!= NULL
) && (aux_length
!= NULL
) && (fifo
!= NULL
))
2951 /* Parsing the FIFO data in header-less mode */
2952 if (fifo
->header_enable
== 0)
2954 rslt
= parse_fifo_aux_len(&data_index
, &data_read_length
, aux_length
, fifo
);
2956 /* Convert word to byte since all sensor enables are in
2959 data_enable
= (uint8_t)(fifo
->data_enable
>> 8);
2960 for (; (data_index
< data_read_length
) && (rslt
!= BMI2_W_FIFO_EMPTY
);)
2962 /* Unpack frame to get auxiliary data */
2963 rslt
= unpack_aux_frame(aux
, &data_index
, &aux_index
, data_enable
, fifo
, dev
);
2964 if (rslt
!= BMI2_W_FIFO_EMPTY
)
2966 /* Check for the availability of next
2967 * two bytes of FIFO data
2969 rslt
= check_empty_fifo(&data_index
, fifo
);
2973 /* Update number of auxiliary frames to be read */
2974 *aux_length
= aux_index
;
2976 /* Update the auxiliary byte index */
2977 fifo
->aux_byte_start_idx
= data_index
;
2981 /* Parsing the FIFO data in header mode */
2982 rslt
= extract_aux_header_mode(aux
, aux_length
, fifo
, dev
);
2987 rslt
= BMI2_E_NULL_PTR
;
2994 * @brief This API writes the available sensor specific commands to the sensor.
2996 int8_t bmi2_set_command_register(uint8_t command
, struct bmi2_dev
*dev
)
2998 /* Variable to define error */
3001 /* Null-pointer check */
3002 rslt
= null_ptr_check(dev
);
3003 if (rslt
== BMI2_OK
)
3005 /* Set the command in the command register */
3006 rslt
= bmi2_set_regs(BMI2_CMD_REG_ADDR
, &command
, 1, dev
);
3013 * @brief This API sets the FIFO self wake up functionality in the sensor.
3015 int8_t bmi2_set_fifo_self_wake_up(uint8_t fifo_self_wake_up
, struct bmi2_dev
*dev
)
3017 /* Variable to define error */
3020 /* Variable to store data */
3023 /* Null-pointer check */
3024 rslt
= null_ptr_check(dev
);
3025 if (rslt
== BMI2_OK
)
3027 /* Set FIFO self wake-up */
3028 rslt
= bmi2_get_regs(BMI2_PWR_CONF_ADDR
, &data
, 1, dev
);
3029 if (rslt
== BMI2_OK
)
3031 data
= BMI2_SET_BITS(data
, BMI2_FIFO_SELF_WAKE_UP
, fifo_self_wake_up
);
3032 rslt
= bmi2_set_regs(BMI2_PWR_CONF_ADDR
, &data
, 1, dev
);
3040 * @brief This API gets the status of FIFO self wake up functionality from
3043 int8_t bmi2_get_fifo_self_wake_up(uint8_t *fifo_self_wake_up
, struct bmi2_dev
*dev
)
3045 /* Variable to define error */
3048 /* Variable to store data */
3051 /* Null-pointer check */
3052 rslt
= null_ptr_check(dev
);
3053 if ((rslt
== BMI2_OK
) && (fifo_self_wake_up
!= NULL
))
3055 /* Get the status of FIFO self wake-up */
3056 rslt
= bmi2_get_regs(BMI2_PWR_CONF_ADDR
, &data
, 1, dev
);
3057 if (rslt
== BMI2_OK
)
3059 (*fifo_self_wake_up
) = BMI2_GET_BITS(data
, BMI2_FIFO_SELF_WAKE_UP
);
3064 rslt
= BMI2_E_NULL_PTR
;
3071 * @brief This API sets the FIFO water-mark level in the sensor.
3073 int8_t bmi2_set_fifo_wm(uint16_t fifo_wm
, struct bmi2_dev
*dev
)
3075 /* Variable to define error */
3078 /* Array to store data */
3079 uint8_t data
[2] = { 0 };
3081 /* Null-pointer check */
3082 rslt
= null_ptr_check(dev
);
3083 if (rslt
== BMI2_OK
)
3085 /* Get LSB value of FIFO water-mark */
3086 data
[0] = BMI2_GET_LSB(fifo_wm
);
3088 /* Get MSB value of FIFO water-mark */
3089 data
[1] = BMI2_GET_MSB(fifo_wm
);
3091 /* Set the FIFO water-mark level */
3092 rslt
= bmi2_set_regs(BMI2_FIFO_WTM_0_ADDR
, data
, 2, dev
);
3099 * @brief This API reads the FIFO water mark level set in the sensor.
3101 int8_t bmi2_get_fifo_wm(uint16_t *fifo_wm
, struct bmi2_dev
*dev
)
3103 /* Variable to define error */
3106 /* Array to to store data */
3107 uint8_t data
[2] = { 0 };
3109 /* Null-pointer check */
3110 rslt
= null_ptr_check(dev
);
3111 if ((rslt
== BMI2_OK
) && (fifo_wm
!= NULL
))
3113 /* Read the FIFO water mark level */
3114 rslt
= bmi2_get_regs(BMI2_FIFO_WTM_0_ADDR
, data
, BMI2_FIFO_WM_LENGTH
, dev
);
3115 if (rslt
== BMI2_OK
)
3117 (*fifo_wm
) = (uint16_t)((uint16_t) data
[1] << 8) | (data
[0]);
3122 rslt
= BMI2_E_NULL_PTR
;
3129 * @brief This API sets either filtered or un-filtered FIFO accelerometer or
3132 int8_t bmi2_set_fifo_filter_data(uint8_t sens_sel
, uint8_t fifo_filter_data
, struct bmi2_dev
*dev
)
3134 /* Variable to define error */
3137 /* Variable to store data */
3140 /* Null-pointer check */
3141 rslt
= null_ptr_check(dev
);
3142 if (rslt
== BMI2_OK
)
3148 /* Validate filter mode */
3149 if (fifo_filter_data
<= BMI2_MAX_VALUE_FIFO_FILTER
)
3151 /* Set the accelerometer FIFO filter data */
3152 rslt
= bmi2_get_regs(BMI2_FIFO_DOWNS_ADDR
, &data
, 1, dev
);
3153 if (rslt
== BMI2_OK
)
3155 data
= BMI2_SET_BITS(data
, BMI2_ACC_FIFO_FILT_DATA
, fifo_filter_data
);
3156 rslt
= bmi2_set_regs(BMI2_FIFO_DOWNS_ADDR
, &data
, 1, dev
);
3161 rslt
= BMI2_E_OUT_OF_RANGE
;
3167 /* Validate filter mode */
3168 if (fifo_filter_data
<= BMI2_MAX_VALUE_FIFO_FILTER
)
3170 /* Set the gyroscope FIFO filter data */
3171 rslt
= bmi2_get_regs(BMI2_FIFO_DOWNS_ADDR
, &data
, 1, dev
);
3172 if (rslt
== BMI2_OK
)
3174 data
= BMI2_SET_BITS(data
, BMI2_GYR_FIFO_FILT_DATA
, fifo_filter_data
);
3175 rslt
= bmi2_set_regs(BMI2_FIFO_DOWNS_ADDR
, &data
, 1, dev
);
3180 rslt
= BMI2_E_OUT_OF_RANGE
;
3185 rslt
= BMI2_E_INVALID_SENSOR
;
3194 * @brief This API gets the FIFO accelerometer or gyroscope filter data.
3196 int8_t bmi2_get_fifo_filter_data(uint8_t sens_sel
, uint8_t *fifo_filter_data
, struct bmi2_dev
*dev
)
3198 /* Variable to define error */
3201 /* Variable to store FIFO filter mode */
3204 /* Null-pointer check */
3205 rslt
= null_ptr_check(dev
);
3206 if ((rslt
== BMI2_OK
) && (fifo_filter_data
!= NULL
))
3212 /* Read the accelerometer FIFO filter data */
3213 rslt
= bmi2_get_regs(BMI2_FIFO_DOWNS_ADDR
, &data
, 1, dev
);
3214 if (rslt
== BMI2_OK
)
3216 (*fifo_filter_data
) = BMI2_GET_BITS(data
, BMI2_ACC_FIFO_FILT_DATA
);
3222 /* Read the gyroscope FIFO filter data */
3223 rslt
= bmi2_get_regs(BMI2_FIFO_DOWNS_ADDR
, &data
, 1, dev
);
3224 if (rslt
== BMI2_OK
)
3226 (*fifo_filter_data
) = BMI2_GET_BITS(data
, BMI2_GYR_FIFO_FILT_DATA
);
3231 rslt
= BMI2_E_INVALID_SENSOR
;
3237 rslt
= BMI2_E_NULL_PTR
;
3244 * @brief This API sets the down-sampling rates for accelerometer or gyroscope
3247 int8_t bmi2_set_fifo_down_sample(uint8_t sens_sel
, uint8_t fifo_down_samp
, struct bmi2_dev
*dev
)
3249 /* Variable to define error */
3252 /* Variable to store sampling rate */
3255 /* Null-pointer check */
3256 rslt
= null_ptr_check(dev
);
3257 if (rslt
== BMI2_OK
)
3263 /* Set the accelerometer FIFO down sampling rate */
3264 rslt
= bmi2_get_regs(BMI2_FIFO_DOWNS_ADDR
, &data
, 1, dev
);
3265 if (rslt
== BMI2_OK
)
3267 data
= BMI2_SET_BITS(data
, BMI2_ACC_FIFO_DOWNS
, fifo_down_samp
);
3268 rslt
= bmi2_set_regs(BMI2_FIFO_DOWNS_ADDR
, &data
, 1, dev
);
3274 /* Set the gyroscope FIFO down sampling rate */
3275 rslt
= bmi2_get_regs(BMI2_FIFO_DOWNS_ADDR
, &data
, 1, dev
);
3276 if (rslt
== BMI2_OK
)
3278 data
= BMI2_SET_BIT_POS0(data
, BMI2_GYR_FIFO_DOWNS
, fifo_down_samp
);
3279 rslt
= bmi2_set_regs(BMI2_FIFO_DOWNS_ADDR
, &data
, 1, dev
);
3284 rslt
= BMI2_E_INVALID_SENSOR
;
3293 * @brief This API reads the down sampling rates which is configured for
3294 * accelerometer or gyroscope FIFO data.
3296 int8_t bmi2_get_fifo_down_sample(uint8_t sens_sel
, uint8_t *fifo_down_samp
, struct bmi2_dev
*dev
)
3298 /* Variable to define error */
3301 /* Variable to store sampling rate */
3304 /* Null-pointer check */
3305 rslt
= null_ptr_check(dev
);
3306 if ((rslt
== BMI2_OK
) && (fifo_down_samp
!= NULL
))
3312 /* Read the accelerometer FIFO down data sampling rate */
3313 rslt
= bmi2_get_regs(BMI2_FIFO_DOWNS_ADDR
, &data
, 1, dev
);
3314 if (rslt
== BMI2_OK
)
3316 (*fifo_down_samp
) = BMI2_GET_BITS(data
, BMI2_ACC_FIFO_DOWNS
);
3322 /* Read the gyroscope FIFO down data sampling rate */
3323 rslt
= bmi2_get_regs(BMI2_FIFO_DOWNS_ADDR
, &data
, 1, dev
);
3324 if (rslt
== BMI2_OK
)
3326 (*fifo_down_samp
) = BMI2_GET_BIT_POS0(data
, BMI2_GYR_FIFO_DOWNS
);
3331 rslt
= BMI2_E_INVALID_SENSOR
;
3337 rslt
= BMI2_E_NULL_PTR
;
3344 * @brief This API gets the length of FIFO data available in the sensor in
3347 int8_t bmi2_get_fifo_length(uint16_t *fifo_length
, struct bmi2_dev
*dev
)
3349 /* Variable to define error */
3352 /* Variable to define byte index */
3355 /* Array to store FIFO data length */
3356 uint8_t data
[BMI2_FIFO_DATA_LENGTH
] = { 0 };
3358 /* Null-pointer check */
3359 rslt
= null_ptr_check(dev
);
3360 if ((rslt
== BMI2_OK
) && (fifo_length
!= NULL
))
3362 /* Read FIFO length */
3363 rslt
= bmi2_get_regs(BMI2_FIFO_LENGTH_0_ADDR
, data
, BMI2_FIFO_DATA_LENGTH
, dev
);
3364 if (rslt
== BMI2_OK
)
3366 /* Get the MSB byte index */
3367 index
= BMI2_FIFO_LENGTH_MSB_BYTE
;
3369 /* Get the MSB byte of FIFO length */
3370 data
[index
] = BMI2_GET_BIT_POS0(data
[index
], BMI2_FIFO_BYTE_COUNTER_MSB
);
3372 /* Get total FIFO length */
3373 (*fifo_length
) = ((data
[index
] << 8) | data
[index
- 1]);
3378 rslt
= BMI2_E_NULL_PTR
;
3385 * @brief This API reads the user-defined bytes of data from the given register
3386 * address of auxiliary sensor in manual mode.
3388 * @note Change of BMI2_AUX_RD_ADDR is only allowed if AUX is not busy.
3390 int8_t bmi2_read_aux_man_mode(uint8_t reg_addr
, uint8_t *aux_data
, uint16_t len
, struct bmi2_dev
*dev
)
3392 /* Variable to define error */
3395 /* Variable to store burst length */
3396 uint8_t burst_len
= 0;
3398 /* Variable to define APS status */
3399 uint8_t aps_stat
= 0;
3401 /* Null-pointer check */
3402 rslt
= null_ptr_check(dev
);
3403 if ((rslt
== BMI2_OK
) && (aux_data
!= NULL
))
3405 /* Validate if manual mode */
3406 if (dev
->aux_man_en
)
3408 /* Get status of advance power save mode */
3409 aps_stat
= dev
->aps_status
;
3410 if (aps_stat
== BMI2_ENABLE
)
3412 /* Disable APS if enabled */
3413 rslt
= bmi2_set_adv_power_save(BMI2_DISABLE
, dev
);
3416 if (rslt
== BMI2_OK
)
3418 /* Map the register value set to that of burst
3421 rslt
= map_read_len(&burst_len
, dev
);
3422 if (rslt
== BMI2_OK
)
3424 /* Read auxiliary data */
3425 rslt
= read_aux_data(reg_addr
, aux_data
, len
, burst_len
, dev
);
3429 /* Enable Advance power save if disabled for reading
3430 * data and not when already disabled
3432 if ((rslt
== BMI2_OK
) && (aps_stat
== BMI2_ENABLE
))
3434 rslt
= bmi2_set_adv_power_save(BMI2_ENABLE
, dev
);
3439 rslt
= BMI2_E_AUX_INVALID_CFG
;
3444 rslt
= BMI2_E_NULL_PTR
;
3451 * @brief This API writes the user-defined bytes of data and the address of
3452 * auxiliary sensor where data is to be written in manual mode.
3454 * @note Change of BMI2_AUX_WR_ADDR is only allowed if AUX is not busy.
3456 int8_t bmi2_write_aux_man_mode(uint8_t reg_addr
, const uint8_t *aux_data
, uint16_t len
, struct bmi2_dev
*dev
)
3458 /* Variable to define error */
3461 /* Variable to define loop */
3464 /* Variable to define APS status */
3465 uint8_t aps_stat
= 0;
3467 /* Null-pointer check */
3468 rslt
= null_ptr_check(dev
);
3469 if ((rslt
== BMI2_OK
) && (aux_data
!= NULL
))
3471 /* Validate if manual mode */
3472 if (dev
->aux_man_en
)
3474 /* Get status of advance power save mode */
3475 aps_stat
= dev
->aps_status
;
3476 if (aps_stat
== BMI2_ENABLE
)
3478 /* Disable APS if enabled */
3479 rslt
= bmi2_set_adv_power_save(BMI2_DISABLE
, dev
);
3482 /* Byte write data in the corresponding address */
3483 if (rslt
== BMI2_OK
)
3485 for (; ((loop
< len
) && (rslt
== BMI2_OK
)); loop
++)
3487 rslt
= write_aux_data((reg_addr
+ loop
), aux_data
[loop
], dev
);
3488 dev
->delay_us(1000, dev
->intf_ptr
);
3492 /* Enable Advance power save if disabled for writing
3493 * data and not when already disabled
3495 if ((rslt
== BMI2_OK
) && (aps_stat
== BMI2_ENABLE
))
3497 rslt
= bmi2_set_adv_power_save(BMI2_ENABLE
, dev
);
3502 rslt
= BMI2_E_AUX_INVALID_CFG
;
3507 rslt
= BMI2_E_NULL_PTR
;
3514 * @brief This API writes the user-defined bytes of data and the address of
3515 * auxiliary sensor where data is to be written, from an interleaved input,
3518 * @note Change of BMI2_AUX_WR_ADDR is only allowed if AUX is not busy.
3520 int8_t bmi2_write_aux_interleaved(uint8_t reg_addr
, const uint8_t *aux_data
, uint16_t len
, struct bmi2_dev
*dev
)
3522 /* Variable to define error */
3525 /* Variable to define loop */
3528 /* Variable to define APS status */
3529 uint8_t aps_stat
= 0;
3531 /* Null-pointer check */
3532 rslt
= null_ptr_check(dev
);
3533 if ((rslt
== BMI2_OK
) && (aux_data
!= NULL
))
3535 /* Validate if manual mode */
3536 if (dev
->aux_man_en
)
3538 /* Get status of advance power save mode */
3539 aps_stat
= dev
->aps_status
;
3540 if (aps_stat
== BMI2_ENABLE
)
3542 /* Disable APS if enabled */
3543 rslt
= bmi2_set_adv_power_save(BMI2_DISABLE
, dev
);
3546 if (rslt
== BMI2_OK
)
3548 /* Write the start register address extracted
3549 * from the interleaved data
3551 rslt
= write_aux_data(reg_addr
, aux_data
[0], dev
);
3553 /* Extract the remaining address and data from
3554 * the interleaved data and write it in the
3555 * corresponding addresses byte by byte
3557 for (; ((loop
< len
) && (rslt
== BMI2_OK
)); loop
+= 2)
3559 rslt
= write_aux_data(aux_data
[loop
], aux_data
[loop
+ 1], dev
);
3560 dev
->delay_us(1000, dev
->intf_ptr
);
3563 /* Enable Advance power save if disabled for
3564 * writing data and not when already disabled
3566 if ((rslt
== BMI2_OK
) && (aps_stat
== BMI2_ENABLE
))
3568 rslt
= bmi2_set_adv_power_save(BMI2_ENABLE
, dev
);
3574 rslt
= BMI2_E_AUX_INVALID_CFG
;
3579 rslt
= BMI2_E_NULL_PTR
;
3586 * @brief This API gets the data ready status of accelerometer, gyroscope,
3587 * auxiliary, command decoder and busy status of auxiliary.
3589 int8_t bmi2_get_status(uint8_t *status
, struct bmi2_dev
*dev
)
3591 /* Variable to define error */
3594 /* Null-pointer check */
3595 rslt
= null_ptr_check(dev
);
3596 if ((rslt
== BMI2_OK
) && (status
!= NULL
))
3598 rslt
= bmi2_get_regs(BMI2_STATUS_ADDR
, status
, 1, dev
);
3602 rslt
= BMI2_E_NULL_PTR
;
3609 * @brief This API enables/disables OIS interface.
3611 int8_t bmi2_set_ois_interface(uint8_t enable
, struct bmi2_dev
*dev
)
3613 /* Variable to define error */
3616 /* Variable to store data */
3617 uint8_t reg_data
= 0;
3619 /* Null-pointer check */
3620 rslt
= null_ptr_check(dev
);
3621 if (rslt
== BMI2_OK
)
3623 rslt
= bmi2_get_regs(BMI2_IF_CONF_ADDR
, ®_data
, 1, dev
);
3624 if (rslt
== BMI2_OK
)
3626 /* Enable/Disable OIS interface */
3627 reg_data
= BMI2_SET_BITS(reg_data
, BMI2_OIS_IF_EN
, enable
);
3630 /* Disable auxiliary interface if OIS is enabled */
3631 reg_data
= BMI2_SET_BIT_VAL0(reg_data
, BMI2_AUX_IF_EN
);
3634 /* Set the OIS interface configurations */
3635 rslt
= bmi2_set_regs(BMI2_IF_CONF_ADDR
, ®_data
, 1, dev
);
3643 * @brief This API can be used to write sync commands like ODR, sync period,
3644 * frequency and phase, resolution ratio, sync time and delay time.
3646 int8_t bmi2_write_sync_commands(const uint8_t *command
, uint8_t n_comm
, struct bmi2_dev
*dev
)
3648 /* Variable to define error */
3651 /* Null-pointer check */
3652 rslt
= null_ptr_check(dev
);
3653 if ((rslt
== BMI2_OK
) && (command
!= NULL
))
3655 rslt
= bmi2_set_regs(BMI2_SYNC_COMMAND_ADDR
, command
, n_comm
, dev
);
3659 rslt
= BMI2_E_NULL_PTR
;
3666 * @brief This API performs self-test to check the proper functionality of the
3667 * accelerometer sensor.
3669 int8_t bmi2_perform_accel_self_test(struct bmi2_dev
*dev
)
3671 /* Variable to define error */
3674 /* Variable to store self-test result */
3677 /* Structure to define positive accelerometer axes */
3678 struct bmi2_sens_axes_data positive
= { 0, 0, 0, 0 };
3680 /* Structure to define negative accelerometer axes */
3681 struct bmi2_sens_axes_data negative
= { 0, 0, 0, 0 };
3683 /* Structure for difference of accelerometer values in g */
3684 struct bmi2_selftest_delta_limit accel_data_diff
= { 0, 0, 0 };
3686 /* Structure for difference of accelerometer values in mg */
3687 struct bmi2_selftest_delta_limit accel_data_diff_mg
= { 0, 0, 0 };
3689 /* Initialize the polarity of self-test as positive */
3690 int8_t sign
= BMI2_ENABLE
;
3692 /* Null-pointer check */
3693 rslt
= null_ptr_check(dev
);
3694 if (rslt
== BMI2_OK
)
3696 /* Sets the configuration required before enabling self-test */
3697 rslt
= pre_self_test_config(dev
);
3699 /* Wait for greater than 2 milliseconds */
3700 dev
->delay_us(3000, dev
->intf_ptr
);
3701 if (rslt
== BMI2_OK
)
3705 /* Select positive first, then negative polarity
3706 * after enabling self-test
3708 rslt
= self_test_config((uint8_t) sign
, dev
);
3709 if (rslt
== BMI2_OK
)
3711 /* Wait for greater than 50 milli-sec */
3712 dev
->delay_us(51000, dev
->intf_ptr
);
3714 /* If polarity is positive */
3715 if (sign
== BMI2_ENABLE
)
3717 /* Read and store positive acceleration value */
3718 rslt
= read_accel_xyz(&positive
, dev
);
3720 /* If polarity is negative */
3721 else if (sign
== BMI2_DISABLE
)
3723 /* Read and store negative acceleration value */
3724 rslt
= read_accel_xyz(&negative
, dev
);
3729 /* Break if error */
3733 /* Break if error */
3734 if (rslt
!= BMI2_OK
)
3739 /* Turn the polarity of self-test negative */
3741 } while (sign
>= 0);
3742 if (rslt
== BMI2_OK
)
3744 /* Subtract -ve acceleration values from that of +ve values */
3745 accel_data_diff
.x
= (positive
.x
) - (negative
.x
);
3746 accel_data_diff
.y
= (positive
.y
) - (negative
.y
);
3747 accel_data_diff
.z
= (positive
.z
) - (negative
.z
);
3749 /* Convert differences of acceleration values
3752 convert_lsb_g(&accel_data_diff
, &accel_data_diff_mg
, dev
);
3754 /* Validate self-test for acceleration values
3755 * in mg and get the self-test result
3757 st_rslt
= validate_self_test(&accel_data_diff_mg
);
3759 /* Trigger a soft reset after performing self-test */
3760 rslt
= bmi2_soft_reset(dev
);
3762 /* Return the self-test result */
3763 if (rslt
== BMI2_OK
)
3775 * @brief This API maps/unmaps feature interrupts to that of interrupt pins.
3777 int8_t bmi2_map_feat_int(uint8_t type
, enum bmi2_hw_int_pin hw_int_pin
, struct bmi2_dev
*dev
)
3779 /* Variable to define error */
3782 /* Variable to define the value of feature interrupts */
3783 uint8_t feat_int
= 0;
3785 /* Array to store the interrupt mask bits */
3786 uint8_t data_array
[2] = { 0 };
3788 /* Structure to define map the interrupts */
3789 struct bmi2_map_int map_int
= { 0 };
3791 /* Null-pointer check */
3792 rslt
= null_ptr_check(dev
);
3793 if (rslt
== BMI2_OK
)
3795 /* Read interrupt map1 and map2 and register */
3796 rslt
= bmi2_get_regs(BMI2_INT1_MAP_FEAT_ADDR
, data_array
, 2, dev
);
3798 if (rslt
== BMI2_OK
)
3800 /* Get the value of the feature interrupt to be mapped */
3801 extract_feat_int_map(&map_int
, type
, dev
);
3803 feat_int
= map_int
.sens_map_int
;
3805 /* Map the interrupts */
3806 rslt
= map_feat_int(data_array
, hw_int_pin
, feat_int
);
3808 /* Map the interrupts to INT1 and INT2 map register */
3809 if (rslt
== BMI2_OK
)
3811 rslt
= bmi2_set_regs(BMI2_INT1_MAP_FEAT_ADDR
, &data_array
[0], 1, dev
);
3812 if (rslt
== BMI2_OK
)
3814 rslt
= bmi2_set_regs(BMI2_INT2_MAP_FEAT_ADDR
, &data_array
[1], 1, dev
);
3821 rslt
= BMI2_E_NULL_PTR
;
3828 * @brief This API maps/un-maps data interrupts to that of interrupt pins.
3830 int8_t bmi2_map_data_int(uint8_t data_int
, enum bmi2_hw_int_pin int_pin
, struct bmi2_dev
*dev
)
3832 /* Variable to define error */
3835 /* Variable to mask interrupt pin 1 - lower nibble */
3836 uint8_t int1_mask
= data_int
;
3838 /* Variable to mask interrupt pin 2 - higher nibble */
3839 uint8_t int2_mask
= (uint8_t)(data_int
<< 4);
3841 /* Variable to store register data */
3842 uint8_t reg_data
= 0;
3844 /* Read interrupt map1 and map2 and register */
3845 rslt
= bmi2_get_regs(BMI2_INT_MAP_DATA_ADDR
, ®_data
, 1, dev
);
3846 if (rslt
== BMI2_OK
)
3848 if (int_pin
< BMI2_INT_PIN_MAX
)
3854 /* Un-Map the corresponding data
3855 * interrupt to both interrupt pin 1 and 2
3857 reg_data
&= ~(int1_mask
| int2_mask
);
3861 /* Map the corresponding data interrupt to
3864 reg_data
|= int1_mask
;
3868 /* Map the corresponding data interrupt to
3871 reg_data
|= int2_mask
;
3875 /* Map the corresponding data
3876 * interrupt to both interrupt pin 1 and 2
3878 reg_data
|= (int1_mask
| int2_mask
);
3884 /* Set the interrupts in the map register */
3885 rslt
= bmi2_set_regs(BMI2_INT_MAP_DATA_ADDR
, ®_data
, 1, dev
);
3889 /* Return error if invalid pin selection */
3890 rslt
= BMI2_E_INVALID_INT_PIN
;
3898 * @brief This API gets the re-mapped x, y and z axes from the sensor and
3899 * updates the values in the device structure.
3901 int8_t bmi2_get_remap_axes(struct bmi2_remap
*remapped_axis
, struct bmi2_dev
*dev
)
3903 /* Variable to define error */
3906 /* Initialize the local structure for axis re-mapping */
3907 struct bmi2_axes_remap remap
= { 0, 0, 0, 0, 0, 0 };
3909 /* Null-pointer check */
3910 rslt
= null_ptr_check(dev
);
3911 if ((rslt
== BMI2_OK
) && (remapped_axis
!= NULL
))
3913 /* Get the re-mapped axes from the sensor */
3914 rslt
= get_remap_axes(&remap
, dev
);
3915 if (rslt
== BMI2_OK
)
3917 /* Store the re-mapped x-axis value in device structure
3918 * and its user-value in the interface structure
3920 switch (remap
.x_axis
)
3922 case BMI2_MAP_X_AXIS
:
3924 /* If mapped to x-axis */
3925 dev
->remap
.x_axis
= BMI2_MAP_X_AXIS
;
3926 remapped_axis
->x
= BMI2_X
;
3928 case BMI2_MAP_Y_AXIS
:
3930 /* If mapped to y-axis */
3931 dev
->remap
.x_axis
= BMI2_MAP_Y_AXIS
;
3932 remapped_axis
->x
= BMI2_Y
;
3934 case BMI2_MAP_Z_AXIS
:
3936 /* If mapped to z-axis */
3937 dev
->remap
.x_axis
= BMI2_MAP_Z_AXIS
;
3938 remapped_axis
->x
= BMI2_Z
;
3944 /* Store the re-mapped x-axis sign in device structure
3945 * and its user-value in the interface structure
3947 if (remap
.x_axis_sign
)
3949 /* If x-axis is mapped to -ve sign */
3950 dev
->remap
.x_axis_sign
= BMI2_NEG_SIGN
;
3951 remapped_axis
->x
|= BMI2_AXIS_SIGN
;
3955 dev
->remap
.x_axis_sign
= BMI2_POS_SIGN
;
3958 /* Store the re-mapped y-axis value in device structure
3959 * and its user-value in the interface structure
3961 switch (remap
.y_axis
)
3963 case BMI2_MAP_X_AXIS
:
3965 /* If mapped to x-axis */
3966 dev
->remap
.y_axis
= BMI2_MAP_X_AXIS
;
3967 remapped_axis
->y
= BMI2_X
;
3969 case BMI2_MAP_Y_AXIS
:
3971 /* If mapped to y-axis */
3972 dev
->remap
.y_axis
= BMI2_MAP_Y_AXIS
;
3973 remapped_axis
->y
= BMI2_Y
;
3975 case BMI2_MAP_Z_AXIS
:
3977 /* If mapped to z-axis */
3978 dev
->remap
.y_axis
= BMI2_MAP_Z_AXIS
;
3979 remapped_axis
->y
= BMI2_Z
;
3985 /* Store the re-mapped y-axis sign in device structure
3986 * and its user-value in the interface structure
3988 if (remap
.y_axis_sign
)
3990 /* If y-axis is mapped to -ve sign */
3991 dev
->remap
.y_axis_sign
= BMI2_NEG_SIGN
;
3992 remapped_axis
->y
|= BMI2_AXIS_SIGN
;
3996 dev
->remap
.y_axis_sign
= BMI2_POS_SIGN
;
3999 /* Store the re-mapped z-axis value in device structure
4000 * and its user-value in the interface structure
4002 switch (remap
.z_axis
)
4004 case BMI2_MAP_X_AXIS
:
4006 /* If mapped to x-axis */
4007 dev
->remap
.z_axis
= BMI2_MAP_X_AXIS
;
4008 remapped_axis
->z
= BMI2_X
;
4010 case BMI2_MAP_Y_AXIS
:
4012 /* If mapped to y-axis */
4013 dev
->remap
.z_axis
= BMI2_MAP_Y_AXIS
;
4014 remapped_axis
->z
= BMI2_Y
;
4016 case BMI2_MAP_Z_AXIS
:
4018 /* If mapped to z-axis */
4019 dev
->remap
.z_axis
= BMI2_MAP_Z_AXIS
;
4020 remapped_axis
->z
= BMI2_Z
;
4026 /* Store the re-mapped z-axis sign in device structure
4027 * and its user-value in the interface structure
4029 if (remap
.z_axis_sign
)
4031 /* If z-axis is mapped to -ve sign */
4032 dev
->remap
.z_axis_sign
= BMI2_NEG_SIGN
;
4033 remapped_axis
->z
|= BMI2_AXIS_SIGN
;
4037 dev
->remap
.z_axis_sign
= BMI2_POS_SIGN
;
4043 rslt
= BMI2_E_NULL_PTR
;
4050 * @brief This API sets the re-mapped x, y and z axes to the sensor and
4051 * updates the them in the device structure.
4053 int8_t bmi2_set_remap_axes(const struct bmi2_remap
*remapped_axis
, struct bmi2_dev
*dev
)
4055 /* Variable to define error */
4058 /* Variable to store all the re-mapped axes */
4059 uint8_t remap_axes
= 0;
4061 /* Variable to store the re-mapped x-axes */
4062 uint8_t remap_x
= 0;
4064 /* Variable to store the re-mapped y-axes */
4065 uint8_t remap_y
= 0;
4067 /* Variable to store the re-mapped z-axes */
4068 uint8_t remap_z
= 0;
4070 /* Initialize the local structure for axis re-mapping */
4071 struct bmi2_axes_remap remap
= { 0, 0, 0, 0, 0, 0 };
4073 /* Null-pointer check */
4074 rslt
= null_ptr_check(dev
);
4075 if ((rslt
== BMI2_OK
) && (remapped_axis
!= NULL
))
4077 /* Check whether all the axes are re-mapped */
4078 remap_axes
= remapped_axis
->x
| remapped_axis
->y
| remapped_axis
->z
;
4080 /* If all the axes are re-mapped */
4081 if ((remap_axes
& BMI2_AXIS_MASK
) == BMI2_AXIS_MASK
)
4083 /* Get the re-mapped value of x, y and z axis */
4084 remap_x
= remapped_axis
->x
& BMI2_AXIS_MASK
;
4085 remap_y
= remapped_axis
->y
& BMI2_AXIS_MASK
;
4086 remap_z
= remapped_axis
->z
& BMI2_AXIS_MASK
;
4088 /* Store the value of re-mapped x-axis in both
4089 * device structure and the local structure
4095 /* If mapped to x-axis */
4096 dev
->remap
.x_axis
= BMI2_MAP_X_AXIS
;
4097 remap
.x_axis
= BMI2_MAP_X_AXIS
;
4101 /* If mapped to y-axis */
4102 dev
->remap
.x_axis
= BMI2_MAP_Y_AXIS
;
4103 remap
.x_axis
= BMI2_MAP_Y_AXIS
;
4107 /* If mapped to z-axis */
4108 dev
->remap
.x_axis
= BMI2_MAP_Z_AXIS
;
4109 remap
.x_axis
= BMI2_MAP_Z_AXIS
;
4115 /* Store the re-mapped x-axis sign in the device
4116 * structure and its value in local structure
4118 if (remapped_axis
->x
& BMI2_AXIS_SIGN
)
4120 /* If x-axis is mapped to -ve sign */
4121 dev
->remap
.x_axis_sign
= BMI2_NEG_SIGN
;
4122 remap
.x_axis_sign
= BMI2_MAP_NEGATIVE
;
4126 dev
->remap
.x_axis_sign
= BMI2_POS_SIGN
;
4127 remap
.x_axis_sign
= BMI2_MAP_POSITIVE
;
4130 /* Store the value of re-mapped y-axis in both
4131 * device structure and the local structure
4137 /* If mapped to x-axis */
4138 dev
->remap
.y_axis
= BMI2_MAP_X_AXIS
;
4139 remap
.y_axis
= BMI2_MAP_X_AXIS
;
4143 /* If mapped to y-axis */
4144 dev
->remap
.y_axis
= BMI2_MAP_Y_AXIS
;
4145 remap
.y_axis
= BMI2_MAP_Y_AXIS
;
4149 /* If mapped to z-axis */
4150 dev
->remap
.y_axis
= BMI2_MAP_Z_AXIS
;
4151 remap
.y_axis
= BMI2_MAP_Z_AXIS
;
4157 /* Store the re-mapped y-axis sign in the device
4158 * structure and its value in local structure
4160 if (remapped_axis
->y
& BMI2_AXIS_SIGN
)
4162 /* If y-axis is mapped to -ve sign */
4163 dev
->remap
.y_axis_sign
= BMI2_NEG_SIGN
;
4164 remap
.y_axis_sign
= BMI2_MAP_NEGATIVE
;
4168 dev
->remap
.y_axis_sign
= BMI2_POS_SIGN
;
4169 remap
.y_axis_sign
= BMI2_MAP_POSITIVE
;
4172 /* Store the value of re-mapped z-axis in both
4173 * device structure and the local structure
4179 /* If mapped to x-axis */
4180 dev
->remap
.z_axis
= BMI2_MAP_X_AXIS
;
4181 remap
.z_axis
= BMI2_MAP_X_AXIS
;
4185 /* If mapped to y-axis */
4186 dev
->remap
.z_axis
= BMI2_MAP_Y_AXIS
;
4187 remap
.z_axis
= BMI2_MAP_Y_AXIS
;
4191 /* If mapped to z-axis */
4192 dev
->remap
.z_axis
= BMI2_MAP_Z_AXIS
;
4193 remap
.z_axis
= BMI2_MAP_Z_AXIS
;
4199 /* Store the re-mapped z-axis sign in the device
4200 * structure and its value in local structure
4202 if (remapped_axis
->z
& BMI2_AXIS_SIGN
)
4204 /* If z-axis is mapped to -ve sign */
4205 dev
->remap
.z_axis_sign
= BMI2_NEG_SIGN
;
4206 remap
.z_axis_sign
= BMI2_MAP_NEGATIVE
;
4210 dev
->remap
.z_axis_sign
= BMI2_POS_SIGN
;
4211 remap
.z_axis_sign
= BMI2_MAP_POSITIVE
;
4214 /* Set the re-mapped axes in the sensor */
4215 rslt
= set_remap_axes(&remap
, dev
);
4219 rslt
= BMI2_E_REMAP_ERROR
;
4224 rslt
= BMI2_E_NULL_PTR
;
4231 * @brief This API enables/disables gyroscope offset compensation. It adds the
4232 * offsets defined in the offset register with gyroscope data.
4234 int8_t bmi2_set_gyro_offset_comp(uint8_t enable
, struct bmi2_dev
*dev
)
4236 /* Variable to define error */
4239 /* Variable to define register data */
4240 uint8_t reg_data
= 0;
4242 /* Null-pointer check */
4243 rslt
= null_ptr_check(dev
);
4244 if (rslt
== BMI2_OK
)
4246 /* Get the status of gyroscope offset enable */
4247 rslt
= bmi2_get_regs(BMI2_GYR_OFF_COMP_6_ADDR
, ®_data
, 1, dev
);
4248 if (rslt
== BMI2_OK
)
4250 reg_data
= BMI2_SET_BITS(reg_data
, BMI2_GYR_OFF_COMP_EN
, enable
);
4252 /* Enable/Disable gyroscope offset compensation */
4253 rslt
= bmi2_set_regs(BMI2_GYR_OFF_COMP_6_ADDR
, ®_data
, 1, dev
);
4258 rslt
= BMI2_E_NULL_PTR
;
4265 * @brief This API reads the gyroscope bias values for each axis which is used
4266 * for gyroscope offset compensation.
4268 int8_t bmi2_read_gyro_offset_comp_axes(struct bmi2_sens_axes_data
*gyr_off_comp_axes
, struct bmi2_dev
*dev
)
4270 /* Variable to define error */
4273 /* Variable to define register data */
4274 uint8_t reg_data
[4] = { 0 };
4276 /* Variable to store LSB value of offset compensation for x-axis */
4277 uint8_t gyr_off_lsb_x
;
4279 /* Variable to store LSB value of offset compensation for y-axis */
4280 uint8_t gyr_off_lsb_y
;
4282 /* Variable to store LSB value of offset compensation for z-axis */
4283 uint8_t gyr_off_lsb_z
;
4285 /* Variable to store MSB value of offset compensation for x-axis */
4286 uint8_t gyr_off_msb_x
;
4288 /* Variable to store MSB value of offset compensation for y-axis */
4289 uint8_t gyr_off_msb_y
;
4291 /* Variable to store MSB value of offset compensation for z-axis */
4292 uint8_t gyr_off_msb_z
;
4294 /* Null-pointer check */
4295 rslt
= null_ptr_check(dev
);
4296 if ((rslt
== BMI2_OK
) && (gyr_off_comp_axes
!= NULL
))
4298 /* Get the gyroscope compensated offset values */
4299 rslt
= bmi2_get_regs(BMI2_GYR_OFF_COMP_3_ADDR
, reg_data
, 4, dev
);
4300 if (rslt
== BMI2_OK
)
4302 /* Get LSB and MSB values of offset compensation for
4305 gyr_off_lsb_x
= reg_data
[0];
4306 gyr_off_lsb_y
= reg_data
[1];
4307 gyr_off_lsb_z
= reg_data
[2];
4308 gyr_off_msb_x
= reg_data
[3] & BMI2_GYR_OFF_COMP_MSB_X_MASK
;
4309 gyr_off_msb_y
= reg_data
[3] & BMI2_GYR_OFF_COMP_MSB_Y_MASK
;
4310 gyr_off_msb_z
= reg_data
[3] & BMI2_GYR_OFF_COMP_MSB_Z_MASK
;
4312 /* Gyroscope offset compensation value for x-axis */
4313 gyr_off_comp_axes
->x
= (int16_t)(((uint16_t) gyr_off_msb_x
<< 8) | gyr_off_lsb_x
);
4315 /* Gyroscope offset compensation value for y-axis */
4316 gyr_off_comp_axes
->y
= (int16_t)(((uint16_t) gyr_off_msb_y
<< 6) | gyr_off_lsb_y
);
4318 /* Gyroscope offset compensation value for z-axis */
4319 gyr_off_comp_axes
->z
= (int16_t)(((uint16_t) gyr_off_msb_z
<< 4) | gyr_off_lsb_z
);
4324 rslt
= BMI2_E_NULL_PTR
;
4331 * @brief This API writes the gyroscope bias values for each axis which is used
4332 * for gyroscope offset compensation.
4334 int8_t bmi2_write_gyro_offset_comp_axes(const struct bmi2_sens_axes_data
*gyr_off_comp_axes
, struct bmi2_dev
*dev
)
4336 /* Variable to define error */
4339 /* Variable to define register data */
4340 uint8_t reg_data
[4] = { 0 };
4342 /* Variable to store MSB value of offset compensation for x-axis */
4343 uint8_t gyr_off_msb_x
;
4345 /* Variable to store MSB value of offset compensation for y-axis */
4346 uint8_t gyr_off_msb_y
;
4348 /* Variable to store MSB value of offset compensation for z-axis */
4349 uint8_t gyr_off_msb_z
;
4351 /* Null-pointer check */
4352 rslt
= null_ptr_check(dev
);
4353 if ((rslt
== BMI2_OK
) && (gyr_off_comp_axes
!= NULL
))
4355 /* Get the MSB values of gyroscope compensated offset values */
4356 rslt
= bmi2_get_regs(BMI2_GYR_OFF_COMP_6_ADDR
, ®_data
[3], 1, dev
);
4357 if (rslt
== BMI2_OK
)
4359 /* Get MSB value of x-axis from user-input */
4360 gyr_off_msb_x
= (uint8_t)((gyr_off_comp_axes
->x
& BMI2_GYR_OFF_COMP_MSB_MASK
) >> 8);
4362 /* Get MSB value of y-axis from user-input */
4363 gyr_off_msb_y
= (uint8_t)((gyr_off_comp_axes
->y
& BMI2_GYR_OFF_COMP_MSB_MASK
) >> 8);
4365 /* Get MSB value of z-axis from user-input */
4366 gyr_off_msb_z
= (uint8_t)((gyr_off_comp_axes
->z
& BMI2_GYR_OFF_COMP_MSB_MASK
) >> 8);
4368 /* Get LSB value of x-axis from user-input */
4369 reg_data
[0] = (uint8_t)(gyr_off_comp_axes
->x
& BMI2_GYR_OFF_COMP_LSB_MASK
);
4371 /* Get LSB value of y-axis from user-input */
4372 reg_data
[1] = (uint8_t)(gyr_off_comp_axes
->y
& BMI2_GYR_OFF_COMP_LSB_MASK
);
4374 /* Get LSB value of z-axis from user-input */
4375 reg_data
[2] = (uint8_t)(gyr_off_comp_axes
->z
& BMI2_GYR_OFF_COMP_LSB_MASK
);
4377 /* Get MSB value of x-axis to be set */
4378 reg_data
[3] = BMI2_SET_BIT_POS0(reg_data
[3], BMI2_GYR_OFF_COMP_MSB_X
, gyr_off_msb_x
);
4380 /* Get MSB value of y-axis to be set */
4381 reg_data
[3] = BMI2_SET_BITS(reg_data
[3], BMI2_GYR_OFF_COMP_MSB_Y
, gyr_off_msb_y
);
4383 /* Get MSB value of z-axis to be set */
4384 reg_data
[3] = BMI2_SET_BITS(reg_data
[3], BMI2_GYR_OFF_COMP_MSB_Z
, gyr_off_msb_z
);
4386 /* Set the offset compensation values of axes */
4387 rslt
= bmi2_set_regs(BMI2_GYR_OFF_COMP_3_ADDR
, reg_data
, 4, dev
);
4392 rslt
= BMI2_E_NULL_PTR
;
4399 * @brief This API updates the cross sensitivity coefficient between gyroscope's
4402 int8_t bmi2_get_gyro_cross_sense(struct bmi2_dev
*dev
)
4404 /* Variable to define error */
4405 int8_t rslt
= BMI2_OK
;
4406 struct bmi2_sensor_data data
;
4408 /* Check if the feature is supported by this variant */
4409 if (dev
->variant_feature
& BMI2_GYRO_CROSS_SENS_ENABLE
)
4411 rslt
= null_ptr_check(dev
);
4412 if (rslt
== BMI2_OK
)
4414 /* Select the feature whose data is to be acquired */
4415 data
.type
= BMI2_GYRO_CROSS_SENSE
;
4417 /* Get the respective data */
4418 rslt
= bmi2_get_sensor_data(&data
, 1, dev
);
4419 if (rslt
== BMI2_OK
)
4421 /* Update the gyroscope cross sense value of z axis
4422 * in the device structure
4424 dev
->gyr_cross_sens_zx
= data
.sens_data
.correction_factor_zx
;
4429 rslt
= BMI2_E_NULL_PTR
;
4437 * @brief This API gets Error bits and message indicating internal status.
4439 int8_t bmi2_get_internal_status(uint8_t *int_stat
, struct bmi2_dev
*dev
)
4441 /* Variable to define error */
4444 /* Null-pointer check */
4445 rslt
= null_ptr_check(dev
);
4446 if ((rslt
== BMI2_OK
) && (int_stat
!= NULL
))
4448 /* Delay to read the internal status */
4449 dev
->delay_us(20000, dev
->intf_ptr
);
4451 /* Get the error bits and message */
4452 rslt
= bmi2_get_regs(BMI2_INTERNAL_STATUS_ADDR
, int_stat
, 1, dev
);
4456 rslt
= BMI2_E_NULL_PTR
;
4462 /*! @cond DOXYGEN_SUPRESS */
4464 /* Suppressing doxygen warnings triggered for same static function names present across various sensor variant
4468 * @brief This API verifies and allows only the correct position to do Fast Offset Compensation for
4469 * accelerometer & gyro.
4471 static int8_t verify_foc_position(uint8_t sens_list
,
4472 const struct bmi2_accel_foc_g_value
*accel_g_axis
,
4473 struct bmi2_dev
*dev
)
4477 struct bmi2_sens_axes_data avg_foc_data
= { 0 };
4478 struct bmi2_foc_temp_value temp_foc_data
= { 0 };
4480 rslt
= null_ptr_check(dev
);
4481 if (rslt
== BMI2_OK
)
4484 rslt
= bmi2_sensor_enable(&sens_list
, 1, dev
);
4487 if (rslt
== BMI2_OK
)
4490 rslt
= get_average_of_sensor_data(sens_list
, &temp_foc_data
, dev
);
4491 if (rslt
== BMI2_OK
)
4493 if (sens_list
== BMI2_ACCEL
)
4496 /* Taking modulus to make negative values as positive */
4497 if ((accel_g_axis
->x
== 1) && (accel_g_axis
->sign
== 1))
4499 temp_foc_data
.x
= temp_foc_data
.x
* -1;
4501 else if ((accel_g_axis
->y
== 1) && (accel_g_axis
->sign
== 1))
4503 temp_foc_data
.y
= temp_foc_data
.y
* -1;
4505 else if ((accel_g_axis
->z
== 1) && (accel_g_axis
->sign
== 1))
4507 temp_foc_data
.z
= temp_foc_data
.z
* -1;
4511 /* Typecasting into 16bit */
4512 avg_foc_data
.x
= (int16_t)(temp_foc_data
.x
);
4513 avg_foc_data
.y
= (int16_t)(temp_foc_data
.y
);
4514 avg_foc_data
.z
= (int16_t)(temp_foc_data
.z
);
4516 rslt
= validate_foc_position(sens_list
, accel_g_axis
, avg_foc_data
, dev
);
4526 * @brief This API performs Fast Offset Compensation for accelerometer.
4528 int8_t bmi2_perform_accel_foc(const struct bmi2_accel_foc_g_value
*accel_g_value
, struct bmi2_dev
*dev
)
4530 /* Variable to define error */
4533 /* Structure to define the accelerometer configurations */
4534 struct bmi2_accel_config acc_cfg
= { 0, 0, 0, 0 };
4536 /* Variable to store status of advance power save */
4539 /* Variable to store status of accelerometer enable */
4542 /* Null-pointer check */
4543 rslt
= null_ptr_check(dev
);
4544 if ((rslt
== BMI2_OK
) && (accel_g_value
!= NULL
))
4546 /* Check for input validity */
4547 if ((((BMI2_ABS(accel_g_value
->x
)) + (BMI2_ABS(accel_g_value
->y
)) + (BMI2_ABS(accel_g_value
->z
))) == 1) &&
4548 ((accel_g_value
->sign
== 1) || (accel_g_value
->sign
== 0)))
4550 rslt
= verify_foc_position(BMI2_ACCEL
, accel_g_value
, dev
);
4551 if (rslt
== BMI2_OK
)
4554 /* Save accelerometer configurations, accelerometer
4555 * enable status and advance power save status
4557 rslt
= save_accel_foc_config(&acc_cfg
, &aps
, &acc_en
, dev
);
4560 /* Set configurations for FOC */
4561 if (rslt
== BMI2_OK
)
4563 rslt
= set_accel_foc_config(dev
);
4566 /* Perform accelerometer FOC */
4567 if (rslt
== BMI2_OK
)
4569 rslt
= perform_accel_foc(accel_g_value
, &acc_cfg
, dev
);
4572 /* Restore the saved configurations */
4573 if (rslt
== BMI2_OK
)
4575 rslt
= restore_accel_foc_config(&acc_cfg
, aps
, acc_en
, dev
);
4580 rslt
= BMI2_E_INVALID_INPUT
;
4585 rslt
= BMI2_E_NULL_PTR
;
4592 * @brief This API performs Fast Offset Compensation for gyroscope.
4594 int8_t bmi2_perform_gyro_foc(struct bmi2_dev
*dev
)
4596 /* Variable to define error */
4599 /* Structure to define the gyroscope configurations */
4600 struct bmi2_gyro_config gyr_cfg
= { 0, 0, 0, 0, 0, 0 };
4602 /* Variable to store status of advance power save */
4605 /* Variable to store status of gyroscope enable */
4608 /* Array of structure to store gyroscope data */
4609 struct bmi2_sens_axes_data gyr_value
[128];
4611 /* Structure to store gyroscope data temporarily */
4612 struct bmi2_foc_temp_value temp
= { 0, 0, 0 };
4614 /* Variable to store status read from the status register */
4615 uint8_t reg_status
= 0;
4617 /* Variable to define count */
4620 /* Structure to store the offset values to be stored in the register */
4621 struct bmi2_sens_axes_data gyro_offset
= { 0, 0, 0, 0 };
4623 /* Null-pointer check */
4624 rslt
= null_ptr_check(dev
);
4625 if (rslt
== BMI2_OK
)
4627 /* Argument2 is not applicable for gyro */
4628 rslt
= verify_foc_position(BMI2_GYRO
, 0, dev
);
4629 if (rslt
== BMI2_OK
)
4631 /* Save gyroscope configurations, gyroscope enable
4632 * status and advance power save status
4634 rslt
= save_gyro_config(&gyr_cfg
, &aps
, &gyr_en
, dev
);
4636 /* Set configurations for gyroscope FOC */
4637 if (rslt
== BMI2_OK
)
4639 rslt
= set_gyro_foc_config(dev
);
4643 if (rslt
== BMI2_OK
)
4645 for (loop
= 0; loop
< 128; loop
++)
4647 /* Giving a delay of more than 40ms since ODR is configured as 25Hz */
4648 dev
->delay_us(50000, dev
->intf_ptr
);
4650 /* Get gyroscope data ready interrupt status */
4651 rslt
= bmi2_get_status(®_status
, dev
);
4653 /* Read 128 samples of gyroscope data on data ready interrupt */
4654 if ((rslt
== BMI2_OK
) && (reg_status
& BMI2_DRDY_GYR
))
4656 rslt
= read_gyro_xyz(&gyr_value
[loop
], dev
);
4657 if (rslt
== BMI2_OK
)
4659 /* Store the data in a temporary structure */
4660 temp
.x
= temp
.x
+ (int32_t)gyr_value
[loop
].x
;
4661 temp
.y
= temp
.y
+ (int32_t)gyr_value
[loop
].y
;
4662 temp
.z
= temp
.z
+ (int32_t)gyr_value
[loop
].z
;
4666 if (rslt
!= BMI2_OK
)
4670 else if ((reg_status
& BMI2_DRDY_GYR
) != BMI2_DRDY_GYR
)
4672 rslt
= BMI2_E_INVALID_STATUS
;
4677 if (rslt
== BMI2_OK
)
4679 /* Take average of x, y and z data for lesser
4680 * noise. It is same as offset data since lsb/dps
4681 * is same for both data and offset register
4683 gyro_offset
.x
= (int16_t)(temp
.x
/ 128);
4684 gyro_offset
.y
= (int16_t)(temp
.y
/ 128);
4685 gyro_offset
.z
= (int16_t)(temp
.z
/ 128);
4687 /* Saturate gyroscope data since the offset
4688 * registers are of 10 bit value where as the
4689 * gyroscope data is of 16 bit value
4691 saturate_gyro_data(&gyro_offset
);
4693 /* Invert the gyroscope offset data */
4694 invert_gyro_offset(&gyro_offset
);
4696 /* Write offset data in the gyroscope offset
4697 * compensation register
4699 rslt
= bmi2_write_gyro_offset_comp_axes(&gyro_offset
, dev
);
4702 /* Enable gyroscope offset compensation */
4703 if (rslt
== BMI2_OK
)
4705 rslt
= bmi2_set_gyro_offset_comp(BMI2_ENABLE
, dev
);
4708 /* Restore the saved gyroscope configurations */
4709 if (rslt
== BMI2_OK
)
4711 rslt
= restore_gyro_config(&gyr_cfg
, aps
, gyr_en
, dev
);
4721 * @brief This API is used to get the feature configuration from the
4724 int8_t bmi2_get_feat_config(uint8_t sw_page
, uint8_t *feat_config
, struct bmi2_dev
*dev
)
4726 /* Variable to define error */
4729 /* Variable to define bytes remaining to read */
4730 uint8_t bytes_remain
= BMI2_FEAT_SIZE_IN_BYTES
;
4732 /* Variable to define the read-write length */
4733 uint8_t read_write_len
= 0;
4735 /* Variable to define the feature configuration address */
4736 uint8_t addr
= BMI2_FEATURES_REG_ADDR
;
4738 /* Variable to define index */
4741 if ((feat_config
== NULL
) || (dev
== NULL
))
4743 rslt
= BMI2_E_NULL_PTR
;
4747 /* Check whether the page is valid */
4748 if (sw_page
< dev
->page_max
)
4751 rslt
= bmi2_set_regs(BMI2_FEAT_PAGE_ADDR
, &sw_page
, 1, dev
);
4753 /* If user length is less than feature length */
4754 if ((rslt
== BMI2_OK
) && (dev
->read_write_len
< BMI2_FEAT_SIZE_IN_BYTES
))
4756 /* Read-write should be even */
4757 if ((dev
->read_write_len
% 2) != 0)
4759 dev
->read_write_len
--;
4762 while (bytes_remain
> 0)
4764 if (bytes_remain
>= dev
->read_write_len
)
4766 /* Read from the page */
4767 rslt
= bmi2_get_regs(addr
, &feat_config
[index
], dev
->read_write_len
, dev
);
4770 index
+= (uint8_t) dev
->read_write_len
;
4772 /* Update address */
4773 addr
+= (uint8_t) dev
->read_write_len
;
4775 /* Update read-write length */
4776 read_write_len
+= (uint8_t) dev
->read_write_len
;
4780 /* Read from the page */
4781 rslt
= bmi2_get_regs(addr
, (uint8_t *) (feat_config
+ index
), (uint16_t) bytes_remain
, dev
);
4783 /* Update read-write length */
4784 read_write_len
+= bytes_remain
;
4787 /* Remaining bytes */
4788 bytes_remain
= BMI2_FEAT_SIZE_IN_BYTES
- read_write_len
;
4790 if (rslt
!= BMI2_OK
)
4796 else if (rslt
== BMI2_OK
)
4798 /* Get configuration from the page */
4799 rslt
= bmi2_get_regs(BMI2_FEATURES_REG_ADDR
, feat_config
, BMI2_FEAT_SIZE_IN_BYTES
, dev
);
4804 rslt
= BMI2_E_INVALID_PAGE
;
4812 * @brief This API is used to extract the input feature configuration
4813 * details from the look-up table.
4815 uint8_t bmi2_extract_input_feat_config(struct bmi2_feature_config
*feat_config
, uint8_t type
,
4816 const struct bmi2_dev
*dev
)
4818 /* Variable to define loop */
4821 /* Variable to set flag */
4822 uint8_t feat_found
= BMI2_FALSE
;
4824 /* Search for the input feature from the input configuration array */
4825 while (loop
< dev
->input_sens
)
4827 if (dev
->feat_config
[loop
].type
== type
)
4829 *feat_config
= dev
->feat_config
[loop
];
4830 feat_found
= BMI2_TRUE
;
4841 /***************************************************************************/
4843 /*! Local Function Definitions
4844 ****************************************************************************/
4846 /*! @cond DOXYGEN_SUPRESS */
4848 /* Suppressing doxygen warnings triggered for same static function names present across various sensor variant
4852 * @brief This internal API writes the configuration file.
4854 static int8_t write_config_file(struct bmi2_dev
*dev
)
4856 /* Variable to define error */
4859 /* Variable to update the configuration file index */
4862 /* config file size */
4863 uint16_t config_size
= dev
->config_size
;
4865 /* Variable to get the remainder */
4866 uint8_t remain
= (uint8_t)(config_size
% dev
->read_write_len
);
4868 /* Variable to get the balance bytes */
4869 uint16_t bal_byte
= 0;
4871 /* Variable to define temporary read/write length */
4872 uint16_t read_write_len
= 0;
4874 /* Disable advanced power save mode */
4875 rslt
= bmi2_set_adv_power_save(BMI2_DISABLE
, dev
);
4876 if (rslt
== BMI2_OK
)
4878 /* Disable loading of the configuration */
4879 rslt
= set_config_load(BMI2_DISABLE
, dev
);
4880 if (rslt
== BMI2_OK
)
4884 /* Write the configuration file */
4885 for (index
= 0; (index
< config_size
) && (rslt
== BMI2_OK
); index
+= dev
->read_write_len
)
4887 rslt
= upload_file((dev
->config_file_ptr
+ index
), index
, dev
->read_write_len
, dev
);
4892 /* Get the balance bytes */
4893 bal_byte
= (uint16_t) config_size
- (uint16_t) remain
;
4895 /* Write the configuration file for the balancem bytes */
4896 for (index
= 0; (index
< bal_byte
) && (rslt
== BMI2_OK
); index
+= dev
->read_write_len
)
4898 rslt
= upload_file((dev
->config_file_ptr
+ index
), index
, dev
->read_write_len
, dev
);
4901 if (rslt
== BMI2_OK
)
4903 /* Update length in a temporary variable */
4904 read_write_len
= dev
->read_write_len
;
4906 /* Write the remaining bytes in 2 bytes length */
4907 dev
->read_write_len
= 2;
4909 /* Write the configuration file for the remaining bytes */
4910 for (index
= bal_byte
;
4911 (index
< config_size
) && (rslt
== BMI2_OK
);
4912 index
+= dev
->read_write_len
)
4914 rslt
= upload_file((dev
->config_file_ptr
+ index
), index
, dev
->read_write_len
, dev
);
4917 /* Restore the user set length back from the temporary variable */
4918 dev
->read_write_len
= read_write_len
;
4922 if (rslt
== BMI2_OK
)
4924 /* Enable loading of the configuration */
4925 rslt
= set_config_load(BMI2_ENABLE
, dev
);
4927 /* Wait till ASIC is initialized */
4928 dev
->delay_us(150000, dev
->intf_ptr
);
4929 if (rslt
== BMI2_OK
)
4931 /* Enable advanced power save mode */
4932 rslt
= bmi2_set_adv_power_save(BMI2_ENABLE
, dev
);
4942 * @brief This internal API enables/disables the loading of the configuration
4945 static int8_t set_config_load(uint8_t enable
, struct bmi2_dev
*dev
)
4947 /* Variable to define error */
4950 /* Variable to store data */
4951 uint8_t reg_data
= 0;
4953 rslt
= bmi2_get_regs(BMI2_INIT_CTRL_ADDR
, ®_data
, 1, dev
);
4954 if (rslt
== BMI2_OK
)
4956 reg_data
= BMI2_SET_BIT_POS0(reg_data
, BMI2_CONF_LOAD_EN
, enable
);
4957 rslt
= bmi2_set_regs(BMI2_INIT_CTRL_ADDR
, ®_data
, 1, dev
);
4964 * @brief This internal API loads the configuration file.
4966 static int8_t upload_file(const uint8_t *config_data
, uint16_t index
, uint16_t write_len
, struct bmi2_dev
*dev
)
4968 /* Variable to define error */
4971 /* Array to store address */
4972 uint8_t addr_array
[2] = { 0 };
4974 if (config_data
!= NULL
)
4976 /* Store 0 to 3 bits of address in first byte */
4977 addr_array
[0] = (uint8_t)((index
/ 2) & 0x0F);
4979 /* Store 4 to 11 bits of address in the second byte */
4980 addr_array
[1] = (uint8_t)((index
/ 2) >> 4);
4982 /* Write the 2 bytes of address in consecutive locations */
4983 rslt
= bmi2_set_regs(BMI2_INIT_ADDR_0
, addr_array
, 2, dev
);
4984 if (rslt
== BMI2_OK
)
4986 /* Burst write configuration file data corresponding to user set length */
4987 rslt
= bmi2_set_regs(BMI2_INIT_DATA_ADDR
, (uint8_t *)config_data
, write_len
, dev
);
4992 rslt
= BMI2_E_NULL_PTR
;
4999 * @brief This internal API validates bandwidth and performance mode of the
5000 * accelerometer set by the user.
5002 static int8_t validate_bw_perf_mode(uint8_t *bandwidth
, uint8_t *perf_mode
, struct bmi2_dev
*dev
)
5004 /* Variable to define error */
5007 /* Validate and auto-correct performance mode */
5008 rslt
= check_boundary_val(perf_mode
, BMI2_POWER_OPT_MODE
, BMI2_PERF_OPT_MODE
, dev
);
5009 if (rslt
== BMI2_OK
)
5011 /* Validate and auto-correct bandwidth parameter */
5012 if (*perf_mode
== BMI2_PERF_OPT_MODE
)
5014 /* Validate for continuous filter mode */
5015 rslt
= check_boundary_val(bandwidth
, BMI2_ACC_OSR4_AVG1
, BMI2_ACC_CIC_AVG8
, dev
);
5019 /* Validate for CIC averaging mode */
5020 rslt
= check_boundary_val(bandwidth
, BMI2_ACC_OSR4_AVG1
, BMI2_ACC_RES_AVG128
, dev
);
5028 * @brief This internal API validates ODR and range of the accelerometer set by
5031 static int8_t validate_odr_range(uint8_t *odr
, uint8_t *range
, struct bmi2_dev
*dev
)
5033 /* Variable to define error */
5036 /* Validate and auto correct ODR */
5037 rslt
= check_boundary_val(odr
, BMI2_ACC_ODR_0_78HZ
, BMI2_ACC_ODR_1600HZ
, dev
);
5038 if (rslt
== BMI2_OK
)
5040 /* Validate and auto correct Range */
5041 rslt
= check_boundary_val(range
, BMI2_ACC_RANGE_2G
, BMI2_ACC_RANGE_16G
, dev
);
5048 * @brief This internal API validates bandwidth, performance mode, low power/
5049 * high performance mode, ODR, and range set by the user.
5051 static int8_t validate_gyro_config(struct bmi2_gyro_config
*config
, struct bmi2_dev
*dev
)
5053 /* Variable to define error */
5056 /* Validate and auto-correct performance mode */
5057 rslt
= check_boundary_val(&config
->filter_perf
, BMI2_POWER_OPT_MODE
, BMI2_PERF_OPT_MODE
, dev
);
5058 if (rslt
== BMI2_OK
)
5060 /* Validate and auto-correct bandwidth parameter */
5061 rslt
= check_boundary_val(&config
->bwp
, BMI2_GYR_OSR4_MODE
, BMI2_GYR_CIC_MODE
, dev
);
5062 if (rslt
== BMI2_OK
)
5064 /* Validate and auto-correct low power/high-performance parameter */
5065 rslt
= check_boundary_val(&config
->noise_perf
, BMI2_POWER_OPT_MODE
, BMI2_PERF_OPT_MODE
, dev
);
5066 if (rslt
== BMI2_OK
)
5068 /* Validate and auto-correct ODR parameter */
5069 rslt
= check_boundary_val(&config
->odr
, BMI2_GYR_ODR_25HZ
, BMI2_GYR_ODR_3200HZ
, dev
);
5070 if (rslt
== BMI2_OK
)
5072 /* Validate and auto-correct OIS range */
5073 rslt
= check_boundary_val(&config
->ois_range
, BMI2_GYR_OIS_250
, BMI2_GYR_OIS_2000
, dev
);
5074 if (rslt
== BMI2_OK
)
5076 /* Validate and auto-correct range parameter */
5077 rslt
= check_boundary_val(&config
->range
, BMI2_GYR_RANGE_2000
, BMI2_GYR_RANGE_125
, dev
);
5088 * @brief This internal API shows the error status when illegal sensor
5089 * configuration is set.
5091 static int8_t cfg_error_status(struct bmi2_dev
*dev
)
5093 /* Variable to define error */
5096 /* Variable to store data */
5099 /* Get error status of the set sensor configuration */
5100 rslt
= bmi2_get_regs(BMI2_EVENT_ADDR
, ®_data
, 1, dev
);
5101 if (rslt
== BMI2_OK
)
5103 reg_data
= BMI2_GET_BITS(reg_data
, BMI2_EVENT_FLAG
);
5109 case BMI2_ACC_ERROR
:
5110 rslt
= BMI2_E_ACC_INVALID_CFG
;
5112 case BMI2_GYR_ERROR
:
5113 rslt
= BMI2_E_GYRO_INVALID_CFG
;
5115 case BMI2_ACC_GYR_ERROR
:
5116 rslt
= BMI2_E_ACC_GYR_INVALID_CFG
;
5127 * @brief This internal API:
5128 * 1) Enables/Disables auxiliary interface.
5129 * 2) Sets auxiliary interface configurations like I2C address, manual/auto
5130 * mode enable, manual burst read length, AUX burst read length and AUX read
5132 * 3)It maps/un-maps data interrupts to that of hardware interrupt line.
5134 static int8_t set_aux_config(struct bmi2_aux_config
*config
, struct bmi2_dev
*dev
)
5136 /* Variable to define error */
5139 /* Validate auxiliary configurations */
5140 rslt
= validate_aux_config(config
, dev
);
5141 if (rslt
== BMI2_OK
)
5143 /* Enable/Disable auxiliary interface */
5144 rslt
= set_aux_interface(config
, dev
);
5145 if (rslt
== BMI2_OK
)
5147 /* Set the auxiliary interface configurations */
5148 rslt
= config_aux_interface(config
, dev
);
5149 if (rslt
== BMI2_OK
)
5151 /* Set read out offset and ODR */
5152 rslt
= config_aux(config
, dev
);
5161 * @brief This internal API sets gyroscope user-gain configurations like gain
5162 * update value for x, y and z-axis.
5164 static int8_t set_gyro_user_gain_config(const struct bmi2_gyro_user_gain_config
*config
, struct bmi2_dev
*dev
)
5166 /* Variable to define error */
5169 /* Array to define the feature configuration */
5170 uint8_t feat_config
[BMI2_FEAT_SIZE_IN_BYTES
] = { 0 };
5172 /* Variable to define the array offset */
5175 /* Variable to define index */
5178 /* Variable to set flag */
5181 /* Initialize feature configuration for user-gain */
5182 struct bmi2_feature_config user_gain_config
= { 0, 0, 0 };
5184 /* Copy the feature configuration address to a local pointer */
5185 uint16_t *data_p
= (uint16_t *) (void *)feat_config
;
5187 /* Search for user-gain feature and extract its configuration details */
5188 feat_found
= bmi2_extract_input_feat_config(&user_gain_config
, BMI2_GYRO_GAIN_UPDATE
, dev
);
5191 /* Get the configuration from the page where user-gain feature resides */
5192 rslt
= bmi2_get_feat_config(user_gain_config
.page
, feat_config
, dev
);
5193 if (rslt
== BMI2_OK
)
5195 /* Define the offset in bytes for user-gain select */
5196 idx
= user_gain_config
.start_addr
;
5198 /* Get offset in words since all the features are set in words length */
5202 *(data_p
+ idx
) = BMI2_SET_BIT_POS0(*(data_p
+ idx
), BMI2_GYR_USER_GAIN_RATIO_X
, config
->ratio_x
);
5204 /* Increment offset by 1 word to set ratio_y */
5208 *(data_p
+ idx
) = BMI2_SET_BIT_POS0(*(data_p
+ idx
), BMI2_GYR_USER_GAIN_RATIO_Y
, config
->ratio_y
);
5210 /* Increment offset by 1 word to set ratio_z */
5214 *(data_p
+ idx
) = BMI2_SET_BIT_POS0(*(data_p
+ idx
), BMI2_GYR_USER_GAIN_RATIO_Z
, config
->ratio_z
);
5216 /* Increment offset by 1 more word to get the total length in words */
5219 /* Get total length in bytes to copy from local pointer to the array */
5220 idx
= (uint8_t)(idx
* 2) - user_gain_config
.start_addr
;
5222 /* Copy the bytes to be set back to the array */
5223 for (index
= 0; index
< idx
; index
++)
5225 feat_config
[user_gain_config
.start_addr
+
5226 index
] = *((uint8_t *) data_p
+ user_gain_config
.start_addr
+ index
);
5229 /* Set the configuration back to the page */
5230 rslt
= bmi2_set_regs(BMI2_FEATURES_REG_ADDR
, feat_config
, BMI2_FEAT_SIZE_IN_BYTES
, dev
);
5235 rslt
= BMI2_E_INVALID_SENSOR
;
5242 * @brief This internal API enables/disables auxiliary interface.
5244 static int8_t set_aux_interface(const struct bmi2_aux_config
*config
, struct bmi2_dev
*dev
)
5246 /* Variable to define error */
5249 /* Variable to store data */
5252 rslt
= bmi2_get_regs(BMI2_IF_CONF_ADDR
, ®_data
, 1, dev
);
5253 if (rslt
== BMI2_OK
)
5255 reg_data
= BMI2_SET_BITS(reg_data
, BMI2_AUX_IF_EN
, config
->aux_en
);
5257 /* Enable/Disable auxiliary interface */
5258 rslt
= bmi2_set_regs(BMI2_IF_CONF_ADDR
, ®_data
, 1, dev
);
5265 * @brief This internal API sets auxiliary configurations like manual/auto mode
5266 * FCU write command enable and read burst length for both data and manual mode.
5268 * @note Auxiliary sensor should not be busy when configuring aux_i2c_addr,
5269 * man_rd_burst_len, aux_rd_burst_len and aux_rd_addr.
5271 static int8_t config_aux_interface(const struct bmi2_aux_config
*config
, struct bmi2_dev
*dev
)
5273 /* Variable to define error */
5276 /* Variable to store data */
5277 uint8_t reg_data
[2] = { 0 };
5279 /* Variable to store status */
5282 /* Variable to define count */
5285 rslt
= bmi2_get_regs(BMI2_AUX_DEV_ID_ADDR
, reg_data
, 2, dev
);
5286 if (rslt
== BMI2_OK
)
5288 /* Set I2C address for AUX sensor */
5289 reg_data
[0] = BMI2_SET_BITS(reg_data
[0], BMI2_AUX_SET_I2C_ADDR
, config
->i2c_device_addr
);
5291 /* Set the AUX IF to either manual or auto mode */
5292 reg_data
[1] = BMI2_SET_BITS(reg_data
[1], BMI2_AUX_MAN_MODE_EN
, config
->manual_en
);
5294 /* Enables FCU write command on AUX IF for auxiliary sensors that need a trigger */
5295 reg_data
[1] = BMI2_SET_BITS(reg_data
[1], BMI2_AUX_FCU_WR_EN
, config
->fcu_write_en
);
5297 /* Set the burst read length for manual mode */
5298 reg_data
[1] = BMI2_SET_BITS(reg_data
[1], BMI2_AUX_MAN_READ_BURST
, config
->man_rd_burst
);
5300 /* Set the burst read length for data mode */
5301 reg_data
[1] = BMI2_SET_BIT_POS0(reg_data
[1], BMI2_AUX_READ_BURST
, config
->aux_rd_burst
);
5304 /* Check if auxiliary sensor is busy */
5305 rslt
= bmi2_get_status(&status
, dev
);
5306 if ((rslt
== BMI2_OK
) && (!(status
& BMI2_AUX_BUSY
)))
5308 /* Set the configurations if AUX is not busy */
5309 rslt
= bmi2_set_regs(BMI2_AUX_DEV_ID_ADDR
, reg_data
, 2, dev
);
5310 dev
->delay_us(1000, dev
->intf_ptr
);
5311 if (rslt
== BMI2_OK
)
5314 if (!config
->manual_en
)
5316 /* Disable manual enable flag in device structure */
5317 dev
->aux_man_en
= 0;
5319 /* Set the read address of the AUX sensor */
5320 rslt
= bmi2_set_regs(BMI2_AUX_RD_ADDR
, (uint8_t *) &config
->read_addr
, 1, dev
);
5321 dev
->delay_us(1000, dev
->intf_ptr
);
5325 /* Enable manual enable flag in device structure */
5326 dev
->aux_man_en
= 1;
5328 /* Update manual read burst length in device structure */
5329 dev
->aux_man_rd_burst_len
= config
->man_rd_burst
;
5333 /* Break after setting the register */
5337 /* Increment count after every 10 seconds */
5338 dev
->delay_us(10000, dev
->intf_ptr
);
5341 /* Break after 2 seconds if AUX still busy - since slowest ODR is 0.78Hz*/
5344 rslt
= BMI2_E_AUX_BUSY
;
5354 * @brief This internal API triggers read out offset and sets ODR of the
5357 static int8_t config_aux(const struct bmi2_aux_config
*config
, struct bmi2_dev
*dev
)
5359 /* Variable to define error */
5362 /* Variable to store data */
5365 rslt
= bmi2_get_regs(BMI2_AUX_CONF_ADDR
, ®_data
, 1, dev
);
5366 if (rslt
== BMI2_OK
)
5368 /* Trigger read out offset */
5369 reg_data
= BMI2_SET_BITS(reg_data
, BMI2_AUX_OFFSET_READ_OUT
, config
->offset
);
5372 reg_data
= BMI2_SET_BIT_POS0(reg_data
, BMI2_AUX_ODR_EN
, config
->odr
);
5374 /* Set auxiliary configuration register */
5375 rslt
= bmi2_set_regs(BMI2_AUX_CONF_ADDR
, ®_data
, 1, dev
);
5376 dev
->delay_us(1000, dev
->intf_ptr
);
5383 * @brief This internal API checks the busy status of auxiliary sensor and sets
5384 * the auxiliary register addresses when not busy.
5386 static int8_t set_if_aux_not_busy(uint8_t reg_addr
, uint8_t reg_data
, struct bmi2_dev
*dev
)
5388 /* Variable to define error */
5391 /* Variable to get status of AUX_BUSY */
5394 /* Variable to define count for time-out */
5399 /* Check if AUX is busy */
5400 rslt
= bmi2_get_status(&status
, dev
);
5402 /* Set the registers if not busy */
5403 if ((rslt
== BMI2_OK
) && (!(status
& BMI2_AUX_BUSY
)))
5405 rslt
= bmi2_set_regs(reg_addr
, ®_data
, 1, dev
);
5406 dev
->delay_us(1000, dev
->intf_ptr
);
5408 /* Break after setting the register */
5412 /* Increment count after every 10 seconds */
5413 dev
->delay_us(10000, dev
->intf_ptr
);
5416 /* Break after 2 seconds if AUX still busy - since slowest ODR is 0.78Hz*/
5419 rslt
= BMI2_E_AUX_BUSY
;
5428 * @brief This internal API validates auxiliary configuration set by the user.
5430 static int8_t validate_aux_config(struct bmi2_aux_config
*config
, struct bmi2_dev
*dev
)
5432 /* Variable to define error */
5435 /* Validate ODR for auxiliary sensor */
5436 rslt
= check_boundary_val(&config
->odr
, BMI2_AUX_ODR_0_78HZ
, BMI2_AUX_ODR_800HZ
, dev
);
5442 * @brief This internal API gets accelerometer configurations like ODR,
5443 * bandwidth, performance mode and g-range.
5445 static int8_t get_accel_config(struct bmi2_accel_config
*config
, struct bmi2_dev
*dev
)
5447 /* Variable to define error */
5450 /* Array to store data */
5451 uint8_t data_array
[2] = { 0 };
5453 /* Null-pointer check */
5454 rslt
= null_ptr_check(dev
);
5455 if ((rslt
== BMI2_OK
) && (config
!= NULL
))
5457 /* Read the sensor configuration details */
5458 rslt
= bmi2_get_regs(BMI2_ACC_CONF_ADDR
, data_array
, 2, dev
);
5459 if (rslt
== BMI2_OK
)
5461 /* Get accelerometer performance mode */
5462 config
->filter_perf
= BMI2_GET_BITS(data_array
[0], BMI2_ACC_FILTER_PERF_MODE
);
5464 /* Get accelerometer bandwidth */
5465 config
->bwp
= BMI2_GET_BITS(data_array
[0], BMI2_ACC_BW_PARAM
);
5467 /* Get accelerometer ODR */
5468 config
->odr
= BMI2_GET_BIT_POS0(data_array
[0], BMI2_ACC_ODR
);
5470 /* Get accelerometer range */
5471 config
->range
= BMI2_GET_BIT_POS0(data_array
[1], BMI2_ACC_RANGE
);
5476 rslt
= BMI2_E_NULL_PTR
;
5483 * @brief This internal API gets gyroscope configurations like ODR, bandwidth,
5484 * low power/high performance mode, performance mode and range.
5486 static int8_t get_gyro_config(struct bmi2_gyro_config
*config
, struct bmi2_dev
*dev
)
5488 /* Variable to define error */
5491 /* Array to store data */
5492 uint8_t data_array
[2] = { 0 };
5494 /* Null-pointer check */
5495 rslt
= null_ptr_check(dev
);
5496 if ((rslt
== BMI2_OK
) && (config
!= NULL
))
5498 /* Read the sensor configuration details */
5499 rslt
= bmi2_get_regs(BMI2_GYR_CONF_ADDR
, data_array
, 2, dev
);
5500 if (rslt
== BMI2_OK
)
5502 /* Get gyroscope performance mode */
5503 config
->filter_perf
= BMI2_GET_BITS(data_array
[0], BMI2_GYR_FILTER_PERF_MODE
);
5505 /* Get gyroscope noise performance mode */
5506 config
->noise_perf
= BMI2_GET_BITS(data_array
[0], BMI2_GYR_NOISE_PERF_MODE
);
5508 /* Get gyroscope bandwidth */
5509 config
->bwp
= BMI2_GET_BITS(data_array
[0], BMI2_GYR_BW_PARAM
);
5511 /* Get gyroscope ODR */
5512 config
->odr
= BMI2_GET_BIT_POS0(data_array
[0], BMI2_GYR_ODR
);
5514 /* Get gyroscope OIS range */
5515 config
->ois_range
= BMI2_GET_BITS(data_array
[1], BMI2_GYR_OIS_RANGE
);
5517 /* Get gyroscope range */
5518 config
->range
= BMI2_GET_BIT_POS0(data_array
[1], BMI2_GYR_RANGE
);
5523 rslt
= BMI2_E_NULL_PTR
;
5530 * @brief This internal API:
5531 * 1) Gets the status of auxiliary interface enable.
5532 * 2) Gets auxiliary interface configurations like I2C address, manual/auto
5533 * mode enable, manual burst read length, AUX burst read length and AUX read
5535 * 3) Gets ODR and offset.
5537 static int8_t get_aux_config(struct bmi2_aux_config
*config
, struct bmi2_dev
*dev
)
5539 /* Variable to define error */
5542 /* Null-pointer check */
5543 rslt
= null_ptr_check(dev
);
5544 if ((rslt
== BMI2_OK
) && (config
!= NULL
))
5546 /* Get enable status of auxiliary interface */
5547 rslt
= get_aux_interface(config
, dev
);
5548 if (rslt
== BMI2_OK
)
5550 /* Get the auxiliary interface configurations */
5551 rslt
= get_aux_interface_config(config
, dev
);
5552 if (rslt
== BMI2_OK
)
5554 /* Get read out offset and ODR */
5555 rslt
= get_aux_cfg(config
, dev
);
5561 rslt
= BMI2_E_NULL_PTR
;
5568 * @brief This internal API gets gyroscope user-gain configurations like gain
5569 * update value for x, y and z-axis.
5571 static int8_t get_gyro_gain_update_config(struct bmi2_gyro_user_gain_config
*config
, struct bmi2_dev
*dev
)
5573 /* Variable to define error */
5576 /* Array to define the feature configuration */
5577 uint8_t feat_config
[BMI2_FEAT_SIZE_IN_BYTES
] = { 0 };
5579 /* Variable to define the array offset */
5582 /* Variable to define LSB */
5585 /* Variable to define MSB */
5588 /* Variable to define a word */
5589 uint16_t lsb_msb
= 0;
5591 /* Variable to set flag */
5594 /* Initialize feature configuration for user-gain */
5595 struct bmi2_feature_config user_gain_config
= { 0, 0, 0 };
5597 /* Search for user-gain feature and extract its configuration details */
5598 feat_found
= bmi2_extract_input_feat_config(&user_gain_config
, BMI2_GYRO_GAIN_UPDATE
, dev
);
5601 /* Get the configuration from the page where user-gain feature resides */
5602 rslt
= bmi2_get_feat_config(user_gain_config
.page
, feat_config
, dev
);
5603 if (rslt
== BMI2_OK
)
5605 /* Define the offset in bytes for user-gain select */
5606 idx
= user_gain_config
.start_addr
;
5608 /* Get word to calculate ratio_x */
5609 lsb
= (uint16_t) feat_config
[idx
++];
5610 msb
= ((uint16_t) feat_config
[idx
++] << 8);
5611 lsb_msb
= lsb
| msb
;
5614 config
->ratio_x
= lsb_msb
& BMI2_GYR_USER_GAIN_RATIO_X_MASK
;
5616 /* Get word to calculate ratio_y */
5617 lsb
= (uint16_t) feat_config
[idx
++];
5618 msb
= ((uint16_t) feat_config
[idx
++] << 8);
5619 lsb_msb
= lsb
| msb
;
5622 config
->ratio_y
= lsb_msb
& BMI2_GYR_USER_GAIN_RATIO_Y_MASK
;
5624 /* Get word to calculate ratio_z */
5625 lsb
= (uint16_t) feat_config
[idx
++];
5626 msb
= ((uint16_t) feat_config
[idx
++] << 8);
5627 lsb_msb
= lsb
| msb
;
5630 config
->ratio_z
= lsb_msb
& BMI2_GYR_USER_GAIN_RATIO_Z_MASK
;
5635 rslt
= BMI2_E_INVALID_SENSOR
;
5642 * @brief This internal API gets the enable status of auxiliary interface.
5644 static int8_t get_aux_interface(struct bmi2_aux_config
*config
, struct bmi2_dev
*dev
)
5646 /* Variable to define error */
5649 /* Variable to store data */
5652 /* Get the enable status of auxiliary interface */
5653 rslt
= bmi2_get_regs(BMI2_IF_CONF_ADDR
, ®_data
, 1, dev
);
5654 if (rslt
== BMI2_OK
)
5656 config
->aux_en
= BMI2_GET_BITS(reg_data
, BMI2_AUX_IF_EN
);
5663 * @brief This internal API gets auxiliary configurations like manual/auto mode
5664 * FCU write command enable and read burst length for both data and manual mode.
5666 static int8_t get_aux_interface_config(struct bmi2_aux_config
*config
, struct bmi2_dev
*dev
)
5668 /* Variable to define error */
5671 /* Variable to store data */
5672 uint8_t reg_data
[2] = { 0 };
5674 rslt
= bmi2_get_regs(BMI2_AUX_DEV_ID_ADDR
, reg_data
, 2, dev
);
5675 if (rslt
== BMI2_OK
)
5677 /* Get I2C address for auxiliary sensor */
5678 config
->i2c_device_addr
= BMI2_GET_BITS(reg_data
[0], BMI2_AUX_SET_I2C_ADDR
);
5680 /* Get the AUX IF to either manual or auto mode */
5681 config
->manual_en
= BMI2_GET_BITS(reg_data
[1], BMI2_AUX_MAN_MODE_EN
);
5683 /* Enables FCU write command on AUX IF for auxiliary sensors that need a trigger */
5684 config
->fcu_write_en
= BMI2_GET_BITS(reg_data
[1], BMI2_AUX_FCU_WR_EN
);
5686 /* Get the burst read length for manual mode */
5687 config
->man_rd_burst
= BMI2_GET_BITS(reg_data
[1], BMI2_AUX_MAN_READ_BURST
);
5689 /* Get the burst read length for data mode */
5690 config
->aux_rd_burst
= BMI2_GET_BIT_POS0(reg_data
[1], BMI2_AUX_READ_BURST
);
5692 /* If data mode, get the read address of the auxiliary sensor from where data is to be read */
5693 if (!config
->manual_en
)
5695 rslt
= bmi2_get_regs(BMI2_AUX_RD_ADDR
, &config
->read_addr
, 1, dev
);
5703 * @brief This internal API gets read out offset and ODR of the auxiliary
5706 static int8_t get_aux_cfg(struct bmi2_aux_config
*config
, struct bmi2_dev
*dev
)
5708 /* Variable to define error */
5711 /* Variable to store data */
5714 rslt
= bmi2_get_regs(BMI2_AUX_CONF_ADDR
, ®_data
, 1, dev
);
5715 if (rslt
== BMI2_OK
)
5717 /* Get read out offset */
5718 config
->offset
= BMI2_GET_BITS(reg_data
, BMI2_AUX_OFFSET_READ_OUT
);
5721 config
->odr
= BMI2_GET_BIT_POS0(reg_data
, BMI2_AUX_ODR_EN
);
5728 * @brief This internal API maps/un-maps feature interrupts to that of interrupt
5731 static int8_t map_feat_int(uint8_t *reg_data_array
, enum bmi2_hw_int_pin int_pin
, uint8_t int_mask
)
5733 /* Variable to define error */
5734 int8_t rslt
= BMI2_OK
;
5736 /* Check for NULL error */
5737 if (reg_data_array
!= NULL
)
5739 /* Check validity on interrupt pin selection */
5740 if (int_pin
< BMI2_INT_PIN_MAX
)
5746 /* Un-Map the corresponding feature interrupt to interrupt pin 1 and 2 */
5747 reg_data_array
[0] &= ~(int_mask
);
5748 reg_data_array
[1] &= ~(int_mask
);
5752 /* Map the corresponding feature interrupt to interrupt pin 1 */
5753 reg_data_array
[0] |= int_mask
;
5755 /* Un-map the corresponding feature interrupt to interrupt pin 2 */
5756 reg_data_array
[1] &= ~(int_mask
);
5760 /* Map the corresponding feature interrupt to interrupt pin 2 */
5761 reg_data_array
[1] |= int_mask
;
5763 /* Un-map the corresponding feature interrupt to interrupt pin 1 */
5764 reg_data_array
[0] &= ~(int_mask
);
5768 /* Map the corresponding feature interrupt to interrupt pin 1 and 2 */
5769 reg_data_array
[0] |= int_mask
;
5770 reg_data_array
[1] |= int_mask
;
5778 /* Return error if invalid pin selection */
5779 rslt
= BMI2_E_INVALID_INT_PIN
;
5784 rslt
= BMI2_E_NULL_PTR
;
5791 * @brief This internal API gets the accelerometer data from the register.
5793 static int8_t get_accel_sensor_data(struct bmi2_sens_axes_data
*data
, uint8_t reg_addr
, struct bmi2_dev
*dev
)
5795 /* Variable to define error */
5798 /* Array to define data stored in register */
5799 uint8_t reg_data
[BMI2_ACC_GYR_NUM_BYTES
] = { 0 };
5801 /* Read the sensor data */
5802 rslt
= bmi2_get_regs(reg_addr
, reg_data
, BMI2_ACC_GYR_NUM_BYTES
, dev
);
5803 if (rslt
== BMI2_OK
)
5805 /* Get accelerometer data from the register */
5806 get_acc_gyr_data(data
, reg_data
);
5808 /* Get the re-mapped accelerometer data */
5809 get_remapped_data(data
, dev
);
5816 * @brief This internal API gets the gyroscope data from the register.
5818 static int8_t get_gyro_sensor_data(struct bmi2_sens_axes_data
*data
, uint8_t reg_addr
, struct bmi2_dev
*dev
)
5820 /* Variable to define error */
5823 /* Array to define data stored in register */
5824 uint8_t reg_data
[BMI2_ACC_GYR_NUM_BYTES
] = { 0 };
5826 /* Read the sensor data */
5827 rslt
= bmi2_get_regs(reg_addr
, reg_data
, BMI2_ACC_GYR_NUM_BYTES
, dev
);
5828 if (rslt
== BMI2_OK
)
5830 /* Get gyroscope data from the register */
5831 get_acc_gyr_data(data
, reg_data
);
5833 /* Get the compensated gyroscope data */
5834 comp_gyro_cross_axis_sensitivity(data
, dev
);
5836 /* Get the re-mapped gyroscope data */
5837 get_remapped_data(data
, dev
);
5845 * @brief This internal API gets the accelerometer/gyroscope data.
5847 static void get_acc_gyr_data(struct bmi2_sens_axes_data
*data
, const uint8_t *reg_data
)
5849 /* Variables to store msb value */
5852 /* Variables to store lsb value */
5855 /* Variables to store both msb and lsb value */
5858 /* Variables to define index */
5861 /* Read x-axis data */
5862 lsb
= reg_data
[index
++];
5863 msb
= reg_data
[index
++];
5864 msb_lsb
= ((uint16_t) msb
<< 8) | (uint16_t) lsb
;
5865 data
->x
= (int16_t) msb_lsb
;
5867 /* Read y-axis data */
5868 lsb
= reg_data
[index
++];
5869 msb
= reg_data
[index
++];
5870 msb_lsb
= ((uint16_t) msb
<< 8) | (uint16_t) lsb
;
5871 data
->y
= (int16_t) msb_lsb
;
5873 /* Read z-axis data */
5874 lsb
= reg_data
[index
++];
5875 msb
= reg_data
[index
++];
5876 msb_lsb
= ((uint16_t) msb
<< 8) | (uint16_t) lsb
;
5877 data
->z
= (int16_t) msb_lsb
;
5881 * @brief This internal API gets the re-mapped accelerometer/gyroscope data.
5883 static void get_remapped_data(struct bmi2_sens_axes_data
*data
, const struct bmi2_dev
*dev
)
5885 /* Array to defined the re-mapped sensor data */
5886 int16_t remap_data
[3] = { 0 };
5887 int16_t pos_multiplier
= INT16_C(1);
5888 int16_t neg_multiplier
= INT16_C(-1);
5890 /* Fill the array with the un-mapped sensor data */
5891 remap_data
[0] = data
->x
;
5892 remap_data
[1] = data
->y
;
5893 remap_data
[2] = data
->z
;
5895 /* Get the re-mapped x axis data */
5896 if (dev
->remap
.x_axis_sign
== BMI2_POS_SIGN
)
5898 data
->x
= (int16_t)(remap_data
[dev
->remap
.x_axis
] * pos_multiplier
);
5902 data
->x
= (int16_t)(remap_data
[dev
->remap
.x_axis
] * neg_multiplier
);
5905 /* Get the re-mapped y axis data */
5906 if (dev
->remap
.y_axis_sign
== BMI2_POS_SIGN
)
5908 data
->y
= (int16_t)(remap_data
[dev
->remap
.y_axis
] * pos_multiplier
);
5912 data
->y
= (int16_t)(remap_data
[dev
->remap
.y_axis
] * neg_multiplier
);
5915 /* Get the re-mapped z axis data */
5916 if (dev
->remap
.z_axis_sign
== BMI2_POS_SIGN
)
5918 data
->z
= (int16_t)(remap_data
[dev
->remap
.z_axis
] * pos_multiplier
);
5922 data
->z
= (int16_t)(remap_data
[dev
->remap
.z_axis
] * neg_multiplier
);
5927 * @brief This internal API reads the user-defined bytes of data from the given
5928 * register address of auxiliary sensor in manual mode.
5930 static int8_t read_aux_data(uint8_t reg_addr
, uint8_t *aux_data
, uint16_t len
, uint8_t burst_len
, struct bmi2_dev
*dev
)
5932 /* Variable to define error */
5933 int8_t rslt
= BMI2_OK
;
5935 /* Array to store the register data */
5936 uint8_t reg_data
[15] = { 0 };
5938 /* Variable to define number of bytes to read */
5939 uint16_t read_length
= 0;
5941 /* Variable to define loop */
5944 /* Variable to define counts to get the correct array index */
5947 /* Variable to define index for the array */
5952 /* Set the read address if AUX is not busy */
5953 rslt
= set_if_aux_not_busy(BMI2_AUX_RD_ADDR
, reg_addr
, dev
);
5954 if (rslt
== BMI2_OK
)
5956 /* Read data from bmi2 data register */
5957 rslt
= bmi2_get_regs(BMI2_AUX_X_LSB_ADDR
, reg_data
, (uint16_t) burst_len
, dev
);
5958 dev
->delay_us(1000, dev
->intf_ptr
);
5959 if (rslt
== BMI2_OK
)
5961 /* Get number of bytes to be read */
5962 if (len
< burst_len
)
5964 read_length
= (uint8_t) len
;
5968 read_length
= burst_len
;
5971 /* Update array index and store the data */
5972 for (loop
= 0; loop
< read_length
; loop
++)
5975 aux_data
[idx
] = reg_data
[loop
];
5980 /* Update address for the next read */
5981 reg_addr
+= burst_len
;
5983 /* Update count for the array index */
5986 /* Update no of bytes left to read */
5994 * @brief This internal API writes AUX write address and the user-defined bytes
5995 * of data to the AUX sensor in manual mode.
5997 * @note Change of BMI2_AUX_WR_ADDR is only allowed if AUX is not busy.
5999 static int8_t write_aux_data(uint8_t reg_addr
, uint8_t reg_data
, struct bmi2_dev
*dev
)
6001 /* Variable to define error */
6004 /* Write data to be written to the AUX sensor in bmi2 register */
6005 rslt
= bmi2_set_regs(BMI2_AUX_WR_DATA_ADDR
, ®_data
, 1, dev
);
6006 if (rslt
== BMI2_OK
)
6008 /* Write the AUX address where data is to be stored when AUX is not busy */
6009 rslt
= set_if_aux_not_busy(BMI2_AUX_WR_ADDR
, reg_addr
, dev
);
6016 * @brief This internal API reads the user-defined bytes of data from the given
6017 * register address of auxiliary sensor in data mode.
6019 static int8_t read_aux_data_mode(uint8_t *aux_data
, struct bmi2_dev
*dev
)
6021 /* Variable to define error */
6024 /* Variables to define loop */
6027 /* Variables to define index */
6030 /* Array to define data stored in register */
6031 uint8_t reg_data
[BMI2_AUX_NUM_BYTES
] = { 0 };
6033 /* Check if data mode */
6034 if (!dev
->aux_man_en
)
6036 /* Read the auxiliary sensor data */
6037 rslt
= bmi2_get_regs(BMI2_AUX_X_LSB_ADDR
, reg_data
, BMI2_AUX_NUM_BYTES
, dev
);
6038 if (rslt
== BMI2_OK
)
6040 /* Get the 8 bytes of auxiliary data */
6043 *(aux_data
+ count
++) = *(reg_data
+ index
++);
6044 } while (count
< BMI2_AUX_NUM_BYTES
);
6049 rslt
= BMI2_E_AUX_INVALID_CFG
;
6056 * @brief This internal API maps the actual burst read length with that of the
6057 * register value set by user.
6059 static int8_t map_read_len(uint8_t *len
, const struct bmi2_dev
*dev
)
6061 /* Variable to define error */
6062 int8_t rslt
= BMI2_OK
;
6064 /* Get the burst read length against the values set by the user */
6065 switch (dev
->aux_man_rd_burst_len
)
6067 case BMI2_AUX_READ_LEN_0
:
6070 case BMI2_AUX_READ_LEN_1
:
6073 case BMI2_AUX_READ_LEN_2
:
6076 case BMI2_AUX_READ_LEN_3
:
6080 rslt
= BMI2_E_AUX_INVALID_CFG
;
6088 * @brief This internal API computes the number of bytes of accelerometer FIFO
6089 * data which is to be parsed in header-less mode.
6091 static int8_t parse_fifo_accel_len(uint16_t *start_idx
,
6093 const uint16_t *acc_count
,
6094 const struct bmi2_fifo_frame
*fifo
)
6096 /* Variable to define error */
6097 int8_t rslt
= BMI2_OK
;
6099 /* Data start index */
6100 (*start_idx
) = fifo
->acc_byte_start_idx
;
6102 /* If only accelerometer is enabled */
6103 if (fifo
->data_enable
== BMI2_FIFO_ACC_EN
)
6105 /* Number of bytes to be read */
6106 (*len
) = (uint16_t)((*acc_count
) * BMI2_FIFO_ACC_LENGTH
);
6108 /* If only accelerometer and auxiliary are enabled */
6109 else if (fifo
->data_enable
== (BMI2_FIFO_ACC_EN
| BMI2_FIFO_AUX_EN
))
6111 /* Number of bytes to be read */
6112 (*len
) = (uint16_t)((*acc_count
) * BMI2_FIFO_ACC_AUX_LENGTH
);
6114 /* If only accelerometer and gyroscope are enabled */
6115 else if (fifo
->data_enable
== (BMI2_FIFO_ACC_EN
| BMI2_FIFO_GYR_EN
))
6117 /* Number of bytes to be read */
6118 (*len
) = (uint16_t)((*acc_count
) * BMI2_FIFO_ACC_GYR_LENGTH
);
6120 /* If only accelerometer, gyroscope and auxiliary are enabled */
6121 else if (fifo
->data_enable
== (BMI2_FIFO_ACC_EN
| BMI2_FIFO_GYR_EN
| BMI2_FIFO_AUX_EN
))
6123 /* Number of bytes to be read */
6124 (*len
) = (uint16_t)((*acc_count
) * BMI2_FIFO_ALL_LENGTH
);
6128 /* Move the data index to the last byte to mark completion when
6129 * no sensors or sensors apart from accelerometer are enabled
6131 (*start_idx
) = fifo
->length
;
6134 rslt
= BMI2_W_FIFO_EMPTY
;
6137 /* If more data is requested than available */
6138 if ((*len
) > fifo
->length
)
6140 (*len
) = fifo
->length
;
6147 * @brief This internal API is used to parse the accelerometer data from the
6148 * FIFO in header mode.
6150 static int8_t extract_accel_header_mode(struct bmi2_sens_axes_data
*acc
,
6151 uint16_t *accel_length
,
6152 struct bmi2_fifo_frame
*fifo
,
6153 const struct bmi2_dev
*dev
)
6155 /* Variable to define error */
6156 int8_t rslt
= BMI2_OK
;
6158 /* Variable to define header frame */
6159 uint8_t frame_header
= 0;
6161 /* Variable to index the data bytes */
6162 uint16_t data_index
;
6164 /* Variable to index accelerometer frames */
6165 uint16_t accel_index
= 0;
6167 /* Variable to indicate accelerometer frames read */
6168 uint16_t frame_to_read
= *accel_length
;
6170 for (data_index
= fifo
->acc_byte_start_idx
; data_index
< fifo
->length
;)
6172 /* Get frame header byte */
6173 frame_header
= fifo
->data
[data_index
] & BMI2_FIFO_TAG_INTR_MASK
;
6175 /* Parse virtual header if S4S is enabled */
6176 parse_if_virtual_header(&frame_header
, &data_index
, fifo
);
6178 /* Index shifted to next byte where data starts */
6180 switch (frame_header
)
6182 /* If header defines accelerometer frame */
6183 case BMI2_FIFO_HEADER_ACC_FRM
:
6184 case BMI2_FIFO_HEADER_AUX_ACC_FRM
:
6185 case BMI2_FIFO_HEADER_GYR_ACC_FRM
:
6186 case BMI2_FIFO_HEADER_ALL_FRM
:
6188 /* Unpack from normal frames */
6189 rslt
= unpack_accel_frame(acc
, &data_index
, &accel_index
, frame_header
, fifo
, dev
);
6192 /* If header defines only gyroscope frame */
6193 case BMI2_FIFO_HEADER_GYR_FRM
:
6194 rslt
= move_next_frame(&data_index
, fifo
->gyr_frm_len
, fifo
);
6197 /* If header defines only auxiliary frame */
6198 case BMI2_FIFO_HEADER_AUX_FRM
:
6199 rslt
= move_next_frame(&data_index
, fifo
->aux_frm_len
, fifo
);
6202 /* If header defines only auxiliary and gyroscope frame */
6203 case BMI2_FIFO_HEADER_AUX_GYR_FRM
:
6204 rslt
= move_next_frame(&data_index
, fifo
->aux_gyr_frm_len
, fifo
);
6207 /* If header defines sensor time frame */
6208 case BMI2_FIFO_HEADER_SENS_TIME_FRM
:
6209 rslt
= unpack_sensortime_frame(&data_index
, fifo
);
6212 /* If header defines skip frame */
6213 case BMI2_FIFO_HEADER_SKIP_FRM
:
6214 rslt
= unpack_skipped_frame(&data_index
, fifo
);
6217 /* If header defines Input configuration frame */
6218 case BMI2_FIFO_HEADER_INPUT_CFG_FRM
:
6219 rslt
= move_next_frame(&data_index
, BMI2_FIFO_INPUT_CFG_LENGTH
, fifo
);
6222 /* If header defines invalid frame or end of valid data */
6223 case BMI2_FIFO_HEAD_OVER_READ_MSB
:
6225 /* Move the data index to the last byte to mark completion */
6226 data_index
= fifo
->length
;
6229 rslt
= BMI2_W_FIFO_EMPTY
;
6231 case BMI2_FIFO_VIRT_ACT_RECOG_FRM
:
6232 rslt
= move_next_frame(&data_index
, BMI2_FIFO_VIRT_ACT_DATA_LENGTH
, fifo
);
6236 /* Move the data index to the last byte in case of invalid values */
6237 data_index
= fifo
->length
;
6240 rslt
= BMI2_W_FIFO_EMPTY
;
6244 /* Break if Number of frames to be read is complete or FIFO is mpty */
6245 if ((frame_to_read
== accel_index
) || (rslt
== BMI2_W_FIFO_EMPTY
))
6251 /* Update the accelerometer frame index */
6252 (*accel_length
) = accel_index
;
6254 /* Update the accelerometer byte index */
6255 fifo
->acc_byte_start_idx
= data_index
;
6261 * @brief This internal API is used to parse the accelerometer data from the
6262 * FIFO data in both header and header-less mode. It updates the current data
6263 * byte to be parsed.
6265 static int8_t unpack_accel_frame(struct bmi2_sens_axes_data
*acc
,
6269 const struct bmi2_fifo_frame
*fifo
,
6270 const struct bmi2_dev
*dev
)
6272 /* Variable to define error */
6273 int8_t rslt
= BMI2_OK
;
6277 /* If frame contains only accelerometer data */
6278 case BMI2_FIFO_HEADER_ACC_FRM
:
6279 case BMI2_FIFO_HEAD_LESS_ACC_FRM
:
6281 /* Partially read, then skip the data */
6282 if (((*idx
) + fifo
->acc_frm_len
) > fifo
->length
)
6284 /* Update the data index as complete*/
6285 (*idx
) = fifo
->length
;
6288 rslt
= BMI2_W_FIFO_EMPTY
;
6292 /* Get the accelerometer data */
6293 unpack_accel_data(&acc
[(*acc_idx
)], *idx
, fifo
, dev
);
6295 /* Update data index */
6296 (*idx
) = (*idx
) + BMI2_FIFO_ACC_LENGTH
;
6298 /* Get virtual sensor time if S4S is enabled */
6299 if (dev
->sens_en_stat
& BMI2_EXT_SENS_SEL
)
6301 unpack_virt_sensor_time(&acc
[(*acc_idx
)], idx
, fifo
);
6304 /* Update accelerometer frame index */
6307 /* More frames could be read */
6308 rslt
= BMI2_W_PARTIAL_READ
;
6311 /* If frame contains accelerometer and gyroscope data */
6312 case BMI2_FIFO_HEADER_GYR_ACC_FRM
:
6313 case BMI2_FIFO_HEAD_LESS_GYR_ACC_FRM
:
6315 /* Partially read, then skip the data */
6316 if (((*idx
) + fifo
->acc_gyr_frm_len
) > fifo
->length
)
6318 /* Move the data index to the last byte */
6319 (*idx
) = fifo
->length
;
6322 rslt
= BMI2_W_FIFO_EMPTY
;
6326 /* Get the accelerometer data */
6327 unpack_accel_data(&acc
[(*acc_idx
)], ((*idx
) + BMI2_FIFO_GYR_LENGTH
), fifo
, dev
);
6329 /* Update data index */
6330 (*idx
) = (*idx
) + BMI2_FIFO_ACC_GYR_LENGTH
;
6332 /* Get virtual sensor time if S4S is enabled */
6333 if (dev
->sens_en_stat
& BMI2_EXT_SENS_SEL
)
6335 unpack_virt_sensor_time(&acc
[(*acc_idx
)], idx
, fifo
);
6338 /* Update accelerometer frame index */
6341 /* More frames could be read */
6342 rslt
= BMI2_W_PARTIAL_READ
;
6345 /* If frame contains accelerometer and auxiliary data */
6346 case BMI2_FIFO_HEADER_AUX_ACC_FRM
:
6347 case BMI2_FIFO_HEAD_LESS_AUX_ACC_FRM
:
6349 /* Partially read, then skip the data */
6350 if (((*idx
) + fifo
->acc_aux_frm_len
) > fifo
->length
)
6352 /* Move the data index to the last byte */
6353 (*idx
) = fifo
->length
;
6356 rslt
= BMI2_W_FIFO_EMPTY
;
6360 /* Get the accelerometer data */
6361 unpack_accel_data(&acc
[(*acc_idx
)], ((*idx
) + BMI2_FIFO_AUX_LENGTH
), fifo
, dev
);
6363 /* Update data index */
6364 (*idx
) = (*idx
) + BMI2_FIFO_ACC_AUX_LENGTH
;
6366 /* Get virtual sensor time if S4S is enabled */
6367 if (dev
->sens_en_stat
& BMI2_EXT_SENS_SEL
)
6369 unpack_virt_sensor_time(&acc
[(*acc_idx
)], idx
, fifo
);
6372 /* Update accelerometer frame index */
6375 /* More frames could be read */
6376 rslt
= BMI2_W_PARTIAL_READ
;
6379 /* If frame contains accelerometer, gyroscope and auxiliary data */
6380 case BMI2_FIFO_HEADER_ALL_FRM
:
6381 case BMI2_FIFO_HEAD_LESS_ALL_FRM
:
6383 /* Partially read, then skip the data*/
6384 if ((*idx
+ fifo
->all_frm_len
) > fifo
->length
)
6386 /* Move the data index to the last byte */
6387 (*idx
) = fifo
->length
;
6390 rslt
= BMI2_W_FIFO_EMPTY
;
6394 /* Get the accelerometer data */
6395 unpack_accel_data(&acc
[(*acc_idx
)], ((*idx
) + BMI2_FIFO_GYR_AUX_LENGTH
), fifo
, dev
);
6397 /* Update data index */
6398 (*idx
) = (*idx
) + BMI2_FIFO_ALL_LENGTH
;
6400 /* Get virtual sensor time if S4S is enabled */
6401 if (dev
->sens_en_stat
& BMI2_EXT_SENS_SEL
)
6403 unpack_virt_sensor_time(&acc
[(*acc_idx
)], idx
, fifo
);
6406 /* Update accelerometer frame index */
6409 /* More frames could be read */
6410 rslt
= BMI2_W_PARTIAL_READ
;
6413 /* If frame contains gyroscope and auxiliary data */
6414 case BMI2_FIFO_HEADER_AUX_GYR_FRM
:
6415 case BMI2_FIFO_HEAD_LESS_GYR_AUX_FRM
:
6417 /* Update data index */
6418 (*idx
) = (*idx
) + fifo
->aux_gyr_frm_len
;
6420 /* More frames could be read */
6421 rslt
= BMI2_W_PARTIAL_READ
;
6424 /* If frame contains only auxiliary data */
6425 case BMI2_FIFO_HEADER_AUX_FRM
:
6426 case BMI2_FIFO_HEAD_LESS_AUX_FRM
:
6428 /* Update data index */
6429 (*idx
) = (*idx
) + fifo
->aux_frm_len
;
6431 /* More frames could be read */
6432 rslt
= BMI2_W_PARTIAL_READ
;
6435 /* If frame contains only gyroscope data */
6436 case BMI2_FIFO_HEADER_GYR_FRM
:
6437 case BMI2_FIFO_HEAD_LESS_GYR_FRM
:
6439 /* Update data index */
6440 (*idx
) = (*idx
) + fifo
->gyr_frm_len
;
6442 /* More frames could be read */
6443 rslt
= BMI2_W_PARTIAL_READ
;
6447 /* Move the data index to the last byte in case of invalid values */
6448 (*idx
) = fifo
->length
;
6451 rslt
= BMI2_W_FIFO_EMPTY
;
6459 * @brief This internal API is used to parse accelerometer data from the
6462 static void unpack_accel_data(struct bmi2_sens_axes_data
*acc
,
6463 uint16_t data_start_index
,
6464 const struct bmi2_fifo_frame
*fifo
,
6465 const struct bmi2_dev
*dev
)
6467 /* Variables to store LSB value */
6470 /* Variables to store MSB value */
6473 /* Accelerometer raw x data */
6474 data_lsb
= fifo
->data
[data_start_index
++];
6475 data_msb
= fifo
->data
[data_start_index
++];
6476 acc
->x
= (int16_t)((data_msb
<< 8) | data_lsb
);
6478 /* Accelerometer raw y data */
6479 data_lsb
= fifo
->data
[data_start_index
++];
6480 data_msb
= fifo
->data
[data_start_index
++];
6481 acc
->y
= (int16_t)((data_msb
<< 8) | data_lsb
);
6483 /* Accelerometer raw z data */
6484 data_lsb
= fifo
->data
[data_start_index
++];
6485 data_msb
= fifo
->data
[data_start_index
++];
6486 acc
->z
= (int16_t)((data_msb
<< 8) | data_lsb
);
6488 /* Get the re-mapped accelerometer data */
6489 get_remapped_data(acc
, dev
);
6493 * @brief This internal API computes the number of bytes of gyroscope FIFO data
6494 * which is to be parsed in header-less mode.
6496 static int8_t parse_fifo_gyro_len(uint16_t *start_idx
,
6498 const uint16_t *gyr_count
,
6499 const struct bmi2_fifo_frame
*fifo
)
6501 /* Variable to define error */
6502 int8_t rslt
= BMI2_OK
;
6504 /* Data start index */
6505 (*start_idx
) = fifo
->gyr_byte_start_idx
;
6507 /* If only gyroscope is enabled */
6508 if (fifo
->data_enable
== BMI2_FIFO_GYR_EN
)
6510 /* Number of bytes to be read */
6511 (*len
) = (uint16_t)((*gyr_count
) * BMI2_FIFO_GYR_LENGTH
);
6513 /* If only gyroscope and auxiliary are enabled */
6514 else if (fifo
->data_enable
== (BMI2_FIFO_GYR_EN
| BMI2_FIFO_AUX_EN
))
6516 /* Number of bytes to be read */
6517 (*len
) = (uint16_t)((*gyr_count
) * BMI2_FIFO_GYR_AUX_LENGTH
);
6519 /* If only accelerometer and gyroscope are enabled */
6520 else if (fifo
->data_enable
== (BMI2_FIFO_ACC_EN
| BMI2_FIFO_GYR_EN
))
6522 /* Number of bytes to be read */
6523 (*len
) = (uint16_t)((*gyr_count
) * BMI2_FIFO_ACC_GYR_LENGTH
);
6525 /* If only accelerometer, gyroscope and auxiliary are enabled */
6526 else if (fifo
->data_enable
== (BMI2_FIFO_GYR_EN
| BMI2_FIFO_AUX_EN
| BMI2_FIFO_ACC_EN
))
6528 /* Number of bytes to be read */
6529 (*len
) = (uint16_t)((*gyr_count
) * BMI2_FIFO_ALL_LENGTH
);
6533 /* Move the data index to the last byte to mark completion when
6534 * no sensors or sensors apart from gyroscope are enabled
6536 (*start_idx
) = fifo
->length
;
6539 rslt
= BMI2_W_FIFO_EMPTY
;
6542 /* If more data is requested than available */
6543 if (((*len
)) > fifo
->length
)
6545 (*len
) = fifo
->length
;
6552 * @brief This internal API is used to parse the gyroscope data from the
6553 * FIFO data in header mode.
6555 static int8_t extract_gyro_header_mode(struct bmi2_sens_axes_data
*gyr
,
6556 uint16_t *gyro_length
,
6557 struct bmi2_fifo_frame
*fifo
,
6558 const struct bmi2_dev
*dev
)
6560 /* Variable to define error */
6561 int8_t rslt
= BMI2_OK
;
6563 /* Variable to define header frame */
6564 uint8_t frame_header
= 0;
6566 /* Variable to index the data bytes */
6567 uint16_t data_index
;
6569 /* Variable to index gyroscope frames */
6570 uint16_t gyro_index
= 0;
6572 /* Variable to indicate gyroscope frames read */
6573 uint16_t frame_to_read
= (*gyro_length
);
6575 for (data_index
= fifo
->gyr_byte_start_idx
; data_index
< fifo
->length
;)
6577 /* Get frame header byte */
6578 frame_header
= fifo
->data
[data_index
] & BMI2_FIFO_TAG_INTR_MASK
;
6580 /* Parse virtual header if S4S is enabled */
6581 parse_if_virtual_header(&frame_header
, &data_index
, fifo
);
6583 /* Index shifted to next byte where data starts */
6585 switch (frame_header
)
6587 /* If header defines gyroscope frame */
6588 case BMI2_FIFO_HEADER_GYR_FRM
:
6589 case BMI2_FIFO_HEADER_GYR_ACC_FRM
:
6590 case BMI2_FIFO_HEADER_AUX_GYR_FRM
:
6591 case BMI2_FIFO_HEADER_ALL_FRM
:
6593 /* Unpack from normal frames */
6594 rslt
= unpack_gyro_frame(gyr
, &data_index
, &gyro_index
, frame_header
, fifo
, dev
);
6597 /* If header defines only accelerometer frame */
6598 case BMI2_FIFO_HEADER_ACC_FRM
:
6599 rslt
= move_next_frame(&data_index
, fifo
->acc_frm_len
, fifo
);
6602 /* If header defines only auxiliary frame */
6603 case BMI2_FIFO_HEADER_AUX_FRM
:
6604 rslt
= move_next_frame(&data_index
, fifo
->aux_frm_len
, fifo
);
6607 /* If header defines only auxiliary and accelerometer frame */
6608 case BMI2_FIFO_HEADER_AUX_ACC_FRM
:
6609 rslt
= move_next_frame(&data_index
, fifo
->acc_aux_frm_len
, fifo
);
6612 /* If header defines sensor time frame */
6613 case BMI2_FIFO_HEADER_SENS_TIME_FRM
:
6614 rslt
= unpack_sensortime_frame(&data_index
, fifo
);
6617 /* If header defines skip frame */
6618 case BMI2_FIFO_HEADER_SKIP_FRM
:
6619 rslt
= unpack_skipped_frame(&data_index
, fifo
);
6622 /* If header defines Input configuration frame */
6623 case BMI2_FIFO_HEADER_INPUT_CFG_FRM
:
6624 rslt
= move_next_frame(&data_index
, BMI2_FIFO_INPUT_CFG_LENGTH
, fifo
);
6627 /* If header defines invalid frame or end of valid data */
6628 case BMI2_FIFO_HEAD_OVER_READ_MSB
:
6630 /* Move the data index to the last byte */
6631 data_index
= fifo
->length
;
6634 rslt
= BMI2_W_FIFO_EMPTY
;
6636 case BMI2_FIFO_VIRT_ACT_RECOG_FRM
:
6637 rslt
= move_next_frame(&data_index
, BMI2_FIFO_VIRT_ACT_DATA_LENGTH
, fifo
);
6641 /* Move the data index to the last byte in case of invalid values */
6642 data_index
= fifo
->length
;
6645 rslt
= BMI2_W_FIFO_EMPTY
;
6649 /* Break if number of frames to be read is complete or FIFO is empty */
6650 if ((frame_to_read
== gyro_index
) || (rslt
== BMI2_W_FIFO_EMPTY
))
6656 /* Update the gyroscope frame index */
6657 (*gyro_length
) = gyro_index
;
6659 /* Update the gyroscope byte index */
6660 fifo
->gyr_byte_start_idx
= data_index
;
6666 * @brief This internal API is used to parse the gyroscope data from the FIFO
6667 * data in both header and header-less mode. It updates the current data byte to
6670 static int8_t unpack_gyro_frame(struct bmi2_sens_axes_data
*gyr
,
6674 const struct bmi2_fifo_frame
*fifo
,
6675 const struct bmi2_dev
*dev
)
6677 /* Variable to define error */
6678 int8_t rslt
= BMI2_OK
;
6682 /* If frame contains only gyroscope data */
6683 case BMI2_FIFO_HEADER_GYR_FRM
:
6684 case BMI2_FIFO_HEAD_LESS_GYR_FRM
:
6686 /* Partially read, then skip the data */
6687 if (((*idx
) + fifo
->gyr_frm_len
) > fifo
->length
)
6689 /* Update the data index as complete*/
6690 (*idx
) = fifo
->length
;
6693 rslt
= BMI2_W_FIFO_EMPTY
;
6697 /* Get the gyroscope data */
6698 unpack_gyro_data(&gyr
[(*gyr_idx
)], *idx
, fifo
, dev
);
6700 /* Update data index */
6701 (*idx
) = (*idx
) + BMI2_FIFO_GYR_LENGTH
;
6703 /* Get virtual sensor time if S4S is enabled */
6704 if (dev
->sens_en_stat
& BMI2_EXT_SENS_SEL
)
6706 unpack_virt_sensor_time(&gyr
[(*gyr_idx
)], idx
, fifo
);
6709 /* Update gyroscope frame index */
6712 /* More frames could be read */
6713 rslt
= BMI2_W_PARTIAL_READ
;
6716 /* If frame contains accelerometer and gyroscope data */
6717 case BMI2_FIFO_HEADER_GYR_ACC_FRM
:
6718 case BMI2_FIFO_HEAD_LESS_GYR_ACC_FRM
:
6720 /* Partially read, then skip the data */
6721 if (((*idx
) + fifo
->acc_gyr_frm_len
) > fifo
->length
)
6723 /* Move the data index to the last byte */
6724 (*idx
) = fifo
->length
;
6727 rslt
= BMI2_W_FIFO_EMPTY
;
6731 /* Get the gyroscope data */
6732 unpack_gyro_data(&gyr
[(*gyr_idx
)], (*idx
), fifo
, dev
);
6734 /* Update data index */
6735 (*idx
) = (*idx
) + BMI2_FIFO_ACC_GYR_LENGTH
;
6737 /* Get virtual sensor time if S4S is enabled */
6738 if (dev
->sens_en_stat
& BMI2_EXT_SENS_SEL
)
6740 unpack_virt_sensor_time(&gyr
[(*gyr_idx
)], idx
, fifo
);
6743 /* Update gyroscope frame index */
6746 /* More frames could be read */
6747 rslt
= BMI2_W_PARTIAL_READ
;
6750 /* If frame contains gyroscope and auxiliary data */
6751 case BMI2_FIFO_HEADER_AUX_GYR_FRM
:
6752 case BMI2_FIFO_HEAD_LESS_GYR_AUX_FRM
:
6754 /* Partially read, then skip the data */
6755 if (((*idx
) + fifo
->aux_gyr_frm_len
) > fifo
->length
)
6757 /* Move the data index to the last byte */
6758 (*idx
) = fifo
->length
;
6761 rslt
= BMI2_W_FIFO_EMPTY
;
6765 /* Get the gyroscope data */
6766 unpack_gyro_data(&gyr
[(*gyr_idx
)], ((*idx
) + BMI2_FIFO_AUX_LENGTH
), fifo
, dev
);
6768 /* Update data index */
6769 (*idx
) = (*idx
) + BMI2_FIFO_GYR_AUX_LENGTH
;
6771 /* Get virtual sensor time if S4S is enabled */
6772 if (dev
->sens_en_stat
& BMI2_EXT_SENS_SEL
)
6774 unpack_virt_sensor_time(&gyr
[(*gyr_idx
)], idx
, fifo
);
6777 /* Update gyroscope frame index */
6780 /* More frames could be read */
6781 rslt
= BMI2_W_PARTIAL_READ
;
6784 /* If frame contains accelerometer, gyroscope and auxiliary data */
6785 case BMI2_FIFO_HEADER_ALL_FRM
:
6786 case BMI2_FIFO_HEAD_LESS_ALL_FRM
:
6788 /* Partially read, then skip the data*/
6789 if ((*idx
+ fifo
->all_frm_len
) > fifo
->length
)
6791 /* Move the data index to the last byte */
6792 (*idx
) = fifo
->length
;
6795 rslt
= BMI2_W_FIFO_EMPTY
;
6799 /* Get the gyroscope data */
6800 unpack_gyro_data(&gyr
[(*gyr_idx
)], ((*idx
) + BMI2_FIFO_AUX_LENGTH
), fifo
, dev
);
6802 /* Update data index */
6803 (*idx
) = (*idx
) + BMI2_FIFO_ALL_LENGTH
;
6805 /* Get virtual sensor time if S4S is enabled */
6806 if (dev
->sens_en_stat
& BMI2_EXT_SENS_SEL
)
6808 unpack_virt_sensor_time(&gyr
[(*gyr_idx
)], idx
, fifo
);
6811 /* Update gyroscope frame index */
6814 /* More frames could be read */
6815 rslt
= BMI2_W_PARTIAL_READ
;
6818 /* If frame contains accelerometer and auxiliary data */
6819 case BMI2_FIFO_HEADER_AUX_ACC_FRM
:
6820 case BMI2_FIFO_HEAD_LESS_AUX_ACC_FRM
:
6822 /* Update data index */
6823 (*idx
) = (*idx
) + fifo
->acc_aux_frm_len
;
6825 /* More frames could be read */
6826 rslt
= BMI2_W_PARTIAL_READ
;
6829 /* If frame contains only auxiliary data */
6830 case BMI2_FIFO_HEADER_AUX_FRM
:
6831 case BMI2_FIFO_HEAD_LESS_AUX_FRM
:
6833 /* Update data index */
6834 (*idx
) = (*idx
) + fifo
->aux_frm_len
;
6836 /* More frames could be read */
6837 rslt
= BMI2_W_PARTIAL_READ
;
6840 /* If frame contains only accelerometer data */
6841 case BMI2_FIFO_HEADER_ACC_FRM
:
6842 case BMI2_FIFO_HEAD_LESS_ACC_FRM
:
6844 /* Update data index */
6845 (*idx
) = (*idx
) + fifo
->acc_frm_len
;
6847 /* More frames could be read */
6848 rslt
= BMI2_W_PARTIAL_READ
;
6852 /* Move the data index to the last byte in case of invalid values */
6853 (*idx
) = fifo
->length
;
6856 rslt
= BMI2_W_FIFO_EMPTY
;
6864 * @brief This internal API is used to parse gyroscope data from the FIFO data.
6866 static void unpack_gyro_data(struct bmi2_sens_axes_data
*gyr
,
6867 uint16_t data_start_index
,
6868 const struct bmi2_fifo_frame
*fifo
,
6869 const struct bmi2_dev
*dev
)
6871 /* Variables to store LSB value */
6874 /* Variables to store MSB value */
6877 /* Gyroscope raw x data */
6878 data_lsb
= fifo
->data
[data_start_index
++];
6879 data_msb
= fifo
->data
[data_start_index
++];
6880 gyr
->x
= (int16_t)((data_msb
<< 8) | data_lsb
);
6882 /* Gyroscope raw y data */
6883 data_lsb
= fifo
->data
[data_start_index
++];
6884 data_msb
= fifo
->data
[data_start_index
++];
6885 gyr
->y
= (int16_t)((data_msb
<< 8) | data_lsb
);
6887 /* Gyroscope raw z data */
6888 data_lsb
= fifo
->data
[data_start_index
++];
6889 data_msb
= fifo
->data
[data_start_index
++];
6890 gyr
->z
= (int16_t)((data_msb
<< 8) | data_lsb
);
6892 /* Get the compensated gyroscope data */
6893 comp_gyro_cross_axis_sensitivity(gyr
, dev
);
6895 /* Get the re-mapped gyroscope data */
6896 get_remapped_data(gyr
, dev
);
6900 * @brief This API computes the number of bytes of auxiliary FIFO data which is
6901 * to be parsed in header-less mode.
6903 static int8_t parse_fifo_aux_len(uint16_t *start_idx
,
6905 const uint16_t *aux_count
,
6906 const struct bmi2_fifo_frame
*fifo
)
6908 /* Variable to define error */
6909 int8_t rslt
= BMI2_OK
;
6911 /* Data start index */
6912 *start_idx
= fifo
->aux_byte_start_idx
;
6914 /* If only auxiliary is enabled */
6915 if (fifo
->data_enable
== BMI2_FIFO_AUX_EN
)
6917 /* Number of bytes to be read */
6918 (*len
) = (uint16_t)((*aux_count
) * BMI2_FIFO_AUX_LENGTH
);
6920 /* If only accelerometer and auxiliary are enabled */
6921 else if (fifo
->data_enable
== (BMI2_FIFO_AUX_EN
| BMI2_FIFO_ACC_EN
))
6923 /* Number of bytes to be read */
6924 (*len
) = (uint16_t)((*aux_count
) * BMI2_FIFO_ACC_AUX_LENGTH
);
6926 /* If only accelerometer and gyroscope are enabled */
6927 else if (fifo
->data_enable
== (BMI2_FIFO_AUX_EN
| BMI2_FIFO_GYR_EN
))
6929 /* Number of bytes to be read */
6930 (*len
) = (uint16_t)((*aux_count
) * BMI2_FIFO_GYR_AUX_LENGTH
);
6932 /* If only accelerometer, gyroscope and auxiliary are enabled */
6933 else if (fifo
->data_enable
== (BMI2_FIFO_AUX_EN
| BMI2_FIFO_GYR_EN
| BMI2_FIFO_ACC_EN
))
6935 /* Number of bytes to be read */
6936 (*len
) = (uint16_t)((*aux_count
) * BMI2_FIFO_ALL_LENGTH
);
6940 /* Move the data index to the last byte to mark completion when
6941 * no sensors or sensors apart from gyroscope are enabled
6943 (*start_idx
) = fifo
->length
;
6946 rslt
= BMI2_W_FIFO_EMPTY
;
6949 /* If more data is requested than available */
6950 if (((*len
)) > fifo
->length
)
6952 (*len
) = fifo
->length
;
6959 * @brief This API is used to parse the auxiliary data from the FIFO data in
6962 static int8_t extract_aux_header_mode(struct bmi2_aux_fifo_data
*aux
,
6964 struct bmi2_fifo_frame
*fifo
,
6965 const struct bmi2_dev
*dev
)
6967 /* Variable to define error */
6968 int8_t rslt
= BMI2_OK
;
6970 /* Variable to define header frame */
6971 uint8_t frame_header
= 0;
6973 /* Variable to index the data bytes */
6974 uint16_t data_index
;
6976 /* Variable to index gyroscope frames */
6977 uint16_t aux_index
= 0;
6979 /* Variable to indicate auxiliary frames read */
6980 uint16_t frame_to_read
= *aux_len
;
6982 for (data_index
= fifo
->aux_byte_start_idx
; data_index
< fifo
->length
;)
6984 /* Get frame header byte */
6985 frame_header
= fifo
->data
[data_index
] & BMI2_FIFO_TAG_INTR_MASK
;
6987 /* Parse virtual header if S4S is enabled */
6988 parse_if_virtual_header(&frame_header
, &data_index
, fifo
);
6990 /* Index shifted to next byte where data starts */
6992 switch (frame_header
)
6994 /* If header defines auxiliary frame */
6995 case BMI2_FIFO_HEADER_AUX_FRM
:
6996 case BMI2_FIFO_HEADER_AUX_ACC_FRM
:
6997 case BMI2_FIFO_HEADER_AUX_GYR_FRM
:
6998 case BMI2_FIFO_HEADER_ALL_FRM
:
7000 /* Unpack from normal frames */
7001 rslt
= unpack_aux_frame(aux
, &data_index
, &aux_index
, frame_header
, fifo
, dev
);
7004 /* If header defines only accelerometer frame */
7005 case BMI2_FIFO_HEADER_ACC_FRM
:
7006 rslt
= move_next_frame(&data_index
, fifo
->acc_frm_len
, fifo
);
7009 /* If header defines only gyroscope frame */
7010 case BMI2_FIFO_HEADER_GYR_FRM
:
7011 rslt
= move_next_frame(&data_index
, fifo
->gyr_frm_len
, fifo
);
7014 /* If header defines only gyroscope and accelerometer frame */
7015 case BMI2_FIFO_HEADER_GYR_ACC_FRM
:
7016 rslt
= move_next_frame(&data_index
, fifo
->acc_gyr_frm_len
, fifo
);
7019 /* If header defines sensor time frame */
7020 case BMI2_FIFO_HEADER_SENS_TIME_FRM
:
7021 rslt
= unpack_sensortime_frame(&data_index
, fifo
);
7024 /* If header defines skip frame */
7025 case BMI2_FIFO_HEADER_SKIP_FRM
:
7026 rslt
= unpack_skipped_frame(&data_index
, fifo
);
7029 /* If header defines Input configuration frame */
7030 case BMI2_FIFO_HEADER_INPUT_CFG_FRM
:
7031 rslt
= move_next_frame(&data_index
, BMI2_FIFO_INPUT_CFG_LENGTH
, fifo
);
7034 /* If header defines invalid frame or end of valid data */
7035 case BMI2_FIFO_HEAD_OVER_READ_MSB
:
7037 /* Move the data index to the last byte */
7038 data_index
= fifo
->length
;
7041 rslt
= BMI2_W_FIFO_EMPTY
;
7043 case BMI2_FIFO_VIRT_ACT_RECOG_FRM
:
7044 rslt
= move_next_frame(&data_index
, BMI2_FIFO_VIRT_ACT_DATA_LENGTH
, fifo
);
7048 /* Move the data index to the last byte in case
7051 data_index
= fifo
->length
;
7054 rslt
= BMI2_W_FIFO_EMPTY
;
7058 /* Break if number of frames to be read is complete or FIFO is
7061 if ((frame_to_read
== aux_index
) || (rslt
== BMI2_W_FIFO_EMPTY
))
7067 /* Update the gyroscope frame index */
7068 (*aux_len
) = aux_index
;
7070 /* Update the gyroscope byte index */
7071 fifo
->aux_byte_start_idx
= data_index
;
7077 * @brief This API is used to parse the auxiliary frame from the FIFO data in
7078 * both header mode and header-less mode and update the data_index value which
7079 * is used to store the index of the current data byte which is parsed.
7081 static int8_t unpack_aux_frame(struct bmi2_aux_fifo_data
*aux
,
7085 const struct bmi2_fifo_frame
*fifo
,
7086 const struct bmi2_dev
*dev
)
7088 /* Variable to define error */
7089 int8_t rslt
= BMI2_OK
;
7093 /* If frame contains only auxiliary data */
7094 case BMI2_FIFO_HEADER_AUX_FRM
:
7095 case BMI2_FIFO_HEAD_LESS_AUX_FRM
:
7097 /* Partially read, then skip the data */
7098 if (((*idx
) + fifo
->aux_frm_len
) > fifo
->length
)
7100 /* Update the data index as complete*/
7101 (*idx
) = fifo
->length
;
7104 rslt
= BMI2_W_FIFO_EMPTY
;
7108 /* Get the auxiliary data */
7109 unpack_aux_data(&aux
[(*aux_idx
)], (*idx
), fifo
);
7111 /* Update data index */
7112 (*idx
) = (*idx
) + BMI2_FIFO_AUX_LENGTH
;
7114 /* Get virtual sensor time if S4S is enabled */
7115 if (dev
->sens_en_stat
& BMI2_EXT_SENS_SEL
)
7117 unpack_virt_aux_sensor_time(&aux
[(*aux_idx
)], idx
, fifo
);
7120 /* Update auxiliary frame index */
7123 /* More frames could be read */
7124 rslt
= BMI2_W_PARTIAL_READ
;
7127 /* If frame contains accelerometer and auxiliary data */
7128 case BMI2_FIFO_HEADER_AUX_ACC_FRM
:
7129 case BMI2_FIFO_HEAD_LESS_AUX_ACC_FRM
:
7131 /* Partially read, then skip the data */
7132 if (((*idx
) + fifo
->acc_aux_frm_len
) > fifo
->length
)
7134 /* Move the data index to the last byte */
7135 (*idx
) = fifo
->length
;
7138 rslt
= BMI2_W_FIFO_EMPTY
;
7142 /* Get the auxiliary data */
7143 unpack_aux_data(&aux
[(*aux_idx
)], (*idx
), fifo
);
7145 /* Update data index */
7146 (*idx
) = (*idx
) + BMI2_FIFO_ACC_AUX_LENGTH
;
7148 /* Get virtual sensor time if S4S is enabled */
7149 if (dev
->sens_en_stat
& BMI2_EXT_SENS_SEL
)
7151 unpack_virt_aux_sensor_time(&aux
[(*aux_idx
)], idx
, fifo
);
7154 /* Update auxiliary frame index */
7157 /* More frames could be read */
7158 rslt
= BMI2_W_PARTIAL_READ
;
7161 /* If frame contains gyroscope and auxiliary data */
7162 case BMI2_FIFO_HEADER_AUX_GYR_FRM
:
7163 case BMI2_FIFO_HEAD_LESS_GYR_AUX_FRM
:
7165 /* Partially read, then skip the data */
7166 if (((*idx
) + fifo
->aux_gyr_frm_len
) > fifo
->length
)
7168 /* Move the data index to the last byte */
7169 (*idx
) = fifo
->length
;
7172 rslt
= BMI2_W_FIFO_EMPTY
;
7176 /* Get the auxiliary data */
7177 unpack_aux_data(&aux
[(*aux_idx
)], (*idx
), fifo
);
7179 /* Update data index */
7180 (*idx
) = (*idx
) + BMI2_FIFO_GYR_AUX_LENGTH
;
7182 /* Get virtual sensor time if S4S is enabled */
7183 if (dev
->sens_en_stat
& BMI2_EXT_SENS_SEL
)
7185 unpack_virt_aux_sensor_time(&aux
[(*aux_idx
)], idx
, fifo
);
7188 /* Update auxiliary frame index */
7191 /* More frames could be read */
7192 rslt
= BMI2_W_PARTIAL_READ
;
7195 /* If frame contains accelerometer, gyroscope and auxiliary data */
7196 case BMI2_FIFO_HEADER_ALL_FRM
:
7197 case BMI2_FIFO_HEAD_LESS_ALL_FRM
:
7199 /* Partially read, then skip the data */
7200 if ((*idx
+ fifo
->all_frm_len
) > fifo
->length
)
7202 /* Move the data index to the last byte */
7203 (*idx
) = fifo
->length
;
7206 rslt
= BMI2_W_FIFO_EMPTY
;
7210 /* Get the auxiliary data */
7211 unpack_aux_data(&aux
[(*aux_idx
)], (*idx
), fifo
);
7213 /* Update data index */
7214 (*idx
) = (*idx
) + BMI2_FIFO_ALL_LENGTH
;
7216 /* Get virtual sensor time if S4S is enabled */
7217 if (dev
->sens_en_stat
& BMI2_EXT_SENS_SEL
)
7219 unpack_virt_aux_sensor_time(&aux
[(*aux_idx
)], idx
, fifo
);
7222 /* Update auxiliary frame index */
7225 /* More frames could be read */
7226 rslt
= BMI2_W_PARTIAL_READ
;
7229 /* If frame contains only accelerometer data */
7230 case BMI2_FIFO_HEADER_ACC_FRM
:
7231 case BMI2_FIFO_HEAD_LESS_ACC_FRM
:
7233 /* Update data index */
7234 (*idx
) = (*idx
) + fifo
->acc_frm_len
;
7236 /* More frames could be read */
7237 rslt
= BMI2_W_PARTIAL_READ
;
7240 /* If frame contains only gyroscope data */
7241 case BMI2_FIFO_HEADER_GYR_FRM
:
7242 case BMI2_FIFO_HEAD_LESS_GYR_FRM
:
7244 /* Update data index */
7245 (*idx
) = (*idx
) + fifo
->gyr_frm_len
;
7247 /* More frames could be read */
7248 rslt
= BMI2_W_PARTIAL_READ
;
7251 /* If frame contains accelerometer and gyroscope data */
7252 case BMI2_FIFO_HEADER_GYR_ACC_FRM
:
7253 case BMI2_FIFO_HEAD_LESS_GYR_ACC_FRM
:
7255 /* Update data index */
7256 (*idx
) = (*idx
) + fifo
->acc_gyr_frm_len
;
7258 /* More frames could be read */
7259 rslt
= BMI2_W_PARTIAL_READ
;
7263 /* Move the data index to the last byte in case of
7266 (*idx
) = fifo
->length
;
7269 rslt
= BMI2_W_FIFO_EMPTY
;
7277 * @brief This internal API is used to parse auxiliary data from the FIFO data.
7279 static void unpack_aux_data(struct bmi2_aux_fifo_data
*aux
,
7280 uint16_t data_start_index
,
7281 const struct bmi2_fifo_frame
*fifo
)
7283 /* Variables to store index */
7286 /* Get auxiliary data */
7287 for (; idx
< 8; idx
++)
7289 aux
->data
[idx
] = fifo
->data
[data_start_index
++];
7294 * @brief This internal API parses virtual frame header from the FIFO data.
7296 static void parse_if_virtual_header(uint8_t *frame_header
, uint16_t *data_index
, const struct bmi2_fifo_frame
*fifo
)
7298 /* Variable to extract virtual header byte */
7299 uint8_t virtual_header_mode
;
7301 /* Extract virtual header mode from the frame header */
7302 virtual_header_mode
= BMI2_GET_BITS(*frame_header
, BMI2_FIFO_VIRT_FRM_MODE
);
7304 /* If the extracted header byte is a virtual header */
7305 if (virtual_header_mode
== BMI2_FIFO_VIRT_FRM_MODE
)
7307 /* If frame header is not activity recognition header */
7308 if (*frame_header
!= 0xC8)
7310 /* Index shifted to next byte where sensor frame is present */
7311 (*data_index
) = (*data_index
) + 1;
7313 /* Get the sensor frame header */
7314 *frame_header
= fifo
->data
[*data_index
] & BMI2_FIFO_TAG_INTR_MASK
;
7320 * @brief This internal API gets sensor time from the accelerometer and
7321 * gyroscope virtual frames and updates in the data structure.
7323 static void unpack_virt_sensor_time(struct bmi2_sens_axes_data
*sens
, uint16_t *idx
, const struct bmi2_fifo_frame
*fifo
)
7325 /* Variables to define 3 bytes of sensor time */
7326 uint32_t sensor_time_byte3
;
7327 uint16_t sensor_time_byte2
;
7328 uint8_t sensor_time_byte1
;
7330 /* Get sensor time from the FIFO data */
7331 sensor_time_byte3
= (uint32_t)(fifo
->data
[(*idx
) + BMI2_SENSOR_TIME_MSB_BYTE
] << 16);
7332 sensor_time_byte2
= (uint16_t) fifo
->data
[(*idx
) + BMI2_SENSOR_TIME_XLSB_BYTE
] << 8;
7333 sensor_time_byte1
= fifo
->data
[(*idx
)];
7335 /* Store sensor time in the sensor data structure */
7336 sens
->virt_sens_time
= (uint32_t)(sensor_time_byte3
| sensor_time_byte2
| sensor_time_byte1
);
7338 /* Move the data index by 3 bytes */
7339 (*idx
) = (*idx
) + BMI2_SENSOR_TIME_LENGTH
;
7343 * @brief This internal API gets sensor time from the auxiliary virtual
7344 * frames and updates in the data structure.
7346 static void unpack_virt_aux_sensor_time(struct bmi2_aux_fifo_data
*aux
,
7348 const struct bmi2_fifo_frame
*fifo
)
7350 /* Variables to define 3 bytes of sensor time */
7351 uint32_t sensor_time_byte3
;
7352 uint16_t sensor_time_byte2
;
7353 uint8_t sensor_time_byte1
;
7355 /* Get sensor time from the FIFO data */
7356 sensor_time_byte3
= (uint32_t)(fifo
->data
[(*idx
) + BMI2_SENSOR_TIME_MSB_BYTE
] << 16);
7357 sensor_time_byte2
= (uint16_t) fifo
->data
[(*idx
) + BMI2_SENSOR_TIME_XLSB_BYTE
] << 8;
7358 sensor_time_byte1
= fifo
->data
[(*idx
)];
7360 /* Store sensor time in the sensor data structure */
7361 aux
->virt_sens_time
= (uint32_t)(sensor_time_byte3
| sensor_time_byte2
| sensor_time_byte1
);
7363 /* Move the data index by 3 bytes */
7364 (*idx
) = (*idx
) + BMI2_SENSOR_TIME_LENGTH
;
7368 * @brief This internal API is used to reset the FIFO related configurations in
7369 * the FIFO frame structure for the next FIFO read.
7371 static void reset_fifo_frame_structure(struct bmi2_fifo_frame
*fifo
, const struct bmi2_dev
*dev
)
7373 /* Reset FIFO data structure */
7374 fifo
->acc_byte_start_idx
= 0;
7375 fifo
->aux_byte_start_idx
= 0;
7376 fifo
->gyr_byte_start_idx
= 0;
7377 fifo
->sensor_time
= 0;
7378 fifo
->skipped_frame_count
= 0;
7379 fifo
->act_recog_byte_start_idx
= 0;
7381 /* If S4S is enabled */
7382 if ((dev
->sens_en_stat
& BMI2_EXT_SENS_SEL
) == BMI2_EXT_SENS_SEL
)
7384 fifo
->acc_frm_len
= BMI2_FIFO_VIRT_ACC_LENGTH
;
7385 fifo
->gyr_frm_len
= BMI2_FIFO_VIRT_GYR_LENGTH
;
7386 fifo
->aux_frm_len
= BMI2_FIFO_VIRT_AUX_LENGTH
;
7387 fifo
->acc_gyr_frm_len
= BMI2_FIFO_VIRT_ACC_GYR_LENGTH
;
7388 fifo
->acc_aux_frm_len
= BMI2_FIFO_VIRT_ACC_AUX_LENGTH
;
7389 fifo
->aux_gyr_frm_len
= BMI2_FIFO_VIRT_GYR_AUX_LENGTH
;
7390 fifo
->all_frm_len
= BMI2_FIFO_VIRT_ALL_LENGTH
;
7392 /* If S4S is not enabled */
7396 fifo
->acc_frm_len
= BMI2_FIFO_ACC_LENGTH
;
7397 fifo
->gyr_frm_len
= BMI2_FIFO_GYR_LENGTH
;
7398 fifo
->aux_frm_len
= BMI2_FIFO_AUX_LENGTH
;
7399 fifo
->acc_gyr_frm_len
= BMI2_FIFO_ACC_GYR_LENGTH
;
7400 fifo
->acc_aux_frm_len
= BMI2_FIFO_ACC_AUX_LENGTH
;
7401 fifo
->aux_gyr_frm_len
= BMI2_FIFO_GYR_AUX_LENGTH
;
7402 fifo
->all_frm_len
= BMI2_FIFO_ALL_LENGTH
;
7407 * @brief This API internal checks whether the FIFO data read is an empty frame.
7408 * If empty frame, index is moved to the last byte.
7410 static int8_t check_empty_fifo(uint16_t *data_index
, const struct bmi2_fifo_frame
*fifo
)
7412 /* Variables to define error */
7413 int8_t rslt
= BMI2_OK
;
7415 /* Validate data index */
7416 if (((*data_index
) + 6) < fifo
->length
)
7418 /* Check if FIFO is empty */
7419 if (((fifo
->data
[(*data_index
)] == BMI2_FIFO_MSB_CONFIG_CHECK
) &&
7420 (fifo
->data
[(*data_index
) + 1] == BMI2_FIFO_LSB_CONFIG_CHECK
)) &&
7421 ((fifo
->data
[(*data_index
) + 2] == BMI2_FIFO_MSB_CONFIG_CHECK
) &&
7422 (fifo
->data
[(*data_index
) + 3] == BMI2_FIFO_LSB_CONFIG_CHECK
)) &&
7423 ((fifo
->data
[(*data_index
) + 4] == BMI2_FIFO_MSB_CONFIG_CHECK
) &&
7424 (fifo
->data
[(*data_index
) + 5] == BMI2_FIFO_LSB_CONFIG_CHECK
)))
7426 /* Move the data index to the last byte to mark completion */
7427 (*data_index
) = fifo
->length
;
7430 rslt
= BMI2_W_FIFO_EMPTY
;
7434 /* More frames could be read */
7435 rslt
= BMI2_W_PARTIAL_READ
;
7443 * @brief This internal API is used to move the data index ahead of the
7444 * current_frame_length parameter when unnecessary FIFO data appears while
7445 * extracting the user specified data.
7447 static int8_t move_next_frame(uint16_t *data_index
, uint8_t current_frame_length
, const struct bmi2_fifo_frame
*fifo
)
7449 /* Variables to define error */
7450 int8_t rslt
= BMI2_OK
;
7452 /* Validate data index */
7453 if (((*data_index
) + current_frame_length
) > fifo
->length
)
7455 /* Move the data index to the last byte */
7456 (*data_index
) = fifo
->length
;
7459 rslt
= BMI2_W_FIFO_EMPTY
;
7463 /* Move the data index to next frame */
7464 (*data_index
) = (*data_index
) + current_frame_length
;
7466 /* More frames could be read */
7467 rslt
= BMI2_W_PARTIAL_READ
;
7474 * @brief This internal API is used to parse and store the sensor time from the
7477 static int8_t unpack_sensortime_frame(uint16_t *data_index
, struct bmi2_fifo_frame
*fifo
)
7479 /* Variables to define error */
7480 int8_t rslt
= BMI2_OK
;
7482 /* Variables to define 3 bytes of sensor time */
7483 uint32_t sensor_time_byte3
= 0;
7484 uint16_t sensor_time_byte2
= 0;
7485 uint8_t sensor_time_byte1
= 0;
7487 /* Validate data index */
7488 if (((*data_index
) + BMI2_SENSOR_TIME_LENGTH
) > fifo
->length
)
7490 /* Move the data index to the last byte */
7491 (*data_index
) = fifo
->length
;
7494 rslt
= BMI2_W_FIFO_EMPTY
;
7498 /* Get sensor time from the FIFO data */
7499 sensor_time_byte3
= fifo
->data
[(*data_index
) + BMI2_SENSOR_TIME_MSB_BYTE
] << 16;
7500 sensor_time_byte2
= fifo
->data
[(*data_index
) + BMI2_SENSOR_TIME_XLSB_BYTE
] << 8;
7501 sensor_time_byte1
= fifo
->data
[(*data_index
)];
7503 /* Update sensor time in the FIFO structure */
7504 fifo
->sensor_time
= (uint32_t)(sensor_time_byte3
| sensor_time_byte2
| sensor_time_byte1
);
7506 /* Move the data index by 3 bytes */
7507 (*data_index
) = (*data_index
) + BMI2_SENSOR_TIME_LENGTH
;
7509 /* More frames could be read */
7510 rslt
= BMI2_W_PARTIAL_READ
;
7517 * @brief This internal API is used to parse and store the skipped frame count
7518 * from the FIFO data.
7520 static int8_t unpack_skipped_frame(uint16_t *data_index
, struct bmi2_fifo_frame
*fifo
)
7522 /* Variables to define error */
7523 int8_t rslt
= BMI2_OK
;
7525 /* Validate data index */
7526 if ((*data_index
) >= fifo
->length
)
7528 /* Update the data index to the last byte */
7529 (*data_index
) = fifo
->length
;
7532 rslt
= BMI2_W_FIFO_EMPTY
;
7536 /* Update skipped frame count in the FIFO structure */
7537 fifo
->skipped_frame_count
= fifo
->data
[(*data_index
)];
7539 /* Move the data index by 1 byte */
7540 (*data_index
) = (*data_index
) + 1;
7542 /* More frames could be read */
7543 rslt
= BMI2_W_PARTIAL_READ
;
7550 * @brief This internal API enables and configures the accelerometer which is
7551 * needed for self-test operation. It also sets the amplitude for the self-test.
7553 static int8_t pre_self_test_config(struct bmi2_dev
*dev
)
7555 /* Variable to define error */
7558 /* Structure to define sensor configurations */
7559 struct bmi2_sens_config sens_cfg
;
7561 /* List the sensors to be selected */
7562 uint8_t sens_sel
= BMI2_ACCEL
;
7564 /* Enable accelerometer */
7565 rslt
= bmi2_sensor_enable(&sens_sel
, 1, dev
);
7566 dev
->delay_us(1000, dev
->intf_ptr
);
7568 /* Enable self-test amplitude */
7569 if (rslt
== BMI2_OK
)
7571 rslt
= set_accel_self_test_amp(BMI2_ENABLE
, dev
);
7574 if (rslt
== BMI2_OK
)
7576 /* Select accelerometer for sensor configurations */
7577 sens_cfg
.type
= BMI2_ACCEL
;
7579 /* Get the default values */
7580 rslt
= bmi2_get_sensor_config(&sens_cfg
, 1, dev
);
7581 if (rslt
== BMI2_OK
)
7583 /* Set the configurations required for self-test */
7584 sens_cfg
.cfg
.acc
.odr
= BMI2_ACC_ODR_1600HZ
;
7585 sens_cfg
.cfg
.acc
.bwp
= BMI2_ACC_NORMAL_AVG4
;
7586 sens_cfg
.cfg
.acc
.filter_perf
= BMI2_PERF_OPT_MODE
;
7587 sens_cfg
.cfg
.acc
.range
= BMI2_ACC_RANGE_16G
;
7589 /* Set accelerometer configurations */
7590 rslt
= bmi2_set_sensor_config(&sens_cfg
, 1, dev
);
7598 * @brief This internal API performs the steps needed for self-test operation
7599 * before reading the accelerometer self-test data.
7601 static int8_t self_test_config(uint8_t sign
, struct bmi2_dev
*dev
)
7603 /* Variable to define error */
7606 /* Enable the accelerometer self-test feature */
7607 rslt
= set_accel_self_test_enable(BMI2_ENABLE
, dev
);
7608 if (rslt
== BMI2_OK
)
7610 /* Selects the sign of accelerometer self-test excitation */
7611 rslt
= set_acc_self_test_sign(sign
, dev
);
7618 * @brief This internal API enables or disables the accelerometer self-test
7619 * feature in the sensor.
7621 static int8_t set_accel_self_test_enable(uint8_t enable
, struct bmi2_dev
*dev
)
7623 /* Variable to define error */
7626 /* Variable to define data */
7629 /* Enable/Disable self-test feature */
7630 rslt
= bmi2_get_regs(BMI2_ACC_SELF_TEST_ADDR
, &data
, 1, dev
);
7631 if (rslt
== BMI2_OK
)
7633 data
= BMI2_SET_BIT_POS0(data
, BMI2_ACC_SELF_TEST_EN
, enable
);
7634 rslt
= bmi2_set_regs(BMI2_ACC_SELF_TEST_ADDR
, &data
, 1, dev
);
7641 * @brief This internal API selects the sign for accelerometer self-test
7644 static int8_t set_acc_self_test_sign(uint8_t sign
, struct bmi2_dev
*dev
)
7646 /* Variable to define error */
7649 /* Variable to define data */
7652 /* Select the sign for self-test excitation */
7653 rslt
= bmi2_get_regs(BMI2_ACC_SELF_TEST_ADDR
, &data
, 1, dev
);
7654 if (rslt
== BMI2_OK
)
7656 data
= BMI2_SET_BITS(data
, BMI2_ACC_SELF_TEST_SIGN
, sign
);
7657 rslt
= bmi2_set_regs(BMI2_ACC_SELF_TEST_ADDR
, &data
, 1, dev
);
7664 * @brief This internal API sets the amplitude of the accelerometer self-test
7665 * deflection in the sensor.
7667 static int8_t set_accel_self_test_amp(uint8_t amp
, struct bmi2_dev
*dev
)
7669 /* Variable to define error */
7672 /* Variable to define data */
7675 /* Select amplitude of the self-test deflection */
7676 rslt
= bmi2_get_regs(BMI2_ACC_SELF_TEST_ADDR
, &data
, 1, dev
);
7677 if (rslt
== BMI2_OK
)
7679 data
= BMI2_SET_BITS(data
, BMI2_ACC_SELF_TEST_AMP
, amp
);
7680 rslt
= bmi2_set_regs(BMI2_ACC_SELF_TEST_ADDR
, &data
, 1, dev
);
7687 * @brief This internal API reads the accelerometer data for x,y and z axis from
7688 * the sensor. The data units is in LSB format.
7690 static int8_t read_accel_xyz(struct bmi2_sens_axes_data
*accel
, struct bmi2_dev
*dev
)
7692 /* Variable to define error */
7695 /* Variable to define LSB */
7698 /* Variable to define MSB */
7701 /* Array to define data buffer */
7702 uint8_t data
[BMI2_ACC_GYR_NUM_BYTES
] = { 0 };
7704 rslt
= bmi2_get_regs(BMI2_ACC_X_LSB_ADDR
, data
, BMI2_ACC_GYR_NUM_BYTES
, dev
);
7705 if (rslt
== BMI2_OK
)
7707 /* Accelerometer data x axis */
7710 accel
->x
= (int16_t)((msb
<< 8) | lsb
);
7712 /* Accelerometer data y axis */
7715 accel
->y
= (int16_t)((msb
<< 8) | lsb
);
7717 /* Accelerometer data z axis */
7720 accel
->z
= (int16_t)((msb
<< 8) | lsb
);
7727 * @brief This internal API reads the gyroscope data for x, y and z axis from
7728 * the sensor. The data units is in LSB format.
7730 static int8_t read_gyro_xyz(struct bmi2_sens_axes_data
*gyro
, struct bmi2_dev
*dev
)
7732 /* Variable to define error */
7735 /* Variable to define LSB */
7738 /* Variable to define MSB */
7741 /* Array to define data buffer */
7742 uint8_t data
[BMI2_ACC_GYR_NUM_BYTES
] = { 0 };
7744 rslt
= bmi2_get_regs(BMI2_GYR_X_LSB_ADDR
, data
, BMI2_ACC_GYR_NUM_BYTES
, dev
);
7745 if (rslt
== BMI2_OK
)
7747 /* Gyroscope data x axis */
7750 gyro
->x
= (int16_t)((msb
<< 8) | lsb
);
7752 /* Gyroscope data y axis */
7755 gyro
->y
= (int16_t)((msb
<< 8) | lsb
);
7757 /* Gyroscope data z axis */
7760 gyro
->z
= (int16_t)((msb
<< 8) | lsb
);
7767 * @brief This internal API converts LSB value of accelerometer axes to form
7768 * 'g' to 'mg' for self-test.
7770 static void convert_lsb_g(const struct bmi2_selftest_delta_limit
*acc_data_diff
,
7771 struct bmi2_selftest_delta_limit
*acc_data_diff_mg
,
7772 const struct bmi2_dev
*dev
)
7774 /* Variable to define LSB/g value of axes */
7777 /* Range considered for self-test is +/-16g */
7778 uint8_t range
= BMI2_ACC_SELF_TEST_RANGE
;
7780 /* lsb_per_g for the respective resolution and 16g range */
7781 lsb_per_g
= (uint32_t)(power(2, dev
->resolution
) / (2 * range
));
7783 /* Accelerometer x value in mg */
7784 acc_data_diff_mg
->x
= (acc_data_diff
->x
/ (int32_t) lsb_per_g
) * 1000;
7786 /* Accelerometer y value in mg */
7787 acc_data_diff_mg
->y
= (acc_data_diff
->y
/ (int32_t) lsb_per_g
) * 1000;
7789 /* Accelerometer z value in mg */
7790 acc_data_diff_mg
->z
= (acc_data_diff
->z
/ (int32_t) lsb_per_g
) * 1000;
7794 * @brief This internal API is used to calculate the power of a value.
7796 static int32_t power(int16_t base
, uint8_t resolution
)
7798 /* Initialize loop */
7801 /* Initialize variable to store the power of 2 value */
7804 for (; loop
<= resolution
; loop
++)
7806 value
= (int32_t)(value
* base
);
7813 * @brief This internal API validates the accelerometer self-test data and
7814 * decides the result of self-test operation.
7816 static int8_t validate_self_test(const struct bmi2_selftest_delta_limit
*accel_data_diff
)
7818 /* Variable to define error */
7821 /* As per the data sheet, The actually measured signal differences should be significantly
7822 * larger than the minimum differences for each axis in order for the self-test to pass.
7824 if ((accel_data_diff
->x
> BMI2_ST_ACC_X_SIG_MIN_DIFF
) && (accel_data_diff
->y
< BMI2_ST_ACC_Y_SIG_MIN_DIFF
) &&
7825 (accel_data_diff
->z
> BMI2_ST_ACC_Z_SIG_MIN_DIFF
))
7827 /* Self-test pass */
7833 rslt
= BMI2_E_SELF_TEST_FAIL
;
7840 * @brief This internal API gets the re-mapped x, y and z axes from the sensor.
7842 static int8_t get_remap_axes(struct bmi2_axes_remap
*remap
, struct bmi2_dev
*dev
)
7844 /* Variable to define error */
7845 int8_t rslt
= BMI2_OK
;
7847 /* Array to define the feature configuration */
7848 uint8_t feat_config
[BMI2_FEAT_SIZE_IN_BYTES
] = { 0 };
7850 /* Variable to define the array offset */
7853 /* Variable to set flag */
7856 /* Initialize feature configuration for axis re-mapping */
7857 struct bmi2_feature_config remap_config
= { 0, 0, 0 };
7859 /* Variable to get the status of advance power save */
7862 /* Get status of advance power save mode */
7863 aps_stat
= dev
->aps_status
;
7864 if (aps_stat
== BMI2_ENABLE
)
7866 /* Disable advance power save if enabled */
7867 rslt
= bmi2_set_adv_power_save(BMI2_DISABLE
, dev
);
7870 if (rslt
== BMI2_OK
)
7872 /* Search for axis re-mapping and extract its configuration details */
7873 feat_found
= bmi2_extract_input_feat_config(&remap_config
, BMI2_AXIS_MAP
, dev
);
7876 rslt
= bmi2_get_feat_config(remap_config
.page
, feat_config
, dev
);
7877 if (rslt
== BMI2_OK
)
7879 /* Define the offset for axis re-mapping */
7880 idx
= remap_config
.start_addr
;
7882 /* Get the re-mapped x-axis */
7883 remap
->x_axis
= BMI2_GET_BIT_POS0(feat_config
[idx
], BMI2_X_AXIS
);
7885 /* Get the re-mapped x-axis polarity */
7886 remap
->x_axis_sign
= BMI2_GET_BITS(feat_config
[idx
], BMI2_X_AXIS_SIGN
);
7888 /* Get the re-mapped y-axis */
7889 remap
->y_axis
= BMI2_GET_BITS(feat_config
[idx
], BMI2_Y_AXIS
);
7891 /* Get the re-mapped y-axis polarity */
7892 remap
->y_axis_sign
= BMI2_GET_BITS(feat_config
[idx
], BMI2_Y_AXIS_SIGN
);
7894 /* Get the re-mapped z-axis */
7895 remap
->z_axis
= BMI2_GET_BITS(feat_config
[idx
], BMI2_Z_AXIS
);
7897 /* Increment byte to fetch the next data */
7900 /* Get the re-mapped z-axis polarity */
7901 remap
->z_axis_sign
= BMI2_GET_BIT_POS0(feat_config
[idx
], BMI2_Z_AXIS_SIGN
);
7906 rslt
= BMI2_E_INVALID_SENSOR
;
7909 /* Enable Advance power save if disabled while configuring and
7910 * not when already disabled
7912 if ((aps_stat
== BMI2_ENABLE
) && (rslt
== BMI2_OK
))
7914 rslt
= bmi2_set_adv_power_save(BMI2_ENABLE
, dev
);
7922 * @brief This internal API sets the re-mapped x, y and z axes in the sensor.
7924 static int8_t set_remap_axes(const struct bmi2_axes_remap
*remap
, struct bmi2_dev
*dev
)
7926 /* Variable to define error */
7927 int8_t rslt
= BMI2_OK
;
7929 /* Array to define the feature configuration */
7930 uint8_t feat_config
[BMI2_FEAT_SIZE_IN_BYTES
] = { 0 };
7932 /* Variable to define the array offset */
7935 /* Variable to define the register address */
7936 uint8_t reg_addr
= 0;
7938 /* Variable to set the re-mapped x-axes in the sensor */
7941 /* Variable to set the re-mapped y-axes in the sensor */
7944 /* Variable to set the re-mapped z-axes in the sensor */
7947 /* Variable to set the re-mapped x-axes sign in the sensor */
7948 uint8_t x_axis_sign
= 0;
7950 /* Variable to set the re-mapped y-axes sign in the sensor */
7951 uint8_t y_axis_sign
= 0;
7953 /* Variable to set the re-mapped z-axes sign in the sensor */
7954 uint8_t z_axis_sign
= 0;
7956 /* Variable to set flag */
7959 /* Initialize feature configuration for axis re-mapping */
7960 struct bmi2_feature_config remap_config
= { 0, 0, 0 };
7962 /* Variable to get the status of advance power save */
7965 /* Get status of advance power save mode */
7966 aps_stat
= dev
->aps_status
;
7967 if (aps_stat
== BMI2_ENABLE
)
7969 /* Disable advance power save if enabled */
7970 rslt
= bmi2_set_adv_power_save(BMI2_DISABLE
, dev
);
7973 if (rslt
== BMI2_OK
)
7975 /* Search for axis-re-mapping and extract its configuration details */
7976 feat_found
= bmi2_extract_input_feat_config(&remap_config
, BMI2_AXIS_MAP
, dev
);
7979 /* Get the configuration from the page where axis re-mapping feature resides */
7980 rslt
= bmi2_get_feat_config(remap_config
.page
, feat_config
, dev
);
7981 if (rslt
== BMI2_OK
)
7983 /* Define the offset in bytes */
7984 idx
= remap_config
.start_addr
;
7986 /* Set the value of re-mapped x-axis */
7987 x_axis
= remap
->x_axis
& BMI2_X_AXIS_MASK
;
7989 /* Set the value of re-mapped x-axis sign */
7990 x_axis_sign
= ((remap
->x_axis_sign
<< BMI2_X_AXIS_SIGN_POS
) & BMI2_X_AXIS_SIGN_MASK
);
7992 /* Set the value of re-mapped y-axis */
7993 y_axis
= ((remap
->y_axis
<< BMI2_Y_AXIS_POS
) & BMI2_Y_AXIS_MASK
);
7995 /* Set the value of re-mapped y-axis sign */
7996 y_axis_sign
= ((remap
->y_axis_sign
<< BMI2_Y_AXIS_SIGN_POS
) & BMI2_Y_AXIS_SIGN_MASK
);
7998 /* Set the value of re-mapped z-axis */
7999 z_axis
= ((remap
->z_axis
<< BMI2_Z_AXIS_POS
) & BMI2_Z_AXIS_MASK
);
8001 /* Set the value of re-mapped z-axis sign */
8002 z_axis_sign
= remap
->z_axis_sign
& BMI2_Z_AXIS_SIGN_MASK
;
8004 /* Arrange axes in the first byte */
8005 feat_config
[idx
] = x_axis
| x_axis_sign
| y_axis
| y_axis_sign
| z_axis
;
8007 /* Increment the index */
8010 /* Cannot OR in the second byte since it holds
8011 * gyroscope self-offset correction bit
8013 feat_config
[idx
] = BMI2_SET_BIT_POS0(feat_config
[idx
], BMI2_Z_AXIS_SIGN
, z_axis_sign
);
8015 /* Update the register address */
8016 reg_addr
= BMI2_FEATURES_REG_ADDR
+ remap_config
.start_addr
;
8018 /* Set the configuration back to the page */
8019 rslt
= bmi2_set_regs(reg_addr
, &feat_config
[remap_config
.start_addr
], 2, dev
);
8024 rslt
= BMI2_E_INVALID_SENSOR
;
8027 /* Enable Advance power save if disabled while configuring and
8028 * not when already disabled
8030 if ((aps_stat
== BMI2_ENABLE
) && (rslt
== BMI2_OK
))
8032 rslt
= bmi2_set_adv_power_save(BMI2_ENABLE
, dev
);
8040 * @brief This internal API corrects the gyroscope cross-axis sensitivity
8041 * between the z and the x axis.
8043 static void comp_gyro_cross_axis_sensitivity(struct bmi2_sens_axes_data
*gyr_data
, const struct bmi2_dev
*dev
)
8045 /* Get the compensated gyroscope x-axis */
8046 gyr_data
->x
= gyr_data
->x
- (int16_t)(((int32_t) dev
->gyr_cross_sens_zx
* (int32_t) gyr_data
->z
) / 512);
8050 * @brief This internal API is used to validate the boundary conditions.
8052 static int8_t check_boundary_val(uint8_t *val
, uint8_t min
, uint8_t max
, struct bmi2_dev
*dev
)
8054 /* Variable to define error */
8055 int8_t rslt
= BMI2_OK
;
8059 /* Check if value is below minimum value */
8062 /* Auto correct the invalid value to minimum value */
8064 dev
->info
|= BMI2_I_MIN_VALUE
;
8067 /* Check if value is above maximum value */
8070 /* Auto correct the invalid value to maximum value */
8072 dev
->info
|= BMI2_I_MAX_VALUE
;
8077 rslt
= BMI2_E_NULL_PTR
;
8084 * @brief This internal API saves the configurations before performing FOC.
8086 static int8_t save_accel_foc_config(struct bmi2_accel_config
*acc_cfg
,
8089 struct bmi2_dev
*dev
)
8091 /* Variable to define error */
8094 /* Variable to get the status from PWR_CTRL register */
8095 uint8_t pwr_ctrl_data
= 0;
8097 /* Get accelerometer configurations to be saved */
8098 rslt
= get_accel_config(acc_cfg
, dev
);
8099 if (rslt
== BMI2_OK
)
8101 /* Get accelerometer enable status to be saved */
8102 rslt
= bmi2_get_regs(BMI2_PWR_CTRL_ADDR
, &pwr_ctrl_data
, 1, dev
);
8103 *acc_en
= BMI2_GET_BITS(pwr_ctrl_data
, BMI2_ACC_EN
);
8105 /* Get advance power save mode to be saved */
8106 if (rslt
== BMI2_OK
)
8108 rslt
= bmi2_get_adv_power_save(aps
, dev
);
8116 * @brief This internal sets configurations for performing accelerometer FOC.
8118 static int8_t set_accel_foc_config(struct bmi2_dev
*dev
)
8120 /* Variable to define error */
8123 /* Variable to select the sensor */
8124 uint8_t sens_list
= BMI2_ACCEL
;
8126 /* Variable to set the accelerometer configuration value */
8127 uint8_t acc_conf_data
= BMI2_FOC_ACC_CONF_VAL
;
8129 /* Disabling offset compensation */
8130 rslt
= set_accel_offset_comp(BMI2_DISABLE
, dev
);
8131 if (rslt
== BMI2_OK
)
8133 /* Set accelerometer configurations to 50Hz, continuous mode, CIC mode */
8134 rslt
= bmi2_set_regs(BMI2_ACC_CONF_ADDR
, &acc_conf_data
, 1, dev
);
8135 if (rslt
== BMI2_OK
)
8137 /* Set accelerometer to normal mode by enabling it */
8138 rslt
= bmi2_sensor_enable(&sens_list
, 1, dev
);
8140 if (rslt
== BMI2_OK
)
8142 /* Disable advance power save mode */
8143 rslt
= bmi2_set_adv_power_save(BMI2_DISABLE
, dev
);
8152 * @brief This internal API performs Fast Offset Compensation for accelerometer.
8154 static int8_t perform_accel_foc(const struct bmi2_accel_foc_g_value
*accel_g_value
,
8155 const struct bmi2_accel_config
*acc_cfg
,
8156 struct bmi2_dev
*dev
)
8158 /* Variable to define error */
8159 int8_t rslt
= BMI2_E_INVALID_STATUS
;
8161 /* Variable to define count */
8164 /* Variable to store status read from the status register */
8165 uint8_t reg_status
= 0;
8167 /* Array of structure to store accelerometer data */
8168 struct bmi2_sens_axes_data accel_value
[128] = { { 0 } };
8170 /* Structure to store accelerometer data temporarily */
8171 struct bmi2_foc_temp_value temp
= { 0, 0, 0 };
8173 /* Structure to store the average of accelerometer data */
8174 struct bmi2_sens_axes_data accel_avg
= { 0, 0, 0, 0 };
8176 /* Variable to define LSB per g value */
8177 uint16_t lsb_per_g
= 0;
8179 /* Variable to define range */
8182 /* Structure to store accelerometer data deviation from ideal value */
8183 struct bmi2_offset_delta delta
= { 0, 0, 0 };
8185 /* Structure to store accelerometer offset values */
8186 struct bmi2_accel_offset offset
= { 0, 0, 0 };
8188 /* Variable tries max 5 times for interrupt then generates timeout */
8191 for (loop
= 0; loop
< 128; loop
++)
8194 while (try_cnt
&& (!(reg_status
& BMI2_DRDY_ACC
)))
8196 /* 20ms delay for 50Hz ODR */
8197 dev
->delay_us(20000, dev
->intf_ptr
);
8198 rslt
= bmi2_get_status(®_status
, dev
);
8202 if ((rslt
== BMI2_OK
) && (reg_status
& BMI2_DRDY_ACC
))
8204 rslt
= read_accel_xyz(&accel_value
[loop
], dev
);
8207 if (rslt
== BMI2_OK
)
8209 rslt
= read_accel_xyz(&accel_value
[loop
], dev
);
8212 if (rslt
== BMI2_OK
)
8214 /* Store the data in a temporary structure */
8215 temp
.x
= temp
.x
+ (int32_t)accel_value
[loop
].x
;
8216 temp
.y
= temp
.y
+ (int32_t)accel_value
[loop
].y
;
8217 temp
.z
= temp
.z
+ (int32_t)accel_value
[loop
].z
;
8225 if (rslt
== BMI2_OK
)
8227 /* Take average of x, y and z data for lesser noise */
8228 accel_avg
.x
= (int16_t)(temp
.x
/ 128);
8229 accel_avg
.y
= (int16_t)(temp
.y
/ 128);
8230 accel_avg
.z
= (int16_t)(temp
.z
/ 128);
8232 /* Get the exact range value */
8233 map_accel_range(acc_cfg
->range
, &range
);
8235 /* Get the smallest possible measurable acceleration level given the range and
8237 lsb_per_g
= (uint16_t)(power(2, dev
->resolution
) / (2 * range
));
8239 /* Compensate acceleration data against gravity */
8240 comp_for_gravity(lsb_per_g
, accel_g_value
, &accel_avg
, &delta
);
8242 /* Scale according to offset register resolution */
8243 scale_accel_offset(range
, &delta
, &offset
);
8245 /* Invert the accelerometer offset data */
8246 invert_accel_offset(&offset
);
8248 /* Write offset data in the offset compensation register */
8249 rslt
= write_accel_offset(&offset
, dev
);
8251 /* Enable offset compensation */
8252 if (rslt
== BMI2_OK
)
8254 rslt
= set_accel_offset_comp(BMI2_ENABLE
, dev
);
8262 * @brief This internal API enables/disables the offset compensation for
8263 * filtered and un-filtered accelerometer data.
8265 static int8_t set_accel_offset_comp(uint8_t offset_en
, struct bmi2_dev
*dev
)
8267 /* Variable to define error */
8270 /* Variable to store data */
8273 /* Enable/Disable offset compensation */
8274 rslt
= bmi2_get_regs(BMI2_NV_CONF_ADDR
, &data
, 1, dev
);
8275 if (rslt
== BMI2_OK
)
8277 data
= BMI2_SET_BITS(data
, BMI2_NV_ACC_OFFSET
, offset_en
);
8278 rslt
= bmi2_set_regs(BMI2_NV_CONF_ADDR
, &data
, 1, dev
);
8285 * @brief This internal API converts the accelerometer range value into
8286 * corresponding integer value.
8288 static void map_accel_range(uint8_t range_in
, uint8_t *range_out
)
8292 case BMI2_ACC_RANGE_2G
:
8295 case BMI2_ACC_RANGE_4G
:
8298 case BMI2_ACC_RANGE_8G
:
8301 case BMI2_ACC_RANGE_16G
:
8306 /* By default RANGE 8G is set */
8313 * @brief This internal API compensate the accelerometer data against gravity.
8315 static void comp_for_gravity(uint16_t lsb_per_g
,
8316 const struct bmi2_accel_foc_g_value
*g_val
,
8317 const struct bmi2_sens_axes_data
*data
,
8318 struct bmi2_offset_delta
*comp_data
)
8320 /* Array to store the accelerometer values in LSB */
8321 int16_t accel_value_lsb
[3] = { 0 };
8323 /* Convert g-value to LSB */
8324 accel_value_lsb
[BMI2_X_AXIS
] = (int16_t)(lsb_per_g
* g_val
->x
);
8325 accel_value_lsb
[BMI2_Y_AXIS
] = (int16_t)(lsb_per_g
* g_val
->y
);
8326 accel_value_lsb
[BMI2_Z_AXIS
] = (int16_t)(lsb_per_g
* g_val
->z
);
8328 /* Get the compensated values for X, Y and Z axis */
8329 comp_data
->x
= (data
->x
- accel_value_lsb
[BMI2_X_AXIS
]);
8330 comp_data
->y
= (data
->y
- accel_value_lsb
[BMI2_Y_AXIS
]);
8331 comp_data
->z
= (data
->z
- accel_value_lsb
[BMI2_Z_AXIS
]);
8335 * @brief This internal API scales the compensated accelerometer data according
8336 * to the offset register resolution.
8338 * @note The bit position is always greater than 0 since accelerometer data is
8341 static void scale_accel_offset(uint8_t range
, const struct bmi2_offset_delta
*comp_data
, struct bmi2_accel_offset
*data
)
8343 /* Variable to store the position of bit having 3.9mg resolution */
8344 int8_t bit_pos_3_9mg
;
8346 /* Variable to store the position previous of bit having 3.9mg resolution */
8347 int8_t bit_pos_3_9mg_prev_bit
;
8349 /* Variable to store the round-off value */
8352 /* Find the bit position of 3.9mg */
8353 bit_pos_3_9mg
= get_bit_pos_3_9mg(range
);
8355 /* Round off, consider if the next bit is high */
8356 bit_pos_3_9mg_prev_bit
= bit_pos_3_9mg
- 1;
8357 round_off
= (uint8_t)(power(2, ((uint8_t) bit_pos_3_9mg_prev_bit
)));
8359 /* Scale according to offset register resolution */
8360 data
->x
= (uint8_t)((comp_data
->x
+ round_off
) / power(2, ((uint8_t) bit_pos_3_9mg
)));
8361 data
->y
= (uint8_t)((comp_data
->y
+ round_off
) / power(2, ((uint8_t) bit_pos_3_9mg
)));
8362 data
->z
= (uint8_t)((comp_data
->z
+ round_off
) / power(2, ((uint8_t) bit_pos_3_9mg
)));
8366 * @brief This internal API finds the bit position of 3.9mg according to given
8367 * range and resolution.
8369 static int8_t get_bit_pos_3_9mg(uint8_t range
)
8371 /* Variable to store the bit position of 3.9mg resolution */
8372 int8_t bit_pos_3_9mg
;
8374 /* Variable to shift the bits according to the resolution */
8375 uint32_t divisor
= 1;
8377 /* Scaling factor to get the bit position of 3.9 mg resolution */
8378 int16_t scale_factor
= -1;
8380 /* Variable to store temporary value */
8383 /* Shift left by the times of resolution */
8384 divisor
= divisor
<< 16;
8386 /* Get the bit position to be shifted */
8387 temp
= (uint16_t)(divisor
/ (range
* 256));
8389 /* Get the scaling factor until bit position is shifted to last bit */
8396 /* Scaling factor is the bit position of 3.9 mg resolution */
8397 bit_pos_3_9mg
= (int8_t) scale_factor
;
8399 return bit_pos_3_9mg
;
8403 * @brief This internal API inverts the accelerometer offset data.
8405 static void invert_accel_offset(struct bmi2_accel_offset
*offset_data
)
8407 /* Get the offset data */
8408 offset_data
->x
= (uint8_t)((offset_data
->x
) * (-1));
8409 offset_data
->y
= (uint8_t)((offset_data
->y
) * (-1));
8410 offset_data
->z
= (uint8_t)((offset_data
->z
) * (-1));
8414 * @brief This internal API writes the offset data in the offset compensation
8417 static int8_t write_accel_offset(const struct bmi2_accel_offset
*offset
, struct bmi2_dev
*dev
)
8419 /* Variable to define error */
8422 /* Array to store the offset data */
8423 uint8_t data_array
[3] = { 0 };
8425 data_array
[0] = offset
->x
;
8426 data_array
[1] = offset
->y
;
8427 data_array
[2] = offset
->z
;
8429 /* Offset values are written in the offset register */
8430 rslt
= bmi2_set_regs(BMI2_ACC_OFF_COMP_0_ADDR
, data_array
, 3, dev
);
8436 * @brief This internal API restores the configurations saved before performing
8437 * accelerometer FOC.
8439 static int8_t restore_accel_foc_config(struct bmi2_accel_config
*acc_cfg
,
8442 struct bmi2_dev
*dev
)
8444 /* Variable to define error */
8447 /* Variable to get the status from PWR_CTRL register */
8448 uint8_t pwr_ctrl_data
= 0;
8450 /* Restore the saved accelerometer configurations */
8451 rslt
= set_accel_config(acc_cfg
, dev
);
8452 if (rslt
== BMI2_OK
)
8454 /* Restore the saved accelerometer enable status */
8455 rslt
= bmi2_get_regs(BMI2_PWR_CTRL_ADDR
, &pwr_ctrl_data
, 1, dev
);
8456 if (rslt
== BMI2_OK
)
8458 pwr_ctrl_data
= BMI2_SET_BITS(pwr_ctrl_data
, BMI2_ACC_EN
, acc_en
);
8459 rslt
= bmi2_set_regs(BMI2_PWR_CTRL_ADDR
, &pwr_ctrl_data
, 1, dev
);
8461 /* Restore the saved advance power save */
8462 if (rslt
== BMI2_OK
)
8464 rslt
= bmi2_set_adv_power_save(aps
, dev
);
8473 * @brief This internal API sets accelerometer configurations like ODR,
8474 * bandwidth, performance mode and g-range.
8476 static int8_t set_accel_config(struct bmi2_accel_config
*config
, struct bmi2_dev
*dev
)
8478 /* Variable to define error */
8481 /* Variable to store data */
8484 /* Array to store the default value of accelerometer configuration
8485 * reserved registers
8487 uint8_t data_array
[2] = { 0 };
8489 /* Validate bandwidth and performance mode */
8490 rslt
= validate_bw_perf_mode(&config
->bwp
, &config
->filter_perf
, dev
);
8491 if (rslt
== BMI2_OK
)
8493 /* Validate ODR and range */
8494 rslt
= validate_odr_range(&config
->odr
, &config
->range
, dev
);
8495 if (rslt
== BMI2_OK
)
8497 /* Set accelerometer performance mode */
8498 reg_data
= BMI2_SET_BITS(data_array
[0], BMI2_ACC_FILTER_PERF_MODE
, config
->filter_perf
);
8500 /* Set accelerometer bandwidth */
8501 reg_data
= BMI2_SET_BITS(reg_data
, BMI2_ACC_BW_PARAM
, config
->bwp
);
8503 /* Set accelerometer ODR */
8504 reg_data
= BMI2_SET_BIT_POS0(reg_data
, BMI2_ACC_ODR
, config
->odr
);
8506 /* Copy the register data to the array */
8507 data_array
[0] = reg_data
;
8509 /* Set accelerometer range */
8510 reg_data
= BMI2_SET_BIT_POS0(data_array
[1], BMI2_ACC_RANGE
, config
->range
);
8512 /* Copy the register data to the array */
8513 data_array
[1] = reg_data
;
8515 /* Write accelerometer configuration to ACC_CONFand
8516 * ACC_RANGE registers simultaneously as they lie in consecutive places
8518 rslt
= bmi2_set_regs(BMI2_ACC_CONF_ADDR
, data_array
, 2, dev
);
8520 /* Get error status to check for invalid configurations */
8521 if (rslt
== BMI2_OK
)
8523 rslt
= cfg_error_status(dev
);
8532 * @brief This internal API sets gyroscope configurations like ODR, bandwidth,
8533 * low power/high performance mode, performance mode and range. It also
8534 * maps/un-maps data interrupts to that of hardware interrupt line.
8536 static int8_t set_gyro_config(struct bmi2_gyro_config
*config
, struct bmi2_dev
*dev
)
8538 /* Variable to define error */
8541 /* Variable to store data */
8544 /* Array to store the default value of gyroscope configuration reserved registers */
8545 uint8_t data_array
[2] = { 0 };
8547 /* Validate gyroscope configurations */
8548 rslt
= validate_gyro_config(config
, dev
);
8549 if (rslt
== BMI2_OK
)
8551 /* Set gyroscope performance mode */
8552 reg_data
= BMI2_SET_BITS(data_array
[0], BMI2_GYR_FILTER_PERF_MODE
, config
->filter_perf
);
8554 /* Set gyroscope noise performance mode */
8555 reg_data
= BMI2_SET_BITS(reg_data
, BMI2_GYR_NOISE_PERF_MODE
, config
->noise_perf
);
8557 /* Set gyroscope bandwidth */
8558 reg_data
= BMI2_SET_BITS(reg_data
, BMI2_GYR_BW_PARAM
, config
->bwp
);
8560 /* Set gyroscope ODR */
8561 reg_data
= BMI2_SET_BIT_POS0(reg_data
, BMI2_GYR_ODR
, config
->odr
);
8563 /* Copy the register data to the array */
8564 data_array
[0] = reg_data
;
8566 /* Set gyroscope OIS range */
8567 reg_data
= BMI2_SET_BITS(data_array
[1], BMI2_GYR_OIS_RANGE
, config
->ois_range
);
8569 /* Set gyroscope range */
8570 reg_data
= BMI2_SET_BIT_POS0(reg_data
, BMI2_GYR_RANGE
, config
->range
);
8572 /* Copy the register data to the array */
8573 data_array
[1] = reg_data
;
8575 /* Write accelerometer configuration to GYR_CONF and GYR_RANGE
8576 * registers simultaneously as they lie in consecutive places
8578 rslt
= bmi2_set_regs(BMI2_GYR_CONF_ADDR
, data_array
, 2, dev
);
8580 /* Get error status to check for invalid configurations */
8581 if (rslt
== BMI2_OK
)
8583 rslt
= cfg_error_status(dev
);
8591 * @brief This internal API saves the configurations before performing gyroscope
8594 static int8_t save_gyro_config(struct bmi2_gyro_config
*gyr_cfg
, uint8_t *aps
, uint8_t *gyr_en
, struct bmi2_dev
*dev
)
8596 /* Variable to define error */
8599 /* Variable to get the status from PWR_CTRL register */
8600 uint8_t pwr_ctrl_data
= 0;
8602 /* Get gyroscope configurations to be saved */
8603 rslt
= get_gyro_config(gyr_cfg
, dev
);
8604 if (rslt
== BMI2_OK
)
8606 /* Get gyroscope enable status to be saved */
8607 rslt
= bmi2_get_regs(BMI2_PWR_CTRL_ADDR
, &pwr_ctrl_data
, 1, dev
);
8608 *gyr_en
= BMI2_GET_BITS(pwr_ctrl_data
, BMI2_GYR_EN
);
8610 /* Get advance power save mode to be saved */
8611 if (rslt
== BMI2_OK
)
8613 rslt
= bmi2_get_adv_power_save(aps
, dev
);
8621 * @brief This internal sets configurations for performing gyroscope FOC.
8623 static int8_t set_gyro_foc_config(struct bmi2_dev
*dev
)
8627 /* Variable to select the sensor */
8628 uint8_t sens_list
= BMI2_GYRO
;
8630 /* Array to set the gyroscope configuration value (ODR, Performance mode
8631 * and bandwidth) and gyroscope range
8633 uint8_t gyr_conf_data
[2] = { BMI2_FOC_GYR_CONF_VAL
, BMI2_GYR_RANGE_2000
};
8635 /* Disabling gyroscope offset compensation */
8636 rslt
= bmi2_set_gyro_offset_comp(BMI2_DISABLE
, dev
);
8637 if (rslt
== BMI2_OK
)
8639 /* Set gyroscope configurations to 25Hz, continuous mode,
8640 * CIC mode, and 2000 dps range
8642 rslt
= bmi2_set_regs(BMI2_GYR_CONF_ADDR
, gyr_conf_data
, 2, dev
);
8643 if (rslt
== BMI2_OK
)
8645 /* Set gyroscope to normal mode by enabling it */
8646 rslt
= bmi2_sensor_enable(&sens_list
, 1, dev
);
8648 if (rslt
== BMI2_OK
)
8650 /* Disable advance power save mode */
8651 rslt
= bmi2_set_adv_power_save(BMI2_DISABLE
, dev
);
8660 * @brief This internal API inverts the gyroscope offset data.
8662 static void invert_gyro_offset(struct bmi2_sens_axes_data
*offset_data
)
8664 /* Invert the values */
8665 offset_data
->x
= (int16_t)((offset_data
->x
) * (-1));
8666 offset_data
->y
= (int16_t)((offset_data
->y
) * (-1));
8667 offset_data
->z
= (int16_t)((offset_data
->z
) * (-1));
8671 * @brief This internal API restores the gyroscope configurations saved
8672 * before performing FOC.
8674 static int8_t restore_gyro_config(struct bmi2_gyro_config
*gyr_cfg
, uint8_t aps
, uint8_t gyr_en
, struct bmi2_dev
*dev
)
8677 uint8_t pwr_ctrl_data
= 0;
8679 /* Restore the saved gyroscope configurations */
8680 rslt
= set_gyro_config(gyr_cfg
, dev
);
8681 if (rslt
== BMI2_OK
)
8683 /* Restore the saved gyroscope enable status */
8684 rslt
= bmi2_get_regs(BMI2_PWR_CTRL_ADDR
, &pwr_ctrl_data
, 1, dev
);
8685 if (rslt
== BMI2_OK
)
8687 pwr_ctrl_data
= BMI2_SET_BITS(pwr_ctrl_data
, BMI2_GYR_EN
, gyr_en
);
8688 rslt
= bmi2_set_regs(BMI2_PWR_CTRL_ADDR
, &pwr_ctrl_data
, 1, dev
);
8690 /* Restore the saved advance power save */
8691 if (rslt
== BMI2_OK
)
8693 rslt
= bmi2_set_adv_power_save(aps
, dev
);
8702 * @brief This internal API saturates the gyroscope data value before writing to
8703 * to 10 bit offset register.
8705 static void saturate_gyro_data(struct bmi2_sens_axes_data
*gyr_off
)
8707 if (gyr_off
->x
> 511)
8712 if (gyr_off
->x
< -512)
8717 if (gyr_off
->y
> 511)
8722 if (gyr_off
->y
< -512)
8727 if (gyr_off
->z
> 511)
8732 if (gyr_off
->z
< -512)
8739 * @brief This internal API is used to validate the device structure pointer for
8742 static int8_t null_ptr_check(const struct bmi2_dev
*dev
)
8744 int8_t rslt
= BMI2_OK
;
8746 if ((dev
== NULL
) || (dev
->read
== NULL
) || (dev
->write
== NULL
) || (dev
->delay_us
== NULL
))
8748 /* Device structure pointer is not valid */
8749 rslt
= BMI2_E_NULL_PTR
;
8756 * @brief This internal API is to get the status of st_status from gry_crt_conf register
8758 static int8_t get_st_running(uint8_t *st_status
, struct bmi2_dev
*dev
)
8761 uint8_t reg_data
= 0;
8763 rslt
= null_ptr_check(dev
);
8764 if (rslt
== BMI2_OK
)
8766 /* Get the status of crt running */
8767 rslt
= bmi2_get_regs(BMI2_GYR_CRT_CONF_ADDR
, ®_data
, 1, dev
);
8768 if (rslt
== BMI2_OK
)
8770 (*st_status
) = BMI2_GET_BITS(reg_data
, BMI2_GYR_CRT_RUNNING
);
8775 rslt
= BMI2_E_NULL_PTR
;
8782 * @brief This API enables/disables the CRT running.
8784 static int8_t set_st_running(uint8_t st_status
, struct bmi2_dev
*dev
)
8787 uint8_t reg_data
= 0;
8789 rslt
= null_ptr_check(dev
);
8790 if (rslt
== BMI2_OK
)
8792 rslt
= bmi2_get_regs(BMI2_GYR_CRT_CONF_ADDR
, ®_data
, 1, dev
);
8793 if (rslt
== BMI2_OK
)
8795 reg_data
= BMI2_SET_BITS(reg_data
, BMI2_GYR_CRT_RUNNING
, st_status
);
8796 rslt
= bmi2_set_regs(BMI2_GYR_CRT_CONF_ADDR
, ®_data
, 1, dev
);
8804 * @brief This API gets the status of rdy for dl bit.
8806 static int8_t get_rdy_for_dl(uint8_t *rdy_for_dl
, struct bmi2_dev
*dev
)
8809 uint8_t reg_data
= 0;
8811 rslt
= null_ptr_check(dev
);
8812 if (rslt
== BMI2_OK
)
8814 /* Get the status of rdy_fo_dl */
8815 rslt
= bmi2_get_regs(BMI2_GYR_CRT_CONF_ADDR
, ®_data
, 1, dev
);
8816 if (rslt
== BMI2_OK
)
8818 (*rdy_for_dl
) = BMI2_GET_BITS(reg_data
, BMI2_GYR_RDY_FOR_DL
);
8823 rslt
= BMI2_E_NULL_PTR
;
8830 * @brief This API does the crt process if max burst length is not zero.
8832 static int8_t process_crt_download(uint8_t last_byte_flag
, struct bmi2_dev
*dev
)
8835 uint8_t rdy_for_dl
= 0;
8836 uint8_t cmd
= BMI2_G_TRIGGER_CMD
;
8838 rslt
= null_ptr_check(dev
);
8839 if (rslt
== BMI2_OK
)
8841 rslt
= get_rdy_for_dl(&rdy_for_dl
, dev
);
8844 /* Trigger next CRT command */
8845 if (rslt
== BMI2_OK
)
8847 rslt
= bmi2_set_regs(BMI2_CMD_REG_ADDR
, &cmd
, 1, dev
);
8850 if ((!last_byte_flag
) && (rslt
== BMI2_OK
))
8852 rslt
= wait_rdy_for_dl_toggle(BMI2_CRT_READY_FOR_DOWNLOAD_RETRY
, rdy_for_dl
, dev
);
8859 * @brief This API to write the 2kb size of crt configuration
8861 static int8_t write_crt_config_file(uint16_t write_len
,
8862 uint16_t config_file_size
,
8863 uint16_t start_index
,
8864 struct bmi2_dev
*dev
)
8866 int8_t rslt
= BMI2_OK
;
8868 uint8_t last_byte_flag
= 0;
8869 uint8_t remain
= (uint8_t)(config_file_size
% write_len
);
8870 uint16_t balance_byte
= 0;
8875 /* Write the configuration file */
8876 for (index
= start_index
;
8877 (index
< (start_index
+ config_file_size
)) && (rslt
== BMI2_OK
);
8880 rslt
= upload_file((dev
->config_file_ptr
+ index
), index
, write_len
, dev
);
8881 if (index
>= ((start_index
+ config_file_size
) - (write_len
)))
8886 if (rslt
== BMI2_OK
)
8888 rslt
= process_crt_download(last_byte_flag
, dev
);
8894 /* Get the balance bytes */
8895 balance_byte
= (uint16_t)start_index
+ (uint16_t)config_file_size
- (uint16_t)remain
;
8897 /* Write the configuration file for the balance bytes */
8898 for (index
= start_index
; (index
< balance_byte
) && (rslt
== BMI2_OK
); index
+= write_len
)
8900 rslt
= upload_file((dev
->config_file_ptr
+ index
), index
, write_len
, dev
);
8901 if (rslt
== BMI2_OK
)
8903 rslt
= process_crt_download(last_byte_flag
, dev
);
8907 if (rslt
== BMI2_OK
)
8909 /* Write the remaining bytes in 2 bytes length */
8911 rslt
= set_maxburst_len(write_len
, dev
);
8913 /* Write the configuration file for the remaining bytes */
8914 for (index
= balance_byte
;
8915 (index
< (start_index
+ config_file_size
)) && (rslt
== BMI2_OK
);
8918 rslt
= upload_file((dev
->config_file_ptr
+ index
), index
, write_len
, dev
);
8919 if (index
< ((start_index
+ config_file_size
) - write_len
))
8924 if (rslt
== BMI2_OK
)
8926 rslt
= process_crt_download(last_byte_flag
, dev
);
8936 * @brief This API is to wait till the rdy for dl bit toggles after every pack of bytes.
8938 static int8_t wait_rdy_for_dl_toggle(uint8_t retry_complete
, uint8_t download_ready
, struct bmi2_dev
*dev
)
8940 int8_t rslt
= BMI2_OK
;
8941 uint8_t dl_ready
= 0;
8942 uint8_t st_status
= 0;
8944 while ((rslt
== BMI2_OK
) && (retry_complete
--))
8946 rslt
= get_rdy_for_dl(&dl_ready
, dev
);
8947 if (download_ready
!= dl_ready
)
8952 dev
->delay_us(BMI2_CRT_READY_FOR_DOWNLOAD_US
, dev
->intf_ptr
);
8955 if ((rslt
== BMI2_OK
) && (download_ready
== dl_ready
))
8957 rslt
= BMI2_E_CRT_READY_FOR_DL_FAIL_ABORT
;
8960 if (rslt
== BMI2_OK
)
8962 rslt
= get_st_running(&st_status
, dev
);
8963 if ((rslt
== BMI2_OK
) && (st_status
== 0))
8965 rslt
= BMI2_E_ST_ALREADY_RUNNING
;
8973 * @brief This API is to wait till crt status complete.
8975 static int8_t wait_st_running(uint8_t retry_complete
, struct bmi2_dev
*dev
)
8977 uint8_t st_status
= 1;
8978 int8_t rslt
= BMI2_OK
;
8980 while (retry_complete
--)
8982 rslt
= get_st_running(&st_status
, dev
);
8983 if ((rslt
== BMI2_OK
) && (st_status
== 0))
8988 dev
->delay_us(BMI2_CRT_WAIT_RUNNING_US
, dev
->intf_ptr
);
8991 if ((rslt
== BMI2_OK
) && (st_status
== 1))
8993 rslt
= BMI2_E_ST_ALREADY_RUNNING
;
9000 * @brief This api is used to perform gyroscope self-test.
9002 int8_t bmi2_do_gyro_st(struct bmi2_dev
*dev
)
9006 rslt
= do_gtrigger_test(BMI2_SELECT_GYRO_SELF_TEST
, dev
);
9012 * @brief This API is to run the CRT process for both max burst length 0 and non zero condition.
9014 int8_t bmi2_do_crt(struct bmi2_dev
*dev
)
9018 rslt
= do_gtrigger_test(BMI2_SELECT_CRT
, dev
);
9024 * @brief This API is to run the crt process for both max burst length 0 and non zero condition.
9026 static int8_t do_gtrigger_test(uint8_t gyro_st_crt
, struct bmi2_dev
*dev
)
9029 int8_t rslt_crt
= BMI2_OK
;
9030 uint8_t st_status
= 0;
9031 uint8_t max_burst_length
= 0;
9032 uint8_t download_ready
= 0;
9033 uint8_t cmd
= BMI2_G_TRIGGER_CMD
;
9034 struct bmi2_gyro_self_test_status gyro_st_result
= { 0 };
9036 /* Variable to get the status of advance power save */
9037 uint8_t aps_stat
= 0;
9039 rslt
= null_ptr_check(dev
);
9040 if (rslt
== BMI2_OK
)
9042 /* Check if the variant supports this feature */
9043 if (dev
->variant_feature
& BMI2_CRT_RTOSK_ENABLE
)
9045 /* Get status of advance power save mode */
9046 aps_stat
= dev
->aps_status
;
9047 if (aps_stat
== BMI2_ENABLE
)
9049 /* Disable advance power save if enabled */
9050 rslt
= bmi2_set_adv_power_save(BMI2_DISABLE
, dev
);
9053 /* Get max burst length */
9054 if (rslt
== BMI2_OK
)
9056 rslt
= get_maxburst_len(&max_burst_length
, dev
);
9059 /* Checking for CRT running status */
9060 if (rslt
== BMI2_OK
)
9062 rslt
= get_st_running(&st_status
, dev
);
9065 /* CRT is not running and Max burst length is zero */
9068 if (rslt
== BMI2_OK
)
9070 rslt
= set_st_running(BMI2_ENABLE
, dev
);
9073 /* Preparing the setup */
9074 if (rslt
== BMI2_OK
)
9076 rslt
= crt_prepare_setup(dev
);
9079 /* Enable the gyro self-test, CRT */
9080 if (rslt
== BMI2_OK
)
9082 rslt
= select_self_test(gyro_st_crt
, dev
);
9085 /* Check if FIFO is unchanged by checking the max burst length */
9086 if ((rslt
== BMI2_OK
) && (max_burst_length
== 0))
9089 rslt
= bmi2_set_regs(BMI2_CMD_REG_ADDR
, &cmd
, 1, dev
);
9090 if (rslt
== BMI2_OK
)
9092 /* Wait until st_status = 0 or time out is 2 seconds */
9093 rslt
= wait_st_running(BMI2_CRT_WAIT_RUNNING_RETRY_EXECUTION
, dev
);
9095 /* CRT Running wait & check is successful */
9096 if (rslt
== BMI2_OK
)
9098 rslt
= crt_gyro_st_update_result(dev
);
9104 /* FIFO may be used */
9105 if (rslt
== BMI2_OK
)
9107 if (dev
->read_write_len
< 2)
9109 dev
->read_write_len
= 2;
9112 if (dev
->read_write_len
> (BMI2_CRT_MAX_BURST_WORD_LENGTH
* 2))
9114 dev
->read_write_len
= BMI2_CRT_MAX_BURST_WORD_LENGTH
* 2;
9117 /* Reset the max burst length to default value */
9118 rslt
= set_maxburst_len(dev
->read_write_len
, dev
);
9121 if (rslt
== BMI2_OK
)
9123 rslt
= get_rdy_for_dl(&download_ready
, dev
);
9127 if (rslt
== BMI2_OK
)
9129 rslt
= bmi2_set_regs(BMI2_CMD_REG_ADDR
, &cmd
, 1, dev
);
9132 /* Wait till either ready for download toggle or crt running = 0 */
9133 if (rslt
== BMI2_OK
)
9135 rslt
= wait_rdy_for_dl_toggle(BMI2_CRT_READY_FOR_DOWNLOAD_RETRY
, download_ready
, dev
);
9136 if (rslt
== BMI2_OK
)
9138 rslt
= write_crt_config_file(dev
->read_write_len
, BMI2_CRT_CONFIG_FILE_SIZE
, 0x1800, dev
);
9141 if (rslt
== BMI2_OK
)
9143 rslt
= wait_st_running(BMI2_CRT_WAIT_RUNNING_RETRY_EXECUTION
, dev
);
9144 rslt_crt
= crt_gyro_st_update_result(dev
);
9145 if (rslt
== BMI2_OK
)
9155 rslt
= BMI2_E_ST_ALREADY_RUNNING
;
9158 if (rslt
== BMI2_OK
)
9160 if (gyro_st_crt
== BMI2_SELECT_GYRO_SELF_TEST
)
9162 rslt
= gyro_self_test_completed(&gyro_st_result
, dev
);
9166 /* Enable Advance power save if disabled while configuring and
9167 * not when already disabled
9169 if ((aps_stat
== BMI2_ENABLE
) && (rslt
== BMI2_OK
))
9171 rslt
= bmi2_set_adv_power_save(BMI2_ENABLE
, dev
);
9180 * @brief This API to set up environment for processing the crt.
9182 static int8_t crt_prepare_setup(struct bmi2_dev
*dev
)
9186 /* Variable to select the sensor */
9187 uint8_t sens_list
= BMI2_GYRO
;
9189 rslt
= null_ptr_check(dev
);
9191 if (rslt
== BMI2_OK
)
9193 /* Disable gyroscope */
9194 rslt
= bmi2_sensor_disable(&sens_list
, 1, dev
);
9197 /* Disable FIFO for all sensors */
9198 if (rslt
== BMI2_OK
)
9200 rslt
= bmi2_set_fifo_config(BMI2_FIFO_ALL_EN
, BMI2_DISABLE
, dev
);
9203 if (rslt
== BMI2_OK
)
9205 /* Enable accelerometer */
9206 sens_list
= BMI2_ACCEL
;
9207 rslt
= bmi2_sensor_enable(&sens_list
, 1, dev
);
9210 if (rslt
== BMI2_OK
)
9212 /* Disable Abort after 1 msec */
9213 dev
->delay_us(1000, dev
->intf_ptr
);
9214 rslt
= abort_bmi2(BMI2_DISABLE
, dev
);
9221 * @brief This API is to update the CRT or gyro self-test final result.
9223 static int8_t crt_gyro_st_update_result(struct bmi2_dev
*dev
)
9226 struct bmi2_gyr_user_gain_status user_gain_stat
= { 0, 0, 0, 0 };
9228 rslt
= null_ptr_check(dev
);
9230 /* CRT status has to be read from the config register map */
9231 if (rslt
== BMI2_OK
)
9233 rslt
= get_gyro_gain_update_status(&user_gain_stat
, dev
);
9236 if (rslt
== BMI2_OK
)
9238 switch (user_gain_stat
.g_trigger_status
)
9240 case BMI2_G_TRIGGER_NO_ERROR
:
9242 /* CRT is successful - Reset the Max Burst Length */
9243 rslt
= set_maxburst_len(0, dev
);
9246 case BMI2_G_TRIGGER_DL_ERROR
:
9248 /* CRT is Download Error - Keep non zero value for Max Burst Length */
9249 rslt
= set_maxburst_len(dev
->read_write_len
, dev
);
9250 if (rslt
== BMI2_OK
)
9252 rslt
= BMI2_E_DL_ERROR
;
9256 case BMI2_G_TRIGGER_ABORT_ERROR
:
9258 /* Command is aborted either by host via the block bit or due to motion
9259 * detection. Keep non zero value for Max Burst Length
9261 rslt
= set_maxburst_len(dev
->read_write_len
, dev
);
9262 if (rslt
== BMI2_OK
)
9264 rslt
= BMI2_E_ABORT_ERROR
;
9269 case BMI2_G_TRIGGER_PRECON_ERROR
:
9271 /* Pre-condition to start the feature was not completed. */
9272 rslt
= BMI2_E_PRECON_ERROR
;
9276 rslt
= BMI2_E_INVALID_STATUS
;
9286 * @brief This internal API gets the max burst length.
9288 static int8_t get_maxburst_len(uint8_t *max_burst_len
, struct bmi2_dev
*dev
)
9290 int8_t rslt
= BMI2_OK
;
9291 uint8_t feat_config
[BMI2_FEAT_SIZE_IN_BYTES
] = { 0 };
9293 uint8_t feat_found
= 0;
9294 struct bmi2_feature_config maxburst_length_bytes
= { 0, 0, 0 };
9297 if ((dev
->variant_feature
& BMI2_CRT_IN_FIFO_NOT_REQ
) != 0)
9304 /* Get status of advance power save mode */
9305 aps_stat
= dev
->aps_status
;
9306 if (aps_stat
== BMI2_ENABLE
)
9308 /* Disable advance power save if enabled */
9309 rslt
= bmi2_set_adv_power_save(BMI2_DISABLE
, dev
);
9312 if (rslt
== BMI2_OK
)
9314 /* Search for max burst length */
9315 feat_found
= bmi2_extract_input_feat_config(&maxburst_length_bytes
, BMI2_MAX_BURST_LEN
, dev
);
9318 rslt
= bmi2_get_feat_config(maxburst_length_bytes
.page
, feat_config
, dev
);
9319 if (rslt
== BMI2_OK
)
9321 /* Define the offset for max burst length */
9322 idx
= maxburst_length_bytes
.start_addr
;
9324 /* Get the max burst length */
9325 *max_burst_len
= feat_config
[idx
];
9330 rslt
= BMI2_E_INVALID_SENSOR
;
9333 /* Enable Advance power save if disabled while configuring and
9334 * not when already disabled
9336 if ((aps_stat
== BMI2_ENABLE
) && (rslt
== BMI2_OK
))
9338 rslt
= bmi2_set_adv_power_save(BMI2_ENABLE
, dev
);
9346 * @brief This internal API sets the max burst length.
9348 static int8_t set_maxburst_len(const uint16_t write_len_byte
, struct bmi2_dev
*dev
)
9350 int8_t rslt
= BMI2_OK
;
9351 uint8_t feat_config
[BMI2_FEAT_SIZE_IN_BYTES
] = { 0 };
9353 uint8_t reg_addr
= 0;
9354 uint8_t max_burst_len
= 0;
9355 uint8_t feat_found
= 0;
9356 struct bmi2_feature_config maxburst_length_bytes
= { 0, 0, 0 };
9358 uint16_t burst_len
= write_len_byte
/ 2;
9360 /* for variant that support crt outside fifo, do not modify the max burst len */
9361 if ((dev
->variant_feature
& BMI2_CRT_IN_FIFO_NOT_REQ
) != 0)
9366 /* Max burst length is only 1 byte */
9367 if (burst_len
> BMI2_CRT_MAX_BURST_WORD_LENGTH
)
9369 max_burst_len
= UINT8_C(0xFF);
9373 max_burst_len
= (uint8_t)burst_len
;
9376 /* Get status of advance power save mode */
9377 aps_stat
= dev
->aps_status
;
9378 if (aps_stat
== BMI2_ENABLE
)
9380 /* Disable advance power save if enabled */
9381 rslt
= bmi2_set_adv_power_save(BMI2_DISABLE
, dev
);
9384 if (rslt
== BMI2_OK
)
9386 /* Search for axis-re-mapping and extract its configuration details */
9387 feat_found
= bmi2_extract_input_feat_config(&maxburst_length_bytes
, BMI2_MAX_BURST_LEN
, dev
);
9390 /* Get the configuration from the page where axis
9391 * re-mapping feature resides
9393 rslt
= bmi2_get_feat_config(maxburst_length_bytes
.page
, feat_config
, dev
);
9394 if (rslt
== BMI2_OK
)
9396 /* Define the offset in bytes */
9397 idx
= maxburst_length_bytes
.start_addr
;
9399 /* update Max burst length */
9400 feat_config
[idx
] = max_burst_len
;
9402 /* Update the register address */
9403 reg_addr
= BMI2_FEATURES_REG_ADDR
+ maxburst_length_bytes
.start_addr
;
9405 /* Set the configuration back to the page */
9406 rslt
= bmi2_set_regs(reg_addr
, &feat_config
[maxburst_length_bytes
.start_addr
], 2, dev
);
9411 rslt
= BMI2_E_INVALID_SENSOR
;
9414 /* Enable Advance power save if disabled while configuring and
9415 * not when already disabled
9417 if ((aps_stat
== BMI2_ENABLE
) && (rslt
== BMI2_OK
))
9419 rslt
= bmi2_set_adv_power_save(BMI2_ENABLE
, dev
);
9427 * @brief This api is used to trigger the preparation for system for NVM programming.
9429 static int8_t set_nvm_prep_prog(uint8_t nvm_prep
, struct bmi2_dev
*dev
)
9431 /* Variable to define error */
9432 int8_t rslt
= BMI2_OK
;
9434 /* Array to define the feature configuration */
9435 uint8_t feat_config
[BMI2_FEAT_SIZE_IN_BYTES
] = { 0 };
9437 /* Variable to define the array offset */
9440 /* Variable to set flag */
9442 uint8_t reg_addr
= 0;
9444 /* Initialize feature configuration for nvm preparation*/
9445 struct bmi2_feature_config nvm_config
= { 0, 0, 0 };
9447 /* Search for bmi2 gyro self offset correction feature as nvm program preparation feature is
9448 * present in the same Word and extract its configuration details
9450 feat_found
= bmi2_extract_input_feat_config(&nvm_config
, BMI2_NVM_PROG_PREP
, dev
);
9453 /* Get the configuration from the page where nvm preparation feature enable feature
9455 rslt
= bmi2_get_feat_config(nvm_config
.page
, feat_config
, dev
);
9456 if (rslt
== BMI2_OK
)
9458 /* Define the offset for nvm preparation feature enable */
9459 idx
= nvm_config
.start_addr
;
9461 /* update nvm_prog_prep enable bit */
9462 feat_config
[idx
] = BMI2_SET_BITS(feat_config
[idx
], BMI2_NVM_PREP_FEATURE_EN
, nvm_prep
);
9464 /* Update the register address */
9465 reg_addr
= BMI2_FEATURES_REG_ADDR
+ nvm_config
.start_addr
- 1;
9467 /* Set the configuration back to the page */
9468 rslt
= bmi2_set_regs(reg_addr
, &feat_config
[nvm_config
.start_addr
- 1], 2, dev
);
9473 rslt
= BMI2_E_INVALID_SENSOR
;
9480 * @brief This api is used to enable the CRT.
9482 static int8_t select_self_test(uint8_t gyro_st_crt
, struct bmi2_dev
*dev
)
9486 uint8_t feat_config
[BMI2_FEAT_SIZE_IN_BYTES
] = { 0 };
9491 uint8_t reg_addr
= 0;
9493 struct bmi2_feature_config gyro_self_test_crt_config
= { 0, 0, 0 };
9495 /* Search for bmi2 crt gyro self-test feature and extract its configuration details */
9496 feat_found
= bmi2_extract_input_feat_config(&gyro_self_test_crt_config
, BMI2_CRT_GYRO_SELF_TEST
, dev
);
9499 /* Get the configuration from the page where gyro self-test and crt enable feature
9501 rslt
= bmi2_get_feat_config(gyro_self_test_crt_config
.page
, feat_config
, dev
);
9502 if (rslt
== BMI2_OK
)
9504 /* Define the offset in bytes */
9505 idx
= gyro_self_test_crt_config
.start_addr
;
9507 /* update the gyro self-test crt enable bit */
9508 feat_config
[idx
] = BMI2_SET_BIT_POS0(feat_config
[idx
], BMI2_GYRO_SELF_TEST_CRT_EN
, gyro_st_crt
);
9510 /* Update the register address */
9511 reg_addr
= BMI2_FEATURES_REG_ADDR
+ (gyro_self_test_crt_config
.start_addr
- 1);
9513 /* Set the configuration back to the page */
9514 rslt
= bmi2_set_regs(reg_addr
, &feat_config
[gyro_self_test_crt_config
.start_addr
- 1], 2, dev
);
9519 rslt
= BMI2_E_INVALID_SENSOR
;
9526 * @brief This api is used to abort ongoing crt or gyro self-test.
9528 int8_t bmi2_abort_crt_gyro_st(struct bmi2_dev
*dev
)
9530 int8_t rslt
= BMI2_OK
;
9532 uint8_t st_running
= 0;
9533 uint8_t cmd
= BMI2_G_TRIGGER_CMD
;
9535 /* Get status of advance power save mode */
9536 aps_stat
= dev
->aps_status
;
9537 if (aps_stat
== BMI2_ENABLE
)
9539 /* Disable advance power save if enabled */
9540 rslt
= bmi2_set_adv_power_save(BMI2_DISABLE
, dev
);
9543 /* Checking for ST running status */
9544 if (rslt
== BMI2_OK
)
9546 rslt
= get_st_running(&st_running
, dev
);
9547 if (rslt
== BMI2_OK
)
9549 /* ST is not running */
9550 if (st_running
== 0)
9552 rslt
= BMI2_E_ST_NOT_RUNING
;
9557 if (rslt
== BMI2_OK
)
9559 rslt
= abort_bmi2(BMI2_ENABLE
, dev
);
9562 /* send the g trigger command */
9563 if (rslt
== BMI2_OK
)
9565 rslt
= bmi2_set_regs(BMI2_CMD_REG_ADDR
, &cmd
, 1, dev
);
9568 if (rslt
== BMI2_OK
)
9570 /* wait until st_status = 0 or time out is 2 seconds */
9571 rslt
= wait_st_running(BMI2_CRT_WAIT_RUNNING_RETRY_EXECUTION
, dev
);
9574 /* Check G trigger status for error */
9575 if (rslt
== BMI2_OK
)
9577 rslt
= crt_gyro_st_update_result(dev
);
9578 if (rslt
== BMI2_E_ABORT_ERROR
)
9584 rslt
= BMI2_E_ABORT_ERROR
;
9588 /* Enable Advance power save if disabled while configuring and
9589 * not when already disabled
9591 if ((aps_stat
== BMI2_ENABLE
) && (rslt
== BMI2_OK
))
9593 rslt
= bmi2_set_adv_power_save(BMI2_ENABLE
, dev
);
9600 * @brief This api is used to enable/disable abort.
9602 static int8_t abort_bmi2(uint8_t abort_enable
, struct bmi2_dev
*dev
)
9604 /* Variable to define error */
9607 /* Array to define the feature configuration */
9608 uint8_t feat_config
[BMI2_FEAT_SIZE_IN_BYTES
] = { 0 };
9610 /* Variable to define the array offset */
9613 /* Variable to set flag */
9615 uint8_t reg_addr
= 0;
9617 /* Initialize feature configuration for blocking a feature */
9618 struct bmi2_feature_config block_config
= { 0, 0, 0 };
9620 /* Search for bmi2 Abort feature and extract its configuration details */
9621 feat_found
= bmi2_extract_input_feat_config(&block_config
, BMI2_ABORT_CRT_GYRO_SELF_TEST
, dev
);
9624 /* Get the configuration from the page where abort(block) feature resides */
9625 rslt
= bmi2_get_feat_config(block_config
.page
, feat_config
, dev
);
9626 if (rslt
== BMI2_OK
)
9628 /* Define the offset in bytes */
9629 idx
= block_config
.start_addr
;
9631 /* update the gyro self-test crt abort enable bit */
9632 feat_config
[idx
] = BMI2_SET_BITS(feat_config
[idx
], BMI2_ABORT_FEATURE_EN
, abort_enable
);
9634 /* Update the register address */
9635 reg_addr
= BMI2_FEATURES_REG_ADDR
+ (block_config
.start_addr
- 1);
9637 /* Set the configuration back to the page */
9638 rslt
= bmi2_set_regs(reg_addr
, &feat_config
[block_config
.start_addr
- 1], 2, dev
);
9643 rslt
= BMI2_E_INVALID_SENSOR
;
9650 * @brief This api is use to wait till gyro self-test is completed and update the status of gyro
9653 static int8_t gyro_self_test_completed(struct bmi2_gyro_self_test_status
*gyro_st_result
, struct bmi2_dev
*dev
)
9658 rslt
= bmi2_get_regs(BMI2_GYR_SELF_TEST_AXES_ADDR
, ®_data
, 1, dev
);
9659 if (rslt
== BMI2_OK
)
9661 gyro_st_result
->gyr_st_axes_done
= BMI2_GET_BIT_POS0(reg_data
, BMI2_GYR_ST_AXES_DONE
);
9662 if (gyro_st_result
->gyr_st_axes_done
== 0x01)
9664 gyro_st_result
->gyr_axis_x_ok
= BMI2_GET_BITS(reg_data
, BMI2_GYR_AXIS_X_OK
);
9665 gyro_st_result
->gyr_axis_y_ok
= BMI2_GET_BITS(reg_data
, BMI2_GYR_AXIS_Y_OK
);
9666 gyro_st_result
->gyr_axis_z_ok
= BMI2_GET_BITS(reg_data
, BMI2_GYR_AXIS_Z_OK
);
9670 rslt
= BMI2_E_SELF_TEST_NOT_DONE
;
9678 * @brief This api validates accel foc position as per the range
9680 static int8_t validate_foc_position(uint8_t sens_list
,
9681 const struct bmi2_accel_foc_g_value
*accel_g_axis
,
9682 struct bmi2_sens_axes_data avg_foc_data
,
9683 struct bmi2_dev
*dev
)
9685 int8_t rslt
= BMI2_E_INVALID_INPUT
;
9687 if (sens_list
== BMI2_ACCEL
)
9689 if (accel_g_axis
->x
== 1)
9691 rslt
= validate_foc_accel_axis(avg_foc_data
.x
, dev
);
9693 else if (accel_g_axis
->y
== 1)
9695 rslt
= validate_foc_accel_axis(avg_foc_data
.y
, dev
);
9699 rslt
= validate_foc_accel_axis(avg_foc_data
.z
, dev
);
9702 else if (sens_list
== BMI2_GYRO
)
9704 if (((avg_foc_data
.x
>= BMI2_GYRO_FOC_NOISE_LIMIT_NEGATIVE
) &&
9705 (avg_foc_data
.x
<= BMI2_GYRO_FOC_NOISE_LIMIT_POSITIVE
)) &&
9706 ((avg_foc_data
.y
>= BMI2_GYRO_FOC_NOISE_LIMIT_NEGATIVE
) &&
9707 (avg_foc_data
.y
<= BMI2_GYRO_FOC_NOISE_LIMIT_POSITIVE
)) &&
9708 ((avg_foc_data
.z
>= BMI2_GYRO_FOC_NOISE_LIMIT_NEGATIVE
) &&
9709 (avg_foc_data
.z
<= BMI2_GYRO_FOC_NOISE_LIMIT_POSITIVE
)))
9715 rslt
= BMI2_E_INVALID_FOC_POSITION
;
9723 * @brief This api validates depends on accel foc access input
9725 static int8_t validate_foc_accel_axis(int16_t avg_foc_data
, struct bmi2_dev
*dev
)
9727 struct bmi2_sens_config sens_cfg
= { 0 };
9731 sens_cfg
.type
= BMI2_ACCEL
;
9732 rslt
= bmi2_get_sensor_config(&sens_cfg
, 1, dev
);
9733 range
= sens_cfg
.cfg
.acc
.range
;
9735 /* reference LSB value of 16G */
9736 if ((range
== BMI2_ACC_RANGE_2G
) && (avg_foc_data
> BMI2_ACC_2G_MIN_NOISE_LIMIT
) &&
9737 (avg_foc_data
< BMI2_ACC_2G_MAX_NOISE_LIMIT
))
9741 /* reference LSB value of 16G */
9742 else if ((range
== BMI2_ACC_RANGE_4G
) && (avg_foc_data
> BMI2_ACC_4G_MIN_NOISE_LIMIT
) &&
9743 (avg_foc_data
< BMI2_ACC_4G_MAX_NOISE_LIMIT
))
9747 /* reference LSB value of 16G */
9748 else if ((range
== BMI2_ACC_RANGE_8G
) && (avg_foc_data
> BMI2_ACC_8G_MIN_NOISE_LIMIT
) &&
9749 (avg_foc_data
< BMI2_ACC_8G_MAX_NOISE_LIMIT
))
9753 /* reference LSB value of 16G */
9754 else if ((range
== BMI2_ACC_RANGE_16G
) && (avg_foc_data
> BMI2_ACC_16G_MIN_NOISE_LIMIT
) &&
9755 (avg_foc_data
< BMI2_ACC_16G_MAX_NOISE_LIMIT
))
9761 rslt
= BMI2_E_INVALID_FOC_POSITION
;
9767 /*! @brief This api is used for programming the non volatile memory(nvm) */
9768 int8_t bmi2_nvm_prog(struct bmi2_dev
*dev
)
9770 int8_t rslt
= BMI2_OK
;
9772 /* Variable to get the status of advance power save */
9777 uint8_t write_timeout
= 100;
9779 /* Get status of advance power save mode */
9780 aps_stat
= dev
->aps_status
;
9781 if (aps_stat
== BMI2_ENABLE
)
9783 /* Disable advance power save if enabled */
9784 rslt
= bmi2_set_adv_power_save(BMI2_DISABLE
, dev
);
9787 /* Check the Write status and proceed only if there is no ongoing write cycle */
9788 if (rslt
== BMI2_OK
)
9790 rslt
= bmi2_get_status(&status
, dev
);
9792 cmd_rdy
= BMI2_GET_BITS(status
, BMI2_CMD_RDY
);
9795 rslt
= set_nvm_prep_prog(BMI2_ENABLE
, dev
);
9796 if (rslt
== BMI2_OK
)
9798 dev
->delay_us(40000, dev
->intf_ptr
);
9800 /* Set the NVM_CONF.nvm_prog_en bit in order to enable the NVM
9802 reg_data
= BMI2_NVM_UNLOCK_ENABLE
;
9803 rslt
= bmi2_set_regs(BMI2_NVM_CONF_ADDR
, ®_data
, 1, dev
);
9804 if (rslt
== BMI2_OK
)
9806 /* Send NVM prog command to command register */
9807 reg_data
= BMI2_NVM_PROG_CMD
;
9808 rslt
= bmi2_set_regs(BMI2_CMD_REG_ADDR
, ®_data
, 1, dev
);
9811 /* Wait till write operation is completed */
9812 if (rslt
== BMI2_OK
)
9814 while (write_timeout
--)
9816 rslt
= bmi2_get_status(&status
, dev
);
9817 if (rslt
== BMI2_OK
)
9819 cmd_rdy
= BMI2_GET_BITS(status
, BMI2_CMD_RDY
);
9821 /* Nvm is complete once cmd_rdy is 1, break if 1 */
9827 /* Wait till cmd_rdy becomes 1 indicating
9828 * nvm process completes */
9829 dev
->delay_us(20000, dev
->intf_ptr
);
9834 if ((rslt
== BMI2_OK
) && (cmd_rdy
!= BMI2_TRUE
))
9836 rslt
= BMI2_E_WRITE_CYCLE_ONGOING
;
9842 rslt
= BMI2_E_WRITE_CYCLE_ONGOING
;
9846 if (rslt
== BMI2_OK
)
9848 /* perform soft reset */
9849 rslt
= bmi2_soft_reset(dev
);
9852 /* Enable Advance power save if disabled while configuring and not when already disabled */
9853 if ((aps_stat
== BMI2_ENABLE
) && (rslt
== BMI2_OK
))
9855 rslt
= bmi2_set_adv_power_save(BMI2_ENABLE
, dev
);
9862 * @brief This API reads and provides average for 128 samples of sensor data for foc operation
9865 static int8_t get_average_of_sensor_data(uint8_t sens_list
,
9866 struct bmi2_foc_temp_value
*temp_foc_data
,
9867 struct bmi2_dev
*dev
)
9870 struct bmi2_sensor_data sensor_data
= { 0 };
9871 uint8_t sample_count
= 0;
9872 uint8_t datardy_try_cnt
;
9873 uint8_t drdy_status
= 0;
9874 uint8_t sensor_drdy
= 0;
9876 sensor_data
.type
= sens_list
;
9877 if (sens_list
== BMI2_ACCEL
)
9879 sensor_drdy
= BMI2_DRDY_ACC
;
9883 sensor_drdy
= BMI2_DRDY_GYR
;
9886 /* Read sensor values before FOC */
9887 while (sample_count
< BMI2_FOC_SAMPLE_LIMIT
)
9889 datardy_try_cnt
= 5;
9892 dev
->delay_us(20000, dev
->intf_ptr
);
9893 rslt
= bmi2_get_status(&drdy_status
, dev
);
9895 } while ((rslt
== BMI2_OK
) && (!(drdy_status
& sensor_drdy
)) && (datardy_try_cnt
));
9897 if ((rslt
!= BMI2_OK
) || (datardy_try_cnt
== 0))
9899 rslt
= BMI2_E_DATA_RDY_INT_FAILED
;
9903 rslt
= bmi2_get_sensor_data(&sensor_data
, 1, dev
);
9905 if (rslt
== BMI2_OK
)
9907 if (sensor_data
.type
== BMI2_ACCEL
)
9909 temp_foc_data
->x
+= sensor_data
.sens_data
.acc
.x
;
9910 temp_foc_data
->y
+= sensor_data
.sens_data
.acc
.y
;
9911 temp_foc_data
->z
+= sensor_data
.sens_data
.acc
.z
;
9913 else if (sensor_data
.type
== BMI2_GYRO
)
9915 temp_foc_data
->x
+= sensor_data
.sens_data
.gyr
.x
;
9916 temp_foc_data
->y
+= sensor_data
.sens_data
.gyr
.y
;
9917 temp_foc_data
->z
+= sensor_data
.sens_data
.gyr
.z
;
9928 if (rslt
== BMI2_OK
)
9930 temp_foc_data
->x
= (temp_foc_data
->x
/ BMI2_FOC_SAMPLE_LIMIT
);
9931 temp_foc_data
->y
= (temp_foc_data
->y
/ BMI2_FOC_SAMPLE_LIMIT
);
9932 temp_foc_data
->z
= (temp_foc_data
->z
/ BMI2_FOC_SAMPLE_LIMIT
);
9939 * @brief This internal API extract the identification feature from the DMR page
9940 * and retrieve the config file major and minor version.
9942 static int8_t extract_config_file(uint8_t *config_major
, uint8_t *config_minor
, struct bmi2_dev
*dev
)
9944 /* Variable to define the result */
9945 int8_t rslt
= BMI2_OK
;
9947 /* Variable to define the array offset */
9950 /* Variable to define LSB */
9953 /* Variable to define MSB */
9956 /* Variable to define a word */
9957 uint16_t lsb_msb
= 0;
9959 /* Variable to set flag */
9962 /* Variable to define advance power save mode status */
9965 /* Array to define the feature configuration */
9966 uint8_t feat_config
[BMI2_FEAT_SIZE_IN_BYTES
] = { 0 };
9968 /* Initialize feature configuration for config file identification */
9969 struct bmi2_feature_config config_id
= { 0, 0, 0 };
9971 /* Check the power mode status */
9972 aps_stat
= dev
->aps_status
;
9973 if (aps_stat
== BMI2_ENABLE
)
9975 /* Disable advance power save if enabled */
9976 rslt
= bmi2_set_adv_power_save(BMI2_DISABLE
, dev
);
9979 if (rslt
== BMI2_OK
)
9981 /* Search for config file identification feature and extract its configuration
9983 feat_found
= bmi2_extract_input_feat_config(&config_id
, BMI2_CONFIG_ID
, dev
);
9986 /* Get the configuration from the page where config file identification
9987 * feature resides */
9988 rslt
= bmi2_get_feat_config(config_id
.page
, feat_config
, dev
);
9989 if (rslt
== BMI2_OK
)
9991 /* Define the offset for config file identification */
9992 idx
= config_id
.start_addr
;
9994 /* Get word to calculate config file identification */
9995 lsb
= (uint16_t) feat_config
[idx
++];
9996 msb
= ((uint16_t) feat_config
[idx
++] << 8);
9997 lsb_msb
= lsb
| msb
;
9999 /* Get major and minor version */
10000 *config_major
= BMI2_GET_BITS(lsb_msb
, BMI2_CONFIG_MAJOR
);
10001 *config_minor
= BMI2_GET_BIT_POS0(lsb
, BMI2_CONFIG_MINOR
);
10005 /* Enable Advance power save if disabled while configuring and
10006 * not when already disabled
10008 if ((aps_stat
== BMI2_ENABLE
) && (rslt
== BMI2_OK
))
10010 rslt
= bmi2_set_adv_power_save(BMI2_ENABLE
, dev
);
10015 rslt
= BMI2_E_INVALID_SENSOR
;
10022 *@brief This internal API is used to map the interrupts to the sensor.
10024 static void extract_feat_int_map(struct bmi2_map_int
*map_int
, uint8_t type
, const struct bmi2_dev
*dev
)
10026 /* Variable to define loop */
10029 /* Search for the interrupts from the input configuration array */
10030 while (loop
< dev
->sens_int_map
)
10032 if (dev
->map_int
[loop
].type
== type
)
10034 *map_int
= dev
->map_int
[loop
];
10043 * @brief This internal API gets the saturation status for the gyroscope user
10046 static int8_t get_gyro_gain_update_status(struct bmi2_gyr_user_gain_status
*user_gain_stat
, struct bmi2_dev
*dev
)
10048 /* Variable to define error */
10051 /* Array to define the feature configuration */
10052 uint8_t feat_config
[BMI2_FEAT_SIZE_IN_BYTES
] = { 0 };
10054 /* Variables to define index */
10057 /* Variable to set flag */
10058 uint8_t feat_found
;
10060 /* Initialize feature output for gyroscope user gain status */
10061 struct bmi2_feature_config user_gain_cfg
= { 0, 0, 0 };
10063 /* Search for gyroscope user gain status output feature and extract its
10064 * configuration details
10066 feat_found
= extract_output_feat_config(&user_gain_cfg
, BMI2_GYRO_GAIN_UPDATE
, dev
);
10069 /* Get the feature output configuration for gyroscope user gain status */
10070 rslt
= bmi2_get_feat_config(user_gain_cfg
.page
, feat_config
, dev
);
10071 if (rslt
== BMI2_OK
)
10073 /* Define the offset in bytes for gyroscope user gain status */
10074 idx
= user_gain_cfg
.start_addr
;
10076 /* Get the saturation status for x-axis */
10077 user_gain_stat
->sat_x
= BMI2_GET_BIT_POS0(feat_config
[idx
], BMI2_GYR_USER_GAIN_SAT_STAT_X
);
10079 /* Get the saturation status for y-axis */
10080 user_gain_stat
->sat_y
= BMI2_GET_BITS(feat_config
[idx
], BMI2_GYR_USER_GAIN_SAT_STAT_Y
);
10082 /* Get the saturation status for z-axis */
10083 user_gain_stat
->sat_z
= BMI2_GET_BITS(feat_config
[idx
], BMI2_GYR_USER_GAIN_SAT_STAT_Z
);
10085 /* Get g trigger status */
10086 user_gain_stat
->g_trigger_status
= BMI2_GET_BITS(feat_config
[idx
], BMI2_G_TRIGGER_STAT
);
10091 rslt
= BMI2_E_INVALID_SENSOR
;
10098 * @brief This internal API is used to extract the output feature configuration
10099 * details from the look-up table.
10101 static uint8_t extract_output_feat_config(struct bmi2_feature_config
*feat_output
,
10103 const struct bmi2_dev
*dev
)
10105 /* Variable to define loop */
10108 /* Variable to set flag */
10109 uint8_t feat_found
= BMI2_FALSE
;
10111 /* Search for the output feature from the output configuration array */
10112 while (loop
< dev
->out_sens
)
10114 if (dev
->feat_output
[loop
].type
== type
)
10116 *feat_output
= dev
->feat_output
[loop
];
10117 feat_found
= BMI2_TRUE
;
10129 * @brief This internal API gets the cross sensitivity coefficient between
10130 * gyroscope's X and Z axes.
10132 static int8_t get_gyro_cross_sense(int16_t *cross_sense
, struct bmi2_dev
*dev
)
10134 /* Variable to define error */
10137 /* Array to define the feature configuration */
10138 uint8_t feat_config
[BMI2_FEAT_SIZE_IN_BYTES
] = { 0 };
10140 /* Variable to define index */
10143 /* Variable to set flag */
10144 uint8_t feat_found
;
10146 uint8_t corr_fact_zx
;
10148 /* Initialize feature output for gyroscope cross sensitivity */
10149 struct bmi2_feature_config cross_sense_out_config
= { 0, 0, 0 };
10151 if (dev
->variant_feature
& BMI2_MAXIMUM_FIFO_VARIANT
)
10153 /* For maximum_fifo variant fetch the correction factor from GPIO0 */
10154 rslt
= bmi2_get_regs(BMI2_GYR_CAS_GPIO0_ADDR
, &corr_fact_zx
, 1, dev
);
10155 if (rslt
== BMI2_OK
)
10157 /* Get the gyroscope cross sensitivity coefficient */
10158 if (corr_fact_zx
& BMI2_GYRO_CROSS_AXES_SENSE_SIGN_BIT_MASK
)
10160 *cross_sense
= (int16_t)(((int16_t)corr_fact_zx
) - 128);
10164 *cross_sense
= (int16_t)(corr_fact_zx
);
10170 /* Search for gyroscope cross sensitivity feature and extract its configuration details */
10171 feat_found
= extract_output_feat_config(&cross_sense_out_config
, BMI2_GYRO_CROSS_SENSE
, dev
);
10174 /* Get the feature output configuration for gyroscope cross sensitivity
10176 rslt
= bmi2_get_feat_config(cross_sense_out_config
.page
, feat_config
, dev
);
10177 if (rslt
== BMI2_OK
)
10179 /* Define the offset in bytes for gyroscope cross sensitivity output */
10180 idx
= cross_sense_out_config
.start_addr
;
10182 /* discard the MSB as GYR_CAS is of only 7 bit */
10183 feat_config
[idx
] = feat_config
[idx
] & BMI2_GYRO_CROSS_AXES_SENSE_MASK
;
10185 /* Get the gyroscope cross sensitivity coefficient */
10186 if (feat_config
[idx
] & BMI2_GYRO_CROSS_AXES_SENSE_SIGN_BIT_MASK
)
10188 *cross_sense
= (int16_t)(((int16_t)feat_config
[idx
]) - 128);
10192 *cross_sense
= (int16_t)(feat_config
[idx
]);
10198 rslt
= BMI2_E_INVALID_SENSOR
;
10206 * @brief This internal API selects the sensor/features to be enabled or
10209 static int8_t select_sensor(const uint8_t *sens_list
, uint8_t n_sens
, uint64_t *sensor_sel
)
10211 /* Variable to define error */
10212 int8_t rslt
= BMI2_OK
;
10214 /* Variable to define loop */
10217 for (count
= 0; count
< n_sens
; count
++)
10219 switch (sens_list
[count
])
10222 *sensor_sel
|= BMI2_ACCEL_SENS_SEL
;
10225 *sensor_sel
|= BMI2_GYRO_SENS_SEL
;
10228 *sensor_sel
|= BMI2_AUX_SENS_SEL
;
10231 *sensor_sel
|= BMI2_TEMP_SENS_SEL
;
10234 rslt
= BMI2_E_INVALID_SENSOR
;
10243 * @brief This internal API enables the selected sensor/features.
10245 static int8_t sensor_enable(uint64_t sensor_sel
, struct bmi2_dev
*dev
)
10247 /* Variable to define error */
10250 /* Variable to store register values */
10251 uint8_t reg_data
= 0;
10253 rslt
= bmi2_get_regs(BMI2_PWR_CTRL_ADDR
, ®_data
, 1, dev
);
10254 if (rslt
== BMI2_OK
)
10256 /* Enable accelerometer */
10257 if (sensor_sel
& BMI2_ACCEL_SENS_SEL
)
10259 reg_data
= BMI2_SET_BITS(reg_data
, BMI2_ACC_EN
, BMI2_ENABLE
);
10262 /* Enable gyroscope */
10263 if (sensor_sel
& BMI2_GYRO_SENS_SEL
)
10265 reg_data
= BMI2_SET_BITS(reg_data
, BMI2_GYR_EN
, BMI2_ENABLE
);
10268 /* Enable auxiliary sensor */
10269 if (sensor_sel
& BMI2_AUX_SENS_SEL
)
10271 reg_data
= BMI2_SET_BIT_POS0(reg_data
, BMI2_AUX_EN
, BMI2_ENABLE
);
10274 /* Enable temperature sensor */
10275 if (sensor_sel
& BMI2_TEMP_SENS_SEL
)
10277 reg_data
= BMI2_SET_BITS(reg_data
, BMI2_TEMP_EN
, BMI2_ENABLE
);
10280 /* Enable the sensors that are set in the power control register */
10281 if (sensor_sel
& BMI2_MAIN_SENSORS
)
10283 rslt
= bmi2_set_regs(BMI2_PWR_CTRL_ADDR
, ®_data
, 1, dev
);
10291 * @brief This internal API disables the selected sensors/features.
10293 static int8_t sensor_disable(uint64_t sensor_sel
, struct bmi2_dev
*dev
)
10295 /* Variable to define error */
10298 /* Variable to store register values */
10299 uint8_t reg_data
= 0;
10301 rslt
= bmi2_get_regs(BMI2_PWR_CTRL_ADDR
, ®_data
, 1, dev
);
10302 if (rslt
== BMI2_OK
)
10304 /* Disable accelerometer */
10305 if (sensor_sel
& BMI2_ACCEL_SENS_SEL
)
10307 reg_data
= BMI2_SET_BIT_VAL0(reg_data
, BMI2_ACC_EN
);
10310 /* Disable gyroscope */
10311 if (sensor_sel
& BMI2_GYRO_SENS_SEL
)
10313 reg_data
= BMI2_SET_BIT_VAL0(reg_data
, BMI2_GYR_EN
);
10316 /* Disable auxiliary sensor */
10317 if (sensor_sel
& BMI2_AUX_SENS_SEL
)
10319 reg_data
= BMI2_SET_BIT_VAL0(reg_data
, BMI2_AUX_EN
);
10322 /* Disable temperature sensor */
10323 if (sensor_sel
& BMI2_TEMP_SENS_SEL
)
10325 reg_data
= BMI2_SET_BIT_VAL0(reg_data
, BMI2_TEMP_EN
);
10328 /* Enable the sensors that are set in the power control register */
10329 if (sensor_sel
& BMI2_MAIN_SENSORS
)
10331 rslt
= bmi2_set_regs(BMI2_PWR_CTRL_ADDR
, ®_data
, 1, dev
);