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.
40 * @defgroup bmi2xy BMI2XY
46 * @brief Sensor driver for BMI2 sensor
57 /***************************************************************************/
60 ****************************************************************************/
61 #include "bmi2_defs.h"
63 /***************************************************************************/
65 /*! BMI2XY User Interface function prototypes
66 ****************************************************************************/
70 * \defgroup bmi2ApiInit Initialization
71 * @brief Initialize the sensor and device structure
75 * \ingroup bmi2ApiInit
76 * \page bmi2_api_bmi2_sec_init bmi2_sec_init
78 * int8_t bmi2_sec_init(struct bmi2_dev *dev);
80 * @details This API is the entry point for bmi2 sensor. It selects between
81 * I2C/SPI interface, based on user selection. It also reads the chip-id of
84 * @param[in,out] dev : Structure instance of bmi2_dev.
86 * @return Result of API execution status
87 * @retval 0 -> Success
90 int8_t bmi2_sec_init(struct bmi2_dev
*dev
);
94 * \defgroup bmi2ApiRegs Registers
95 * @brief Set / Get data from the given register address of the sensor
99 * \ingroup bmi2ApiRegs
100 * \page bmi2_api_bmi2_get_regs bmi2_get_regs
102 * int8_t bmi2_get_regs(uint8_t reg_addr, uint8_t *data, uint16_t len, const struct bmi2_dev *dev);
104 * @details This API reads the data from the given register address of bmi2
107 * @param[in] reg_addr : Register address from which data is read.
108 * @param[out] data : Pointer to data buffer where read data is stored.
109 * @param[in] len : No. of bytes of data to be read.
110 * @param[in] dev : Structure instance of bmi2_dev.
112 * @note For most of the registers auto address increment applies, with the
113 * exception of a few special registers, which trap the address. For e.g.,
114 * Register address - 0x26, 0x5E.
116 * @return Result of API execution status
117 * @retval 0 -> Success
118 * @retval < 0 -> Fail
120 int8_t bmi2_get_regs(uint8_t reg_addr
, uint8_t *data
, uint16_t len
, struct bmi2_dev
*dev
);
123 * \ingroup bmi2ApiRegs
124 * \page bmi2_api_bmi2_set_regs bmi2_set_regs
126 * int8_t bmi2_set_regs(uint8_t reg_addr, const uint8_t *data, uint16_t len, struct bmi2_dev *dev);
128 * @details This API writes data to the given register address of bmi2 sensor.
130 * @param[in] reg_addr : Register address to which the data is written.
131 * @param[in] data : Pointer to data buffer in which data to be written
133 * @param[in] len : No. of bytes of data to be written.
134 * @param[in] dev : Structure instance of bmi2_dev.
136 * @return Result of API execution status
137 * @retval 0 -> Success
138 * @retval < 0 -> Fail
140 int8_t bmi2_set_regs(uint8_t reg_addr
, const uint8_t *data
, uint16_t len
, struct bmi2_dev
*dev
);
144 * \defgroup bmi2ApiSR Soft reset
145 * @brief Set / Get data from the given register address of the sensor
150 * \page bmi2_api_bmi2_soft_reset bmi2_soft_reset
152 * int8_t bmi2_soft_reset(struct bmi2_dev *dev);
154 * @details This API resets bmi2 sensor. All registers are overwritten with
155 * their default values.
157 * @note If selected interface is SPI, an extra dummy byte is read to bring the
158 * interface back to SPI from default, after the soft reset command.
160 * @param[in] dev : Structure instance of bmi2_dev.
162 * @return Result of API execution status
163 * @retval 0 -> Success
164 * @retval < 0 -> Fail
166 int8_t bmi2_soft_reset(struct bmi2_dev
*dev
);
170 * \defgroup bmi2ApiConfig Configuration
171 * @brief Functions related to configuration of the sensor
175 * \ingroup bmi2ApiConfig
176 * \page bmi2_api_bmi2_get_config_file_version bmi2_get_config_file_version
178 * int8_t bmi2_get_config_file_version(uint8_t *config_major, uint8_t *config_minor, struct bmi2_dev *dev);
180 * @details This API is used to get the config file major and minor information.
182 * @param[in] dev : Structure instance of bmi2_dev.
183 * @param[out] config_major : pointer to data buffer to store the config major.
184 * @param[out] config_minor : pointer to data buffer to store the config minor.
186 * @return Result of API execution status
187 * @retval 0 -> Success
188 * @retval < 0 -> Fail
190 int8_t bmi2_get_config_file_version(uint8_t *config_major
, uint8_t *config_minor
, struct bmi2_dev
*dev
);
194 * \defgroup bmi2ApiPowersave Advanced power save mode
195 * @brief Set / Get Advanced power save mode of the sensor
199 * \ingroup bmi2ApiPowersave
200 * \page bmi2_api_bmi2_set_adv_power_save bmi2_set_adv_power_save
202 * int8_t bmi2_set_adv_power_save(uint8_t enable, struct bmi2_dev *dev);
204 * @details This API enables/disables the advance power save mode in the sensor.
206 * @param[in] enable : To enable/disable advance power mode.
207 * @param[in] dev : Structure instance of bmi2_dev.
210 * Enable | Description
211 * -------------|---------------
212 * BMI2_DISABLE | Disables advance power save.
213 * BMI2_ENABLE | Enables advance power save.
216 * @return Result of API execution status
217 * @retval 0 -> Success
218 * @retval < 0 -> Fail
220 int8_t bmi2_set_adv_power_save(uint8_t enable
, struct bmi2_dev
*dev
);
223 * \ingroup bmi2ApiPowersave
224 * \page bmi2_api_bmi2_get_adv_power_save bmi2_get_adv_power_save
226 * int8_t bmi2_get_adv_power_save(uint8_t *aps_status, struct bmi2_dev *dev);
228 * @details This API gets the status of advance power save mode in the sensor.
230 * @param[out] aps_status : Pointer to get the status of APS mode.
231 * @param[in] dev : Structure instance of bmi2_dev.
234 * aps_status | Description
235 * -------------|---------------
236 * BMI2_DISABLE | Advance power save disabled.
237 * BMI2_ENABLE | Advance power save enabled.
240 * @return Result of API execution status
242 * @retval BMI2_OK - Success.
243 * @retval BMI2_E_NULL_PTR - Error: Null pointer error
244 * @retval BMI2_E_COM_FAIL - Error: Communication fail
245 * @retval BMI2_E_SET_APS_FAIL - Error: Set Advance Power Save Fail
247 int8_t bmi2_get_adv_power_save(uint8_t *aps_status
, struct bmi2_dev
*dev
);
250 * \ingroup bmi2ApiConfig
251 * \page bmi2_api_bmi2_write_config_file bmi2_write_config_file
253 * int8_t bmi2_write_config_file(struct bmi2_dev *dev);
255 * @details This API loads the configuration file to the bmi2 sensor.
257 * @param[in] dev : Structure instance of bmi2_dev.
259 * @return Result of API execution status
260 * @retval 0 -> Success
261 * @retval < 0 -> Fail
263 int8_t bmi2_write_config_file(struct bmi2_dev
*dev
);
267 * \defgroup bmi2ApiInt Interrupt
268 * @brief Interrupt operations of the sensor
272 * \ingroup bmi2ApiInt
273 * \page bmi2_api_bmi2_set_int_pin_config bmi2_set_int_pin_config
275 * int8_t bmi2_set_int_pin_config(const struct bmi2_int_pin_config *int_cfg, struct bmi2_dev *dev);
277 * @details This API sets:
278 * 1) The input output configuration of the selected interrupt pin:
280 * 2) The interrupt mode: permanently latched or non-latched.
282 * @param[in] int_cfg : Structure instance of bmi2_int_pin_config.
283 * @param[in] dev : Structure instance of bmi2_dev.
285 * @return Result of API execution status
286 * @retval 0 -> Success
287 * @retval < 0 -> Fail
289 int8_t bmi2_set_int_pin_config(const struct bmi2_int_pin_config
*int_cfg
, struct bmi2_dev
*dev
);
292 * \ingroup bmi2ApiInt
293 * \page bmi2_api_bmi2_get_int_pin_config bmi2_get_int_pin_config
295 * int8_t bmi2_get_int_pin_config(struct bmi2_int_pin_config *int_cfg, const struct bmi2_dev *dev);
297 * @details This API gets:
298 * 1) The input output configuration of the selected interrupt pin:
300 * 2) The interrupt mode: permanently latched or non-latched.
302 * @param[in,out] int_cfg : Structure instance of bmi2_int_pin_config.
303 * @param[in] dev : Structure instance of bmi2_dev.
305 * @return Result of API execution status
306 * @retval 0 -> Success
307 * @retval < 0 -> Fail
309 int8_t bmi2_get_int_pin_config(struct bmi2_int_pin_config
*int_cfg
, struct bmi2_dev
*dev
);
312 * \ingroup bmi2ApiInt
313 * \page bmi2_api_bmi2_get_int_status bmi2_get_int_status
315 * int8_t bmi2_get_int_status(uint16_t *int_status, const struct bmi2_dev *dev);
317 * @details This API gets the interrupt status of both feature and data
320 * @param[out] int_status : Pointer to get the status of the interrupts.
321 * @param[in] dev : Structure instance of bmi2_dev.
324 * int_status | Status
325 * -----------|------------
336 * @return Result of API execution status
337 * @retval 0 -> Success
338 * @retval < 0 -> Fail
340 int8_t bmi2_get_int_status(uint16_t *int_status
, struct bmi2_dev
*dev
);
344 * \defgroup bmi2ApiSensorC Sensor Configuration
345 * @brief Enable / Disable feature configuration of the sensor
349 * \ingroup bmi2ApiSensorC
350 * \page bmi2_api_bmi2_set_sensor_config bmi2_set_sensor_config
352 * int8_t bmi2_set_sensor_config(struct bmi2_sens_config *sens_cfg, uint8_t n_sens, struct bmi2_dev *dev);
354 * @details This API sets the sensor/feature configuration.
356 * @param[in] sens_cfg : Structure instance of bmi2_sens_config.
357 * @param[in] n_sens : Number of sensors selected.
358 * @param[in, out] dev : Structure instance of bmi2_dev.
360 * @note Sensors/features that can be configured
364 * ----------------------------|-----------
368 * BMI2_GYRO_GAIN_UPDATE | 9
371 * @return Result of API execution status
372 * @retval 0 -> Success
373 * @retval < 0 -> Fail
375 int8_t bmi2_set_sensor_config(struct bmi2_sens_config
*sens_cfg
, uint8_t n_sens
, struct bmi2_dev
*dev
);
378 * \ingroup bmi2ApiSensorC
379 * \page bmi2_api_bmi2_get_sensor_config bmi2_get_sensor_config
381 * int8_t bmi2_get_sensor_config(struct bmi2_sens_config *sens_cfg, uint8_t n_sens, struct bmi2_dev *dev);
383 * @details This API gets the sensor/feature configuration.
385 * @param[in] sens_cfg : Structure instance of bmi2_sens_config.
386 * @param[in] n_sens : Number of sensors selected.
387 * @param[in, out] dev : Structure instance of bmi2_dev.
389 * @note Sensors/features whose configurations can be read.
393 * -------------------------|-----------
397 * BMI2_GYRO_GAIN_UPDATE | 9
400 * @return Result of API execution status
401 * @retval 0 -> Success
402 * @retval < 0 -> Fail
404 int8_t bmi2_get_sensor_config(struct bmi2_sens_config
*sens_cfg
, uint8_t n_sens
, struct bmi2_dev
*dev
);
408 * \defgroup bmi2ApiSensor Feature Set
409 * @brief Enable / Disable features of the sensor
413 * \ingroup bmi2ApiSensor
414 * \page bmi2_api_bmi2_sensor_enable bmi2_sensor_enable
416 * int8_t bmi2_sensor_enable(const uint8_t *sens_list, uint8_t n_sens, struct bmi2_dev *dev);
418 * @details This API selects the sensors/features to be enabled.
420 * @param[in] sens_list : Pointer to select the sensor/feature.
421 * @param[in] n_sens : Number of sensors selected.
422 * @param[in, out] dev : Structure instance of bmi2_dev.
424 * @note Sensors/features that can be enabled.
428 * -------------------------|-----------
436 * example uint8_t sens_list[2] = {BMI2_ACCEL, BMI2_GYRO};
437 * uint8_t n_sens = 2;
439 * @return Result of API execution status
440 * @retval 0 -> Success
441 * @retval < 0 -> Fail
443 int8_t bmi2_sensor_enable(const uint8_t *sens_list
, uint8_t n_sens
, struct bmi2_dev
*dev
);
446 * \ingroup bmi2ApiSensor
447 * \page bmi2_api_bmi2_sensor_disable bmi2_sensor_disable
449 * int8_t bmi2_sensor_disable(const uint8_t *sens_list, uint8_t n_sens, struct bmi2_dev *dev);
451 * @details This API selects the sensors/features to be disabled.
453 * @param[in] sens_list : Pointer to select the sensor/feature.
454 * @param[in] n_sens : Number of sensors selected.
455 * @param[in, out] dev : Structure instance of bmi2_dev.
457 * @note Sensors/features that can be disabled.
461 * ----------------------------|-----------
469 * example uint8_t sens_list[2] = {BMI2_ACCEL, BMI2_GYRO};
470 * uint8_t n_sens = 2;
472 * @return Result of API execution status
473 * @retval 0 -> Success
474 * @retval < 0 -> Fail
476 int8_t bmi2_sensor_disable(const uint8_t *sens_list
, uint8_t n_sens
, struct bmi2_dev
*dev
);
480 * \defgroup bmi2ApiSensorD Sensor Data
481 * @brief Get sensor data
485 * \ingroup bmi2ApiSensorD
486 * \page bmi2_api_bmi2_get_sensor_data bmi2_get_sensor_data
488 * int8_t bmi2_get_sensor_data(struct bmi2_sensor_data *sensor_data, uint8_t n_sens, struct bmi2_dev *dev);
490 * @details This API gets the sensor/feature data for accelerometer, gyroscope,
491 * auxiliary sensor, step counter, high-g, gyroscope user-gain update,
492 * orientation, gyroscope cross sensitivity and error status for NVM and VFRM.
494 * @param[out] sensor_data : Structure instance of bmi2_sensor_data.
495 * @param[in] n_sens : Number of sensors selected.
496 * @param[in] dev : Structure instance of bmi2_dev.
498 * @note Sensors/features whose data can be read
502 * ---------------------|-----------
506 * BMI2_GYRO_GAIN_UPDATE| 12
507 * BMI2_GYRO_CROSS_SENSE| 28
510 * @return Result of API execution status
511 * @retval 0 -> Success
512 * @retval < 0 -> Fail
514 int8_t bmi2_get_sensor_data(struct bmi2_sensor_data
*sensor_data
, uint8_t n_sens
, struct bmi2_dev
*dev
);
518 * \defgroup bmi2ApiFIFO FIFO
519 * @brief FIFO operations of the sensor
523 * \ingroup bmi2ApiFIFO
524 * \page bmi2_api_bmi2_set_fifo_config bmi2_set_fifo_config
526 * int8_t bmi2_set_fifo_config(uint16_t config, uint8_t enable, struct bmi2_dev *dev);
528 * @details This API sets the FIFO configuration in the sensor.
530 * @param[in] config : FIFO configurations to be enabled/disabled.
531 * @param[in] enable : Enable/Disable FIFO configurations.
532 * @param[in] dev : Structure instance of bmi2_dev.
535 * enable | Description
536 * -------------|---------------
537 * BMI2_DISABLE | Disables FIFO configuration.
538 * BMI2_ENABLE | Enables FIFO configuration.
541 * @return Result of API execution status
542 * @retval 0 -> Success
543 * @retval < 0 -> Fail
545 int8_t bmi2_set_fifo_config(uint16_t config
, uint8_t enable
, struct bmi2_dev
*dev
);
548 * \ingroup bmi2ApiFIFO
549 * \page bmi2_api_bmi2_get_fifo_config bmi2_get_fifo_config
551 * int8_t bmi2_get_fifo_config(uint16_t *fifo_config, const struct bmi2_dev *dev);
553 * @details This API gets the FIFO configuration from the sensor.
555 * @param[out] fifo_config : Pointer variable to get FIFO configuration value.
556 * @param[in] dev : Structure instance of bmi2_dev.
558 * @return Result of API execution status
559 * @retval 0 -> Success
560 * @retval < 0 -> Fail
562 int8_t bmi2_get_fifo_config(uint16_t *fifo_config
, struct bmi2_dev
*dev
);
565 * \ingroup bmi2ApiFIFO
566 * \page bmi2_api_bmi2_read_fifo_data bmi2_read_fifo_data
568 * int8_t bmi2_read_fifo_data(struct bmi2_fifo_frame *fifo, const struct bmi2_dev *dev);
570 * @details This API reads FIFO data.
572 * @param[in, out] fifo : Structure instance of bmi2_fifo_frame.
573 * @param[in] dev : Structure instance of bmi2_dev.
575 * @note APS has to be disabled before calling this function.
577 * @return Result of API execution status
578 * @retval 0 -> Success
579 * @retval < 0 -> Fail
581 int8_t bmi2_read_fifo_data(struct bmi2_fifo_frame
*fifo
, struct bmi2_dev
*dev
);
584 * \ingroup bmi2ApiFIFO
585 * \page bmi2_api_bmi2_extract_accel bmi2_extract_accel
587 * int8_t bmi2_extract_accel(struct bmi2_sens_axes_data *accel_data,
588 * uint16_t *accel_length,
589 * struct bmi2_fifo_frame *fifo,
590 * const struct bmi2_dev *dev);
592 * @details This API parses and extracts the accelerometer frames from FIFO data read by
593 * the "bmi2_read_fifo_data" API and stores it in the "accel_data" structure
596 * @param[out] accel_data : Structure instance of bmi2_sens_axes_data
597 * where the parsed data bytes are stored.
598 * @param[in,out] accel_length : Number of accelerometer frames.
599 * @param[in,out] fifo : Structure instance of bmi2_fifo_frame.
600 * @param[in] dev : Structure instance of bmi2_dev.
602 * @return Result of API execution status
603 * @retval 0 -> Success
604 * @retval < 0 -> Fail
606 int8_t bmi2_extract_accel(struct bmi2_sens_axes_data
*accel_data
,
607 uint16_t *accel_length
,
608 struct bmi2_fifo_frame
*fifo
,
609 const struct bmi2_dev
*dev
);
612 * \ingroup bmi2ApiFIFO
613 * \page bmi2_api_bmi2_extract_aux bmi2_extract_aux
615 * int8_t bmi2_extract_aux(struct bmi2_aux_fifo_data *aux,
616 * uint16_t *aux_length,
617 * struct bmi2_fifo_frame *fifo,
618 * const struct bmi2_dev *dev);
621 * @details This API parses and extracts the auxiliary frames from FIFO data
622 * read by the "bmi2_read_fifo_data" API and stores it in "aux_data" buffer.
624 * @param[out] aux : Pointer to structure where the parsed auxiliary
625 * data bytes are stored.
626 * @param[in,out] aux_length : Number of auxiliary frames.
627 * @param[in,out] fifo : Structure instance of bmi2_fifo_frame.
628 * @param[in] dev : Structure instance of bmi2_dev.
630 * @return Result of API execution status
631 * @retval 0 -> Success
632 * @retval < 0 -> Fail
634 int8_t bmi2_extract_aux(struct bmi2_aux_fifo_data
*aux
,
635 uint16_t *aux_length
,
636 struct bmi2_fifo_frame
*fifo
,
637 const struct bmi2_dev
*dev
);
640 * \ingroup bmi2ApiFIFO
641 * \page bmi2_api_bmi2_extract_gyro bmi2_extract_gyro
643 * int8_t bmi2_extract_gyro(struct bmi2_sens_axes_data *gyro_data,
644 * uint16_t *gyro_length,
645 * struct bmi2_fifo_frame *fifo,
646 * const struct bmi2_dev *dev);
648 * @details This API parses and extracts the gyroscope frames from FIFO data read by the
649 * "bmi2_read_fifo_data" API and stores it in the "gyro_data"
650 * structure instance.
652 * @param[out] gyro_data : Structure instance of bmi2_sens_axes_data
653 * where the parsed data bytes are stored.
654 * @param[in,out] gyro_length : Number of gyroscope frames.
655 * @param[in,out] fifo : Structure instance of bmi2_fifo_frame.
656 * @param[in] dev : Structure instance of bmi2_dev.
658 * @return Result of API execution status
659 * @retval 0 -> Success
660 * @retval < 0 -> Fail
662 int8_t bmi2_extract_gyro(struct bmi2_sens_axes_data
*gyro_data
,
663 uint16_t *gyro_length
,
664 struct bmi2_fifo_frame
*fifo
,
665 const struct bmi2_dev
*dev
);
669 * \defgroup bmi2ApiCmd Command Register
670 * @brief Write commands to the sensor
674 * \ingroup bmi2ApiCmd
675 * \page bmi2_api_bmi2_set_command_register bmi2_set_command_register
677 * int8_t bmi2_set_command_register(uint8_t command, struct bmi2_dev *dev);
679 * @details This API writes the available sensor specific commands to the sensor.
681 * @param[in] command : Commands to be given to the sensor.
682 * @param[in] dev : Structure instance of bmi2_dev.
686 * ---------------------|---------------------
687 * BMI2_SOFT_RESET_CMD | 0xB6
688 * BMI2_FIFO_FLUSH_CMD | 0xB0
689 * BMI2_USR_GAIN_CMD | 0x03
692 * @return Result of API execution status
693 * @retval 0 -> Success
694 * @retval < 0 -> Fail
696 int8_t bmi2_set_command_register(uint8_t command
, struct bmi2_dev
*dev
);
699 * \ingroup bmi2ApiFIFO
700 * \page bmi2_api_bmi2_set_fifo_self_wake_up bmi2_set_fifo_self_wake_up
702 * int8_t bmi2_set_fifo_self_wake_up(uint8_t fifo_self_wake_up, struct bmi2_dev *dev);
704 * @details This API sets the FIFO self wake up functionality in the sensor.
706 * @param[in] fifo_self_wake_up : Variable to set FIFO self wake-up.
707 * @param[in] dev : Structure instance of bmi2_dev.
710 * fifo_self_wake_up | Description
711 * -------------------|---------------
712 * BMI2_DISABLE | Disables self wake-up.
713 * BMI2_ENABLE | Enables self wake-up.
716 * @return Result of API execution status
717 * @retval 0 -> Success
718 * @retval < 0 -> Fail
720 int8_t bmi2_set_fifo_self_wake_up(uint8_t fifo_self_wake_up
, struct bmi2_dev
*dev
);
723 * \ingroup bmi2ApiFIFO
724 * \page bmi2_api_bmi2_get_fifo_self_wake_up bmi2_get_fifo_self_wake_up
726 * int8_t bmi2_get_fifo_self_wake_up(uint8_t *fifo_self_wake_up, const struct bmi2_dev *dev);
728 * @details This API gets the FIFO self wake up functionality from the sensor.
730 * @param[out] fifo_self_wake_up : Pointer variable to get the status of FIFO
732 * @param[in] dev : Structure instance of bmi2_dev.
735 * fifo_self_wake_up | Description
736 * -------------------|---------------
737 * BMI2_DISABLE | Self wake-up disabled
738 * BMI2_ENABLE | Self wake-up enabled.
741 * @return Result of API execution status
742 * @retval 0 -> Success
743 * @retval < 0 -> Fail
745 int8_t bmi2_get_fifo_self_wake_up(uint8_t *fifo_self_wake_up
, struct bmi2_dev
*dev
);
748 * \ingroup bmi2ApiFIFO
749 * \page bmi2_api_bmi2_set_fifo_wm bmi2_set_fifo_wm
751 * int8_t bmi2_set_fifo_wm(uint16_t fifo_wm, struct bmi2_dev *dev);
753 * @details This API sets the FIFO water mark level which is set in the sensor.
755 * @param[in] fifo_wm : Variable to set FIFO water-mark level.
756 * @param[in] dev : Structure instance of bmi2_dev.
758 * @return Result of API execution status
759 * @retval 0 -> Success
760 * @retval < 0 -> Fail
762 int8_t bmi2_set_fifo_wm(uint16_t fifo_wm
, struct bmi2_dev
*dev
);
765 * \ingroup bmi2ApiFIFO
766 * \page bmi2_api_bmi2_get_fifo_wm bmi2_get_fifo_wm
768 * int8_t bmi2_get_fifo_wm(uint16_t *fifo_wm, const struct bmi2_dev *dev);
770 * @details This API gets the FIFO water mark level which is set in the sensor.
772 * @param[out] fifo_wm : Pointer variable to store FIFO water-mark level.
773 * @param[in] dev : Structure instance of bmi2_dev.
775 * @return Result of API execution status
776 * @retval 0 -> Success
777 * @retval < 0 -> Fail
779 int8_t bmi2_get_fifo_wm(uint16_t *fifo_wm
, struct bmi2_dev
*dev
);
782 * \ingroup bmi2ApiFIFO
783 * \page bmi2_api_bmi2_set_fifo_filter_data bmi2_set_fifo_filter_data
785 * int8_t bmi2_set_fifo_filter_data(uint8_t sens_sel, uint8_t fifo_filter_data, struct bmi2_dev *dev);
787 * @details This API sets either filtered or un-filtered FIFO accelerometer or
790 * @param[in] sens_sel : Selects either accelerometer or
792 * @param[in] fifo_filter_data : Variable to set the filter data.
793 * @param[in] dev : Structure instance of bmi2_dev.
797 * -----------------|----------
803 * Value | fifo_filter_data
804 * ---------|---------------------
805 * 0x00 | Un-filtered data
806 * 0x01 | Filtered data
809 * @return Result of API execution status
810 * @retval 0 -> Success
811 * @retval < 0 -> Fail
813 int8_t bmi2_set_fifo_filter_data(uint8_t sens_sel
, uint8_t fifo_filter_data
, struct bmi2_dev
*dev
);
816 * \ingroup bmi2ApiFIFO
817 * \page bmi2_api_bmi2_get_fifo_filter_data bmi2_get_fifo_filter_data
819 * int8_t bmi2_get_fifo_filter_data(uint8_t sens_sel, uint8_t *fifo_filter_data, const struct bmi2_dev *dev);
821 * @details This API gets the FIFO accelerometer or gyroscope filter data.
823 * @param[in] sens_sel : Selects either accelerometer or
825 * @param[out] fifo_filter_data : Pointer variable to get the filter data.
826 * @param[in] dev : Structure instance of bmi2_dev.
830 * -----------------|----------
836 * Value | fifo_filter_data
837 * ---------|---------------------
838 * 0x00 | Un-filtered data
839 * 0x01 | Filtered data
842 * @return Result of API execution status
843 * @retval 0 -> Success
844 * @retval < 0 -> Fail
846 int8_t bmi2_get_fifo_filter_data(uint8_t sens_sel
, uint8_t *fifo_filter_data
, struct bmi2_dev
*dev
);
849 * \ingroup bmi2ApiFIFO
850 * \page bmi2_api_bmi2_set_fifo_down_sample bmi2_set_fifo_down_sample
852 * int8_t bmi2_set_fifo_down_sample(uint8_t sens_sel, uint8_t fifo_down_samp, struct bmi2_dev *dev);
854 * @details This API sets the down sampling rate for FIFO accelerometer or
855 * gyroscope FIFO data.
857 * @param[in] sens_sel : Selects either either accelerometer or
859 * @param[in] fifo_down_samp : Variable to set the down sampling rate.
860 * @param[in] dev : Structure instance of bmi2_dev.
864 * ----------------|----------
869 * @return Result of API execution status
870 * @retval 0 -> Success
871 * @retval < 0 -> Fail
873 int8_t bmi2_set_fifo_down_sample(uint8_t sens_sel
, uint8_t fifo_down_samp
, struct bmi2_dev
*dev
);
876 * \ingroup bmi2ApiFIFO
877 * \page bmi2_api_bmi2_get_fifo_down_sample bmi2_get_fifo_down_sample
879 * int8_t bmi2_get_fifo_down_sample(uint8_t sens_sel, uint8_t *fifo_down_samp, const struct bmi2_dev *dev);
881 * @details This API gets the down sampling rate, configured for FIFO
882 * accelerometer or gyroscope data.
884 * @param[in] sens_sel : Selects either either accelerometer or
886 * @param[out] fifo_down_samp : Pointer variable to store the down sampling rate
887 * @param[in] dev : Structure instance of bmi2_dev.
891 * ----------------|----------
896 * @return Result of API execution status
897 * @retval 0 -> Success
898 * @retval < 0 -> Fail
900 int8_t bmi2_get_fifo_down_sample(uint8_t sens_sel
, uint8_t *fifo_down_samp
, struct bmi2_dev
*dev
);
903 * \ingroup bmi2ApiFIFO
904 * \page bmi2_api_bmi2_get_fifo_length bmi2_get_fifo_length
906 * int8_t bmi2_get_fifo_length(uint16_t *fifo_length, const struct bmi2_dev *dev);
908 * @details This API gets the length of FIFO data available in the sensor in
911 * @param[out] fifo_length : Pointer variable to store the value of FIFO byte
913 * @param[in] dev : Structure instance of bmi2_dev.
915 * @note The byte counter is updated each time a complete frame is read or
918 * @return Result of API execution status
919 * @retval 0 -> Success
920 * @retval < 0 -> Fail
922 int8_t bmi2_get_fifo_length(uint16_t *fifo_length
, struct bmi2_dev
*dev
);
926 * \defgroup bmi2ApiOIS OIS
927 * @brief OIS operations of the sensor
931 * \ingroup bmi2ApiOIS
932 * \page bmi2_api_bmi2_set_ois_interface bmi2_set_ois_interface
934 * int8_t bmi2_set_ois_interface(uint8_t enable, struct bmi2_dev *dev);
936 * @details This API enables/disables OIS interface.
938 * @param[in] enable : To enable/disable OIS interface.
939 * @param[in] dev : Structure instance of bmi2_dev.
942 * Enable | Description
943 * -------------|---------------
944 * BMI2_DISABLE | Disables OIS interface.
945 * BMI2_ENABLE | Enables OIS interface.
948 * @return Result of API execution status
949 * @retval 0 -> Success
950 * @retval < 0 -> Fail
952 int8_t bmi2_set_ois_interface(uint8_t enable
, struct bmi2_dev
*dev
);
956 * \defgroup bmi2ApiAux Auxiliary sensor
957 * @brief Auxiliary sensor operations of the sensor
961 * \ingroup bmi2ApiAux
962 * \page bmi2_api_bmi2_read_aux_man_mode bmi2_read_aux_man_mode
964 * int8_t bmi2_read_aux_man_mode(uint8_t reg_addr, uint8_t *aux_data, uint16_t len, struct bmi2_dev *dev);
966 * @details This API reads the user-defined bytes of data from the given register
967 * address of auxiliary sensor in manual mode.
969 * @param[in] reg_addr : Address from where data is read.
970 * @param[out] aux_data : Pointer to the stored buffer.
971 * @param[in] len : Total length of data to be read.
972 * @param[in] dev : Structure instance of bmi2_dev.
974 * @note Change of BMI2_AUX_RD_ADDR is only allowed if AUX is not busy.
976 * @return Result of API execution status
977 * @retval 0 -> Success
978 * @retval < 0 -> Fail
980 int8_t bmi2_read_aux_man_mode(uint8_t reg_addr
, uint8_t *aux_data
, uint16_t len
, struct bmi2_dev
*dev
);
983 * \ingroup bmi2ApiAux
984 * \page bmi2_api_bmi2_write_aux_man_mode bmi2_write_aux_man_mode
986 * int8_t bmi2_write_aux_man_mode(uint8_t reg_addr, const uint8_t *aux_data, uint16_t len, struct bmi2_dev *dev);
988 * @details This API writes the user-defined bytes of data and the address of
989 * auxiliary sensor where data is to be written in manual mode.
991 * @param[in] reg_addr : AUX address where data is to be written.
992 * @param[in] aux_data : Pointer to data to be written.
993 * @param[in] len : Total length of data to be written.
994 * @param[in] dev : Structure instance of bmi2_dev.
996 * @note Change of BMI2_AUX_WR_ADDR is only allowed if AUX is not busy.
998 * @return Result of API execution status
999 * @retval 0 -> Success
1000 * @retval < 0 -> Fail
1002 int8_t bmi2_write_aux_man_mode(uint8_t reg_addr
, const uint8_t *aux_data
, uint16_t len
, struct bmi2_dev
*dev
);
1005 * \ingroup bmi2ApiAux
1006 * \page bmi2_api_bmi2_write_aux_interleaved bmi2_write_aux_interleaved
1008 * int8_t bmi2_write_aux_interleaved(uint8_t reg_addr, const uint8_t *aux_data, uint16_t len, struct bmi2_dev *dev);
1010 * @details This API writes the user-defined bytes of data and the address of
1011 * auxiliary sensor where data is to be written, from an interleaved input,
1014 * @param[in] reg_addr : AUX address where data is to be written.
1015 * @param[in] aux_data : Pointer to data to be written.
1016 * @param[in] len : Total length of data to be written.
1017 * @param[in] dev : Structure instance of bmi2_dev.
1019 * @note Change of BMI2_AUX_WR_ADDR is only allowed if AUX is not busy.
1021 * @return Result of API execution status
1022 * @retval 0 -> Success
1023 * @retval < 0 -> Fail
1025 int8_t bmi2_write_aux_interleaved(uint8_t reg_addr
, const uint8_t *aux_data
, uint16_t len
, struct bmi2_dev
*dev
);
1029 * \defgroup bmi2ApiStatus Sensor Status
1030 * @brief Get sensor status
1034 * \ingroup bmi2ApiStatus
1035 * \page bmi2_api_bmi2_get_status bmi2_get_status
1037 * int8_t bmi2_get_status(uint8_t *status, const struct bmi2_dev *dev);
1039 * @details This API gets the data ready status of accelerometer, gyroscope,
1040 * auxiliary, ready status of command decoder and busy status of auxiliary.
1042 * @param[out] status : Pointer variable to the status.
1043 * @param[in] dev : Structure instance of bmi2_dev.
1047 * ---------|---------------------
1055 * @return Result of API execution status
1056 * @retval 0 -> Success
1057 * @retval < 0 -> Fail
1059 int8_t bmi2_get_status(uint8_t *status
, struct bmi2_dev
*dev
);
1063 * \defgroup bmi2ApiWSync Sync commands
1064 * @brief Write sync commands
1068 * \ingroup bmi2ApiWSync
1069 * \page bmi2_api_bmi2_write_sync_commands bmi2_write_sync_commands
1071 * int8_t bmi2_write_sync_commands(const uint8_t *command, uint8_t n_comm, struct bmi2_dev *dev);
1073 * @details This API can be used to write sync commands like ODR, sync period,
1074 * frequency and phase, resolution ratio, sync time and delay time.
1076 * @param[in] command : Sync command to be written.
1077 * @param[in] n_comm : Length of the command.
1078 * @param[in] dev : Structure instance of bmi2_dev.
1080 * @return Result of API execution status
1081 * @retval 0 -> Success
1082 * @retval < 0 -> Fail
1084 int8_t bmi2_write_sync_commands(const uint8_t *command
, uint8_t n_comm
, struct bmi2_dev
*dev
);
1088 * \defgroup bmi2ApiASelftest Accel self test
1089 * @brief Perform accel self test
1093 * \ingroup bmi2ApiASelftest
1094 * \page bmi2_api_bmi2_perform_accel_self_test bmi2_perform_accel_self_test
1096 * int8_t bmi2_perform_accel_self_test(struct bmi2_dev *dev);
1098 * @details This API performs self-test to check the proper functionality of the
1099 * accelerometer sensor.
1101 * @param[in] dev : Structure instance of bmi2_dev.
1103 * @return Result of API execution status
1104 * @retval 0 -> Success
1105 * @retval < 0 -> Fail
1107 int8_t bmi2_perform_accel_self_test(struct bmi2_dev
*dev
);
1110 * \ingroup bmi2ApiInt
1111 * \page bmi2_api_bmi2_map_feat_int bmi2_map_feat_int
1113 * int8_t bmi2_map_feat_int(const struct bmi2_sens_int_config *sens_int, struct bmi2_dev *dev);
1115 * @details This API maps/unmaps feature interrupts to that of interrupt pins.
1117 * @param[in] sens_int : Structure instance of bmi2_sens_int_config.
1118 * @param[in] dev : Structure instance of bmi2_dev.
1120 * @return Result of API execution status
1121 * @retval 0 -> Success
1122 * @retval < 0 -> Fail
1124 int8_t bmi2_map_feat_int(uint8_t type
, enum bmi2_hw_int_pin hw_int_pin
, struct bmi2_dev
*dev
);
1127 * \ingroup bmi2ApiInt
1128 * \page bmi2_api_bmi2_map_data_int bmi2_map_data_int
1130 * int8_t bmi2_map_data_int(uint8_t data_int, enum bmi2_hw_int_pin int_pin, struct bmi2_dev *dev);
1132 * @details This API maps/un-maps data interrupts to that of interrupt pins.
1134 * @param[in] int_pin : Interrupt pin selected.
1135 * @param[in] data_int : Type of data interrupt to be mapped.
1136 * @param[in] dev : Structure instance of bmi2_dev.
1139 * data_int | Mask values
1140 * ---------------------|---------------------
1141 * BMI2_FFULL_INT | 0x01
1142 * BMI2_FWM_INT | 0x02
1143 * BMI2_DRDY_INT | 0x04
1144 * BMI2_ERR_INT | 0x08
1147 * @return Result of API execution status
1148 * @retval 0 -> Success
1149 * @retval < 0 -> Fail
1151 int8_t bmi2_map_data_int(uint8_t data_int
, enum bmi2_hw_int_pin int_pin
, struct bmi2_dev
*dev
);
1155 * \defgroup bmi2ApiRemap Remap Axes
1156 * @brief Set / Get remap axes values from the sensor
1160 * \ingroup bmi2ApiRemap
1161 * \page bmi2_api_bmi2_get_remap_axes bmi2_get_remap_axes
1163 * int8_t bmi2_get_remap_axes(struct bmi2_remap *remapped_axis, struct bmi2_dev *dev);
1165 * @details This API gets the re-mapped x, y and z axes from the sensor and
1166 * updates the values in the device structure.
1168 * @param[out] remapped_axis : Structure that stores re-mapped axes.
1169 * @param[in] dev : Structure instance of bmi2_dev.
1171 * @return Result of API execution status
1172 * @retval 0 -> Success
1173 * @retval < 0 -> Fail
1175 int8_t bmi2_get_remap_axes(struct bmi2_remap
*remapped_axis
, struct bmi2_dev
*dev
);
1178 * \ingroup bmi2ApiRemap
1179 * \page bmi2_api_bmi2_set_remap_axes bmi2_set_remap_axes
1181 * int8_t bmi2_set_remap_axes(const struct bmi2_remap *remapped_axis, struct bmi2_dev *dev);
1183 * @details This API sets the re-mapped x, y and z axes to the sensor and
1184 * updates them in the device structure.
1186 * @param[in] remapped_axis : Structure that stores re-mapped axes.
1187 * @param[in] dev : Structure instance of bmi2_dev.
1189 * @return Result of API execution status
1190 * @retval 0 -> Success
1191 * @retval < 0 -> Fail
1193 int8_t bmi2_set_remap_axes(const struct bmi2_remap
*remapped_axis
, struct bmi2_dev
*dev
);
1197 * \defgroup bmi2ApiGyroOC Gyro Offset Compensation
1198 * @brief Gyro Offset Compensation operations of the sensor
1202 * \ingroup bmi2ApiGyroOC
1203 * \page bmi2_api_bmi2_set_gyro_offset_comp bmi2_set_gyro_offset_comp
1205 * int8_t bmi2_set_gyro_offset_comp(uint8_t enable, struct bmi2_dev *dev);
1207 * @details This API enables/disables gyroscope offset compensation. It adds the
1208 * offsets defined in the offset register with gyroscope data.
1210 * @param[in] enable : Enables/Disables gyroscope offset compensation.
1211 * @param[in] dev : Structure instance of bmi2_dev.
1214 * enable | Description
1215 * -------------|---------------
1216 * BMI2_ENABLE | Enables gyroscope offset compensation.
1217 * BMI2_DISABLE | Disables gyroscope offset compensation.
1220 * @return Result of API execution status
1221 * @retval 0 -> Success
1222 * @retval < 0 -> Fail
1224 int8_t bmi2_set_gyro_offset_comp(uint8_t enable
, struct bmi2_dev
*dev
);
1227 * \ingroup bmi2ApiGyroOC
1228 * \page bmi2_api_bmi2_read_gyro_offset_comp_axes bmi2_read_gyro_offset_comp_axes
1230 * int8_t bmi2_read_gyro_offset_comp_axes(struct bmi2_sens_axes_data *gyr_off_comp_axes, const struct bmi2_dev *dev);
1232 * @details This API reads the gyroscope bias values for each axis which is used
1233 * for gyroscope offset compensation.
1235 * @param[out] gyr_off_comp_axes: Structure to store gyroscope offset
1236 * compensated values.
1237 * @param[in] dev : Structure instance of bmi2_dev.
1239 * @return Result of API execution status
1240 * @retval 0 -> Success
1241 * @retval < 0 -> Fail
1243 int8_t bmi2_read_gyro_offset_comp_axes(struct bmi2_sens_axes_data
*gyr_off_comp_axes
, struct bmi2_dev
*dev
);
1246 * \ingroup bmi2ApiGyroOC
1247 * \page bmi2_api_bmi2_write_gyro_offset_comp_axes bmi2_write_gyro_offset_comp_axes
1249 * int8_t bmi2_write_gyro_offset_comp_axes(const struct bmi2_sens_axes_data *gyr_off_comp_axes, struct bmi2_dev *dev);
1251 * @details This API writes the gyroscope bias values for each axis which is used
1252 * for gyroscope offset compensation.
1254 * @param[in] gyr_off_comp_axes : Structure to store gyroscope offset
1255 * compensated values.
1256 * @param[in] dev : Structure instance of bmi2_dev.
1258 * @return Result of API execution status
1259 * @retval 0 -> Success
1260 * @retval < 0 -> Fail
1262 int8_t bmi2_write_gyro_offset_comp_axes(const struct bmi2_sens_axes_data
*gyr_off_comp_axes
, struct bmi2_dev
*dev
);
1266 * \defgroup bmi2ApiGyroCS Gyro cross sensitivity
1267 * @brief Gyro Cross sensitivity operation
1271 * \ingroup bmi2ApiGyroCS
1272 * \page bmi2_api_bmi2_get_gyro_cross_sense bmi2_get_gyro_cross_sense
1274 * int8_t bmi2_get_gyro_cross_sense(struct bmi2_dev *dev);
1276 * @details This API updates the cross sensitivity coefficient between gyroscope's
1279 * @param[in, out] dev : Structure instance of bmi2_dev.
1281 * @return Result of API execution status
1282 * @retval 0 -> Success
1283 * @retval < 0 -> Fail
1285 int8_t bmi2_get_gyro_cross_sense(struct bmi2_dev
*dev
);
1289 * \defgroup bmi2ApiInts Internal Status
1290 * @brief Get Internal Status of the sensor
1294 * \ingroup bmi2ApiInts
1295 * \page bmi2_api_bmi2_get_internal_status bmi2_get_internal_status
1297 * int8_t bmi2_get_internal_status(uint8_t *int_stat, const struct bmi2_dev *dev);
1299 * @details This API gets error bits and message indicating internal status.
1301 * @param[in] dev : Structure instance of bmi2_dev.
1302 * @param[out] int_stat : Pointer variable to store error bits and
1306 * Internal status | *int_stat
1307 * ---------------------|---------------------
1308 * BMI2_NOT_INIT | 0x00
1309 * BMI2_INIT_OK | 0x01
1310 * BMI2_INIT_ERR | 0x02
1311 * BMI2_DRV_ERR | 0x03
1312 * BMI2_SNS_STOP | 0x04
1313 * BMI2_NVM_ERROR | 0x05
1314 * BMI2_START_UP_ERROR | 0x06
1315 * BMI2_COMPAT_ERROR | 0x07
1316 * BMI2_VFM_SKIPPED | 0x10
1317 * BMI2_AXES_MAP_ERROR | 0x20
1318 * BMI2_ODR_50_HZ_ERROR | 0x40
1319 * BMI2_ODR_HIGH_ERROR | 0x80
1322 * @return Result of API execution status
1323 * @retval 0 -> Success
1324 * @retval < 0 -> Fail
1326 int8_t bmi2_get_internal_status(uint8_t *int_stat
, struct bmi2_dev
*dev
);
1330 * \defgroup bmi2ApiFOC FOC
1331 * @brief FOC operations of the sensor
1335 * \ingroup bmi2ApiFOC
1336 * \page bmi2_api_bmi2_perform_accel_foc bmi2_perform_accel_foc
1338 * int8_t bmi2_perform_accel_foc(const struct bmi2_accel_foc_g_value *accel_g_value, struct bmi2_dev *dev);
1340 * @details This API performs Fast Offset Compensation for accelerometer.
1342 * @param[in] accel_g_value : This parameter selects the accel foc
1343 * axis to be performed
1345 * input format is {x, y, z, sign}. '1' to enable. '0' to disable
1347 * eg to choose x axis {1, 0, 0, 0}
1348 * eg to choose -x axis {1, 0, 0, 1}
1351 * @param[in] dev : Structure instance of bmi2_dev.
1353 * @return Result of API execution status
1354 * @retval 0 -> Success
1355 * @retval < 0 -> Fail
1357 int8_t bmi2_perform_accel_foc(const struct bmi2_accel_foc_g_value
*accel_g_value
, struct bmi2_dev
*dev
);
1360 * \ingroup bmi2ApiFOC
1361 * \page bmi2_api_bmi2_perform_gyro_foc bmi2_perform_gyro_foc
1363 * int8_t bmi2_perform_gyro_foc(struct bmi2_dev *dev);
1365 * @details This API performs Fast Offset Compensation for gyroscope.
1367 * @param[in] dev : Structure instance of bmi2_dev.
1369 * @return Result of API execution status
1370 * @retval 0 -> Success
1371 * @retval < 0 -> Fail
1373 int8_t bmi2_perform_gyro_foc(struct bmi2_dev
*dev
);
1377 * \defgroup bmi2ApiCRT CRT
1378 * @brief CRT operations of the sensor
1382 * \ingroup bmi2ApiCRT
1383 * \page bmi2_api_bmi2_do_crt bmi2_do_crt
1385 * int8_t bmi2_do_crt(struct bmi2_dev *dev);
1387 * @details API performs Component Re-Trim calibration (CRT).
1390 * @param[in] dev : Structure instance of bmi2_dev.
1392 * @return Result of API execution status
1393 * @retval 0 -> Success
1394 * @retval < 0 -> Fail
1396 * @note CRT calibration takes approximately 500ms & maximum time out configured as 2 seconds
1398 int8_t bmi2_do_crt(struct bmi2_dev
*dev
);
1402 * \defgroup bmi2ApiCRTSt CRT and self test
1403 * @brief Enable / Abort CRT and self test operations of gyroscope
1407 * \ingroup bmi2ApiCRTSt
1408 * \page bmi2_api_bmi2_set_gyro_self_test_crt bmi2_set_gyro_self_test_crt
1410 * int8_t bmi2_set_gyro_self_test_crt
1412 * @details This api is used to enable the gyro self-test and crt.
1413 * *gyro_self_test_crt -> 0 then gyro self test enable
1414 * *gyro_self_test_crt -> 1 then CRT enable
1416 * @param[in] gyro_self_test_crt : enable the gyro self test or crt.
1417 * @param[in] dev : Structure instance of bmi2_dev.
1419 * @return Result of API execution status
1420 * @retval 0 -> Success
1421 * @retval < 0 -> Fail
1423 int8_t bmi2_set_gyro_self_test_crt(uint8_t *gyro_self_test_crt
, struct bmi2_dev
*dev
);
1426 * \ingroup bmi2ApiCRTSt
1427 * \page bmi2_api_bmi2_abort_crt_gyro_st bmi2_abort_crt_gyro_st
1429 * int8_t bmi2_abort_crt_gyro_st(struct bmi2_dev *dev);
1431 * @details This api is used to abort ongoing crt or gyro self test.
1433 * @param[in] dev : Structure instance of bmi2_dev.
1435 * @return Result of API execution status
1436 * @retval 0 -> Success
1437 * @retval < 0 -> Fail
1439 int8_t bmi2_abort_crt_gyro_st(struct bmi2_dev
*dev
);
1442 * \ingroup bmi2ApiASelftest
1443 * \page bmi2_api_bmi2_do_gyro_st bmi2_do_gyro_st
1445 * int8_t bmi2_do_gyro_st
1447 * @details this api is used to perform gyroscope self test.
1449 * @param[in] dev : Structure instance of bmi2_dev.
1451 * @return Result of API execution status
1452 * @retval 0 -> Success
1453 * @retval < 0 -> Fail
1455 int8_t bmi2_do_gyro_st(struct bmi2_dev
*dev
);
1459 * \defgroup bmi2ApiNVM NVM
1460 * @brief NVM operations of the sensor
1464 * \ingroup bmi2ApiNVM
1465 * \page bmi2_api_bmi2_nvm_prog bmi2_nvm_prog
1467 * int8_t bmi2_nvm_prog
1469 * @details This api is used for programming the non volatile memory(nvm)
1471 * @param[in] dev : Structure instance of bmi2_dev.
1473 * @return Result of API execution status
1474 * @retval 0 -> Success
1475 * @retval < 0 -> Fail
1477 int8_t bmi2_nvm_prog(struct bmi2_dev
*dev
);
1480 * @brief This API extracts the input feature configuration
1481 * details like page and start address from the look-up table.
1483 * @param[out] feat_config : Structure that stores feature configurations.
1484 * @param[in] type : Type of feature or sensor.
1485 * @param[in] dev : Structure instance of bmi2_dev.
1487 * @return Returns the feature found flag.
1489 * @retval BMI2_FALSE : Feature not found
1490 * BMI2_TRUE : Feature found
1492 uint8_t bmi2_extract_input_feat_config(struct bmi2_feature_config
*feat_config
, uint8_t type
,
1493 const struct bmi2_dev
*dev
);
1496 * @brief This API is used to get the feature configuration from the
1499 * @param[in] sw_page : Switches to the desired page.
1500 * @param[out] feat_config : Pointer to the feature configuration.
1501 * @param[in] dev : Structure instance of bmi2_dev.
1503 * @return Result of API execution status
1504 * @retval 0 -> Success
1505 * @retval < 0 -> Fail
1507 int8_t bmi2_get_feat_config(uint8_t sw_page
, uint8_t *feat_config
, struct bmi2_dev
*dev
);
1511 #endif /* End of CPP guard */
1513 #endif /* BMI2_H_ */