Merge pull request #11538 from klutvott123/osd-visual-beeper
[betaflight.git] / lib / main / BoschSensortec / BMI270-Sensor-API / bmi270_maximum_fifo.h
blobe912a96a632e3e0d952a184f0efe947014978930
1 /**
2 * Copyright (c) 2020 Bosch Sensortec GmbH. All rights reserved.
4 * BSD-3-Clause
6 * Redistribution and use in source and binary forms, with or without
7 * modification, are permitted provided that the following conditions are met:
9 * 1. Redistributions of source code must retain the above copyright
10 * notice, this list of conditions and the following disclaimer.
12 * 2. Redistributions in binary form must reproduce the above copyright
13 * notice, this list of conditions and the following disclaimer in the
14 * documentation and/or other materials provided with the distribution.
16 * 3. Neither the name of the copyright holder nor the names of its
17 * contributors may be used to endorse or promote products derived from
18 * this software without specific prior written permission.
20 * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
21 * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
22 * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
23 * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
24 * COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
25 * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES
26 * (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR
27 * SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION)
28 * HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT,
29 * STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING
30 * IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
31 * POSSIBILITY OF SUCH DAMAGE.
33 * @file bmi270_maximum_fifo.h
34 * @date 2020-11-04
35 * @version v2.63.1
39 /**
40 * \ingroup bmi2xy
41 * \defgroup bmi270_maximum_fifo BMI270_MAXIMUM_FIFO
42 * @brief Sensor driver for BMI270_MAXIMUM_FIFO sensor
45 #ifndef BMI270_MAXIMUM_FIFO_H_
46 #define BMI270_MAXIMUM_FIFO_H_
48 /*! CPP guard */
49 #ifdef __cplusplus
50 extern "C" {
51 #endif
53 /***************************************************************************/
55 /*! Header files
56 ****************************************************************************/
57 #include "bmi2.h"
59 /***************************************************************************/
61 /*! Macro definitions
62 ****************************************************************************/
64 /*! @name BMI270 Chip identifier */
65 #define BMI270_MAXIMUM_FIFO_CHIP_ID UINT8_C(0x24)
67 /*! @name Defines maximum number of pages */
68 #define BMI270_MAXIMUM_FIFO_MAX_PAGE_NUM UINT8_C(0)
70 /*! @name Defines maximum number of feature input configurations */
71 #define BMI270_MAXIMUM_FIFO_MAX_FEAT_IN UINT8_C(0)
73 /*! @name Defines maximum number of feature outputs */
74 #define BMI270_MAXIMUM_FIFO_MAX_FEAT_OUT UINT8_C(0)
76 /*! @name Mask definitions for feature interrupt status bits */
78 /***************************************************************************/
80 /*! BMI270 User Interface function prototypes
81 ****************************************************************************/
83 /**
84 * \ingroup bmi270_maximum_fifo
85 * \defgroup bmi270_maximum_fifoApiInit Initialization
86 * @brief Initialize the sensor and device structure
89 /*!
90 * \ingroup bmi270_maximum_fifoApiInit
91 * \page bmi270_maximum_fifo_api_bmi270_maximum_fifo_init bmi270_maximum_fifo_init
92 * \code
93 * int8_t bmi270_maximum_fifo_init(struct bmi2_dev *dev);
94 * \endcode
95 * @details This API:
96 * 1) updates the device structure with address of the configuration file.
97 * 2) Initializes BMI270 sensor.
98 * 3) Writes the configuration file.
99 * 4) Updates the feature offset parameters in the device structure.
100 * 5) Updates the maximum number of pages, in the device structure.
102 * @param[in, out] dev : Structure instance of bmi2_dev.
104 * @return Result of API execution status
105 * @retval 0 -> Success
106 * @retval < 0 -> Fail
108 int8_t bmi270_maximum_fifo_init(struct bmi2_dev *dev);
110 /******************************************************************************/
111 /*! @name C++ Guard Macros */
112 /******************************************************************************/
113 #ifdef __cplusplus
115 #endif /* End of CPP guard */
117 #endif /* BMI270_MAXIMUM_FIFO_H_ */