├── .gitignore
├── .travis.yml
├── LICENSE
├── Makefile
├── README.md
├── bno055.c
├── bno055.h
├── bno055_stm32.h
└── test.c
/.gitignore:
--------------------------------------------------------------------------------
1 | # Prerequisites
2 | *.d
3 |
4 | # Object files
5 | *.o
6 | *.ko
7 | *.obj
8 | *.elf
9 |
10 | # Linker output
11 | *.ilk
12 | *.map
13 | *.exp
14 |
15 | # Precompiled Headers
16 | *.gch
17 | *.pch
18 |
19 | # Libraries
20 | *.lib
21 | *.a
22 | *.la
23 | *.lo
24 |
25 | # Shared objects (inc. Windows DLLs)
26 | *.dll
27 | *.so
28 | *.so.*
29 | *.dylib
30 |
31 | # Executables
32 | *.exe
33 | *.out
34 | *.app
35 | *.i*86
36 | *.x86_64
37 | *.hex
38 |
39 | # Debug files
40 | *.dSYM/
41 | *.su
42 | *.idb
43 | *.pdb
44 |
45 | # Kernel Module Compile Results
46 | *.mod*
47 | *.cmd
48 | .tmp_versions/
49 | modules.order
50 | Module.symvers
51 | Mkfile.old
52 | dkms.conf
53 |
54 | .vscode
55 | /out/*.*
56 |
--------------------------------------------------------------------------------
/.travis.yml:
--------------------------------------------------------------------------------
1 | compiler:
2 | - gcc
3 | sudo: true
4 | script:
5 | - mkdir -p out
6 | - make build
7 | - sudo pip install cpplint
8 | - make lint
9 |
--------------------------------------------------------------------------------
/LICENSE:
--------------------------------------------------------------------------------
1 | MIT License
2 |
3 | Copyright (c) 2019 Ivy Knob
4 |
5 | Permission is hereby granted, free of charge, to any person obtaining a copy
6 | of this software and associated documentation files (the "Software"), to deal
7 | in the Software without restriction, including without limitation the rights
8 | to use, copy, modify, merge, publish, distribute, sublicense, and/or sell
9 | copies of the Software, and to permit persons to whom the Software is
10 | furnished to do so, subject to the following conditions:
11 |
12 | The above copyright notice and this permission notice shall be included in all
13 | copies or substantial portions of the Software.
14 |
15 | THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
16 | IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
17 | FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
18 | AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
19 | LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM,
20 | OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE
21 | SOFTWARE.
22 |
--------------------------------------------------------------------------------
/Makefile:
--------------------------------------------------------------------------------
1 | .PHONY: build test
2 | build:
3 | gcc *.c -o out/bno055.o
4 | test:
5 | build
6 | lint:
7 | cpplint --filter=-legal/copyright,-build/include_subdir `ls *.c` `ls *.h`
8 |
--------------------------------------------------------------------------------
/README.md:
--------------------------------------------------------------------------------
1 | # BNO055 STM32 library [](https://travis-ci.org/ivyknob/bno055_stm32) [](https://codeclimate.com/github/ivyknob/bno055_stm32/maintainability)
2 |
3 |
4 | ## WORK IN PROGRESS
5 |
6 | There are no libraries to use BNO055 with STM32.
7 | We created one to use with STM32 HAL I2C.
8 |
9 | It does support FreeRTOS, see `bno055.h`. Uncomment `#define FREERTOS_ENABLED` to enable FreeRTOS.
10 |
11 | ## Usage
12 |
13 | Use CubeMX to init i2c in fast mode.
14 |
15 | Copy `bno055.c`, `bno055.h` and `bno055_stm32.h` to your project.
16 |
17 | Set BNO055 i2c address in `bno055.h`
18 |
19 | ```c
20 | #define BNO055_I2C_ADDR BNO055_I2C_ADDR_LO // For 0x28
21 | #define BNO055_I2C_ADDR BNO055_I2C_ADDR_HI // For 0x29
22 | ```
23 |
24 | Include `bno055_stm32.h`.
25 | Pass i2c handler to bno055_assignI2C function and set work mode:
26 |
27 | ```c
28 | bno055_assignI2C(&hi2c1);
29 | bno055_setup();
30 | bno055_setOperationModeNDOF();
31 | ```
32 |
33 | Then use bno055_getVectorEuler to receive euler angle data:
34 |
35 | ```c
36 | bno055_vector_t v = bno055_getVectorEuler();
37 | printf("Heading: %.2f Roll: %.2f Pitch: %.2f\r\n", v.x, v.y, v.z);
38 | ```
39 |
40 | Or use bno055_getVectorQuaternion to receive quaternion data:
41 |
42 | ```c
43 | bno055_vector_t v = bno055_getVectorQuaternion();
44 | printf("W: %.2f X: %.2f Y: %.2f Z: %.2f\r\n", v.w, v.x, v.y, v.z);
45 | ```
46 |
47 | To remap axis, use bno055_setAxisMap in config mode (refer to datasheet page 24):
48 |
49 | ```c
50 | bno055_axis_map_t axis = {
51 | .x = BNO055_AXIS_X,
52 | .x_sign = BNO055_AXIS_SIGN_POSITIVE,
53 | .y = BNO055_AXIS_Y,
54 | .y_sign = BNO055_AXIS_SIGN_POSITIVE,
55 | .z = BNO055_AXIS_Z,
56 | .z_sign = BNO055_AXIS_SIGN_POSITIVE
57 | };
58 | bno055_setAxisMap(axis);
59 | ```
60 |
61 | ### Full example
62 |
63 | ```c
64 | # main.c
65 |
66 | /* USER CODE BEGIN Header */
67 | /**
68 | ******************************************************************************
69 | * @file : main.c
70 | * @brief : Main program body
71 | ******************************************************************************
72 | * @attention
73 | *
74 | *
© Copyright (c) 2019 STMicroelectronics.
75 | * All rights reserved.
76 | *
77 | * This software component is licensed by ST under BSD 3-Clause license,
78 | * the "License"; You may not use this file except in compliance with the
79 | * License. You may obtain a copy of the License at:
80 | * opensource.org/licenses/BSD-3-Clause
81 | *
82 | ******************************************************************************
83 | */
84 | /* USER CODE END Header */
85 |
86 | /* Includes ------------------------------------------------------------------*/
87 | #include "main.h"
88 | #include "i2c.h"
89 | #include "gpio.h"
90 |
91 | /* Private includes ----------------------------------------------------------*/
92 | /* USER CODE BEGIN Includes */
93 | #include "bno055_stm32.h"
94 | /* USER CODE END Includes */
95 |
96 | /* Private typedef -----------------------------------------------------------*/
97 | /* USER CODE BEGIN PTD */
98 |
99 | /* USER CODE END PTD */
100 |
101 | /* Private define ------------------------------------------------------------*/
102 | /* USER CODE BEGIN PD */
103 |
104 | /* USER CODE END PD */
105 |
106 | /* Private macro -------------------------------------------------------------*/
107 | /* USER CODE BEGIN PM */
108 |
109 | /* USER CODE END PM */
110 |
111 | /* Private variables ---------------------------------------------------------*/
112 |
113 | /* USER CODE BEGIN PV */
114 |
115 | /* USER CODE END PV */
116 |
117 | /* Private function prototypes -----------------------------------------------*/
118 | void SystemClock_Config(void);
119 | /* USER CODE BEGIN PFP */
120 |
121 | /* USER CODE END PFP */
122 |
123 | /* Private user code ---------------------------------------------------------*/
124 | /* USER CODE BEGIN 0 */
125 |
126 | /* USER CODE END 0 */
127 |
128 | /**
129 | * @brief The application entry point.
130 | * @retval int
131 | */
132 | int main(void)
133 | {
134 | /* USER CODE BEGIN 1 */
135 |
136 | /* USER CODE END 1 */
137 |
138 | /* MCU Configuration--------------------------------------------------------*/
139 |
140 | /* Reset of all peripherals, Initializes the Flash interface and the Systick. */
141 | HAL_Init();
142 |
143 | /* USER CODE BEGIN Init */
144 |
145 | /* USER CODE END Init */
146 |
147 | /* Configure the system clock */
148 | SystemClock_Config();
149 |
150 | /* USER CODE BEGIN SysInit */
151 |
152 | /* USER CODE END SysInit */
153 |
154 | /* Initialize all configured peripherals */
155 | MX_GPIO_Init();
156 | MX_I2C1_Init();
157 | /* USER CODE BEGIN 2 */
158 | bno055_assignI2C(&hi2c1);
159 | bno055_setup();
160 | bno055_setOperationModeNDOF();
161 | /* USER CODE END 2 */
162 |
163 | /* Infinite loop */
164 | /* USER CODE BEGIN WHILE */
165 | while (1)
166 | {
167 | /* USER CODE END WHILE */
168 | bno055_vector_t v = bno055_getVectorEuler();
169 | printf("Heading: %.2f Roll: %.2f Pitch: %.2f\r\n", v.x, v.y, v.z);
170 | v = bno055_getVectorQuaternion();
171 | printf("W: %.2f X: %.2f Y: %.2f Z: %.2f\r\n", v.w, v.x, v.y, v.z);
172 | HAL_Delay(1000);
173 | /* USER CODE BEGIN 3 */
174 | }
175 | /* USER CODE END 3 */
176 | }
177 |
178 | /**
179 | * @brief System Clock Configuration
180 | * @retval None
181 | */
182 | void SystemClock_Config(void)
183 | {
184 | RCC_OscInitTypeDef RCC_OscInitStruct = {0};
185 | RCC_ClkInitTypeDef RCC_ClkInitStruct = {0};
186 |
187 | /** Initializes the CPU, AHB and APB busses clocks
188 | */
189 | RCC_OscInitStruct.OscillatorType = RCC_OSCILLATORTYPE_HSI;
190 | RCC_OscInitStruct.HSIState = RCC_HSI_ON;
191 | RCC_OscInitStruct.HSICalibrationValue = RCC_HSICALIBRATION_DEFAULT;
192 | RCC_OscInitStruct.PLL.PLLState = RCC_PLL_NONE;
193 | if (HAL_RCC_OscConfig(&RCC_OscInitStruct) != HAL_OK)
194 | {
195 | Error_Handler();
196 | }
197 | /** Initializes the CPU, AHB and APB busses clocks
198 | */
199 | RCC_ClkInitStruct.ClockType = RCC_CLOCKTYPE_HCLK|RCC_CLOCKTYPE_SYSCLK
200 | |RCC_CLOCKTYPE_PCLK1|RCC_CLOCKTYPE_PCLK2;
201 | RCC_ClkInitStruct.SYSCLKSource = RCC_SYSCLKSOURCE_HSI;
202 | RCC_ClkInitStruct.AHBCLKDivider = RCC_SYSCLK_DIV1;
203 | RCC_ClkInitStruct.APB1CLKDivider = RCC_HCLK_DIV1;
204 | RCC_ClkInitStruct.APB2CLKDivider = RCC_HCLK_DIV1;
205 |
206 | if (HAL_RCC_ClockConfig(&RCC_ClkInitStruct, FLASH_LATENCY_0) != HAL_OK)
207 | {
208 | Error_Handler();
209 | }
210 | }
211 |
212 | /* USER CODE BEGIN 4 */
213 |
214 | /* USER CODE END 4 */
215 |
216 | /**
217 | * @brief This function is executed in case of error occurrence.
218 | * @retval None
219 | */
220 | void Error_Handler(void)
221 | {
222 | /* USER CODE BEGIN Error_Handler_Debug */
223 | /* User can add his own implementation to report the HAL error return state */
224 |
225 | /* USER CODE END Error_Handler_Debug */
226 | }
227 |
228 | #ifdef USE_FULL_ASSERT
229 | /**
230 | * @brief Reports the name of the source file and the source line number
231 | * where the assert_param error has occurred.
232 | * @param file: pointer to the source file name
233 | * @param line: assert_param error line source number
234 | * @retval None
235 | */
236 | void assert_failed(uint8_t *file, uint32_t line)
237 | {
238 | /* USER CODE BEGIN 6 */
239 | /* User can add his own implementation to report the file name and line number,
240 | tex: printf("Wrong parameters value: file %s on line %d\r\n", file, line) */
241 | /* USER CODE END 6 */
242 | }
243 | #endif /* USE_FULL_ASSERT */
244 |
245 | /************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/
246 |
247 | ```
248 |
249 | ### Output
250 |
251 | ```
252 | Heading: 292.81 Roll: 50.00 Pitch: 175.62
253 | W: 0.35 X: 0.45 Y: -0.78 Z: 0.23
254 | Heading: 292.81 Roll: 50.00 Pitch: 175.62
255 | W: 0.35 X: 0.45 Y: -0.78 Z: 0.23
256 | ```
257 |
--------------------------------------------------------------------------------
/bno055.c:
--------------------------------------------------------------------------------
1 | #include "bno055.h"
2 | #include
3 |
4 | uint16_t accelScale = 100;
5 | uint16_t tempScale = 1;
6 | uint16_t angularRateScale = 16;
7 | uint16_t eulerScale = 16;
8 | uint16_t magScale = 16;
9 | uint16_t quaScale = (1<<14); // 2^14
10 |
11 | void bno055_setPage(uint8_t page) { bno055_writeData(BNO055_PAGE_ID, page); }
12 |
13 | bno055_opmode_t bno055_getOperationMode() {
14 | bno055_opmode_t mode;
15 | bno055_readData(BNO055_OPR_MODE, &mode, 1);
16 | return mode;
17 | }
18 |
19 | void bno055_setOperationMode(bno055_opmode_t mode) {
20 | bno055_writeData(BNO055_OPR_MODE, mode);
21 | if (mode == BNO055_OPERATION_MODE_CONFIG) {
22 | bno055_delay(19);
23 | } else {
24 | bno055_delay(7);
25 | }
26 | }
27 |
28 | void bno055_setOperationModeConfig() {
29 | bno055_setOperationMode(BNO055_OPERATION_MODE_CONFIG);
30 | }
31 |
32 | void bno055_setOperationModeNDOF() {
33 | bno055_setOperationMode(BNO055_OPERATION_MODE_NDOF);
34 | }
35 |
36 | void bno055_setExternalCrystalUse(bool state) {
37 | bno055_setPage(0);
38 | uint8_t tmp = 0;
39 | bno055_readData(BNO055_SYS_TRIGGER, &tmp, 1);
40 | tmp |= (state == true) ? 0x80 : 0x0;
41 | bno055_writeData(BNO055_SYS_TRIGGER, tmp);
42 | bno055_delay(700);
43 | }
44 |
45 | void bno055_enableExternalCrystal() { bno055_setExternalCrystalUse(true); }
46 | void bno055_disableExternalCrystal() { bno055_setExternalCrystalUse(false); }
47 |
48 | void bno055_reset() {
49 | bno055_writeData(BNO055_SYS_TRIGGER, 0x20);
50 | bno055_delay(700);
51 | }
52 |
53 | int8_t bno055_getTemp() {
54 | bno055_setPage(0);
55 | uint8_t t;
56 | bno055_readData(BNO055_TEMP, &t, 1);
57 | return t;
58 | }
59 |
60 | void bno055_setup() {
61 | bno055_reset();
62 |
63 | uint8_t id = 0;
64 | bno055_readData(BNO055_CHIP_ID, &id, 1);
65 | if (id != BNO055_ID) {
66 | printf("Can't find BNO055, id: 0x%02x. Please check your wiring.\r\n", id);
67 | }
68 | bno055_setPage(0);
69 | bno055_writeData(BNO055_SYS_TRIGGER, 0x0);
70 |
71 | // Select BNO055 config mode
72 | bno055_setOperationModeConfig();
73 | bno055_delay(10);
74 | }
75 |
76 | int16_t bno055_getSWRevision() {
77 | bno055_setPage(0);
78 | uint8_t buffer[2];
79 | bno055_readData(BNO055_SW_REV_ID_LSB, buffer, 2);
80 | return (int16_t)((buffer[1] << 8) | buffer[0]);
81 | }
82 |
83 | uint8_t bno055_getBootloaderRevision() {
84 | bno055_setPage(0);
85 | uint8_t tmp;
86 | bno055_readData(BNO055_BL_REV_ID, &tmp, 1);
87 | return tmp;
88 | }
89 |
90 | uint8_t bno055_getSystemStatus() {
91 | bno055_setPage(0);
92 | uint8_t tmp;
93 | bno055_readData(BNO055_SYS_STATUS, &tmp, 1);
94 | return tmp;
95 | }
96 |
97 | bno055_self_test_result_t bno055_getSelfTestResult() {
98 | bno055_setPage(0);
99 | uint8_t tmp;
100 | bno055_self_test_result_t res = {
101 | .mcuState = 0, .gyrState = 0, .magState = 0, .accState = 0};
102 | bno055_readData(BNO055_ST_RESULT, &tmp, 1);
103 | res.mcuState = (tmp >> 3) & 0x01;
104 | res.gyrState = (tmp >> 2) & 0x01;
105 | res.magState = (tmp >> 1) & 0x01;
106 | res.accState = (tmp >> 0) & 0x01;
107 | return res;
108 | }
109 |
110 | uint8_t bno055_getSystemError() {
111 | bno055_setPage(0);
112 | uint8_t tmp;
113 | bno055_readData(BNO055_SYS_ERR, &tmp, 1);
114 | return tmp;
115 | }
116 |
117 | bno055_calibration_state_t bno055_getCalibrationState() {
118 | bno055_setPage(0);
119 | bno055_calibration_state_t cal = {.sys = 0, .gyro = 0, .mag = 0, .accel = 0};
120 | uint8_t calState = 0;
121 | bno055_readData(BNO055_CALIB_STAT, &calState, 1);
122 | cal.sys = (calState >> 6) & 0x03;
123 | cal.gyro = (calState >> 4) & 0x03;
124 | cal.accel = (calState >> 2) & 0x03;
125 | cal.mag = calState & 0x03;
126 | return cal;
127 | }
128 |
129 |
130 | bno055_calibration_data_t bno055_getCalibrationData() {
131 | bno055_calibration_data_t calData;
132 | uint8_t buffer[22];
133 | bno055_opmode_t operationMode = bno055_getOperationMode();
134 | bno055_setOperationModeConfig();
135 | bno055_setPage(0);
136 |
137 | bno055_readData(BNO055_ACC_OFFSET_X_LSB, buffer, 22);
138 |
139 | // Assumes little endian processor
140 | memcpy(&calData.offset.accel, buffer, 6);
141 | memcpy(&calData.offset.mag, buffer + 6, 6);
142 | memcpy(&calData.offset.gyro, buffer + 12, 6);
143 | memcpy(&calData.radius.accel, buffer + 18, 2);
144 | memcpy(&calData.radius.mag, buffer + 20, 2);
145 |
146 | bno055_setOperationMode(operationMode);
147 |
148 | return calData;
149 | }
150 |
151 | void bno055_setCalibrationData(bno055_calibration_data_t calData) {
152 | uint8_t buffer[22];
153 | bno055_opmode_t operationMode = bno055_getOperationMode();
154 | bno055_setOperationModeConfig();
155 | bno055_setPage(0);
156 |
157 | // Assumes litle endian processor
158 | memcpy(buffer, &calData.offset.accel, 6);
159 | memcpy(buffer + 6, &calData.offset.mag, 6);
160 | memcpy(buffer + 12, &calData.offset.gyro, 6);
161 | memcpy(buffer + 18, &calData.radius.accel, 2);
162 | memcpy(buffer + 20, &calData.radius.mag, 2);
163 |
164 | for (uint8_t i=0; i < 22; i++) {
165 | // TODO(oliv4945): create multibytes write
166 | bno055_writeData(BNO055_ACC_OFFSET_X_LSB+i, buffer[i]);
167 | }
168 |
169 | bno055_setOperationMode(operationMode);
170 | }
171 |
172 | bno055_vector_t bno055_getVector(uint8_t vec) {
173 | bno055_setPage(0);
174 | uint8_t buffer[8]; // Quaternion need 8 bytes
175 |
176 | if (vec == BNO055_VECTOR_QUATERNION)
177 | bno055_readData(vec, buffer, 8);
178 | else
179 | bno055_readData(vec, buffer, 6);
180 |
181 | double scale = 1;
182 |
183 | if (vec == BNO055_VECTOR_MAGNETOMETER) {
184 | scale = magScale;
185 | } else if (vec == BNO055_VECTOR_ACCELEROMETER ||
186 | vec == BNO055_VECTOR_LINEARACCEL || vec == BNO055_VECTOR_GRAVITY) {
187 | scale = accelScale;
188 | } else if (vec == BNO055_VECTOR_GYROSCOPE) {
189 | scale = angularRateScale;
190 | } else if (vec == BNO055_VECTOR_EULER) {
191 | scale = eulerScale;
192 | } else if (vec == BNO055_VECTOR_QUATERNION) {
193 | scale = quaScale;
194 | }
195 |
196 | bno055_vector_t xyz = {.w = 0, .x = 0, .y = 0, .z = 0};
197 | if (vec == BNO055_VECTOR_QUATERNION) {
198 | xyz.w = (int16_t)((buffer[1] << 8) | buffer[0]) / scale;
199 | xyz.x = (int16_t)((buffer[3] << 8) | buffer[2]) / scale;
200 | xyz.y = (int16_t)((buffer[5] << 8) | buffer[4]) / scale;
201 | xyz.z = (int16_t)((buffer[7] << 8) | buffer[6]) / scale;
202 | } else {
203 | xyz.x = (int16_t)((buffer[1] << 8) | buffer[0]) / scale;
204 | xyz.y = (int16_t)((buffer[3] << 8) | buffer[2]) / scale;
205 | xyz.z = (int16_t)((buffer[5] << 8) | buffer[4]) / scale;
206 | }
207 |
208 | return xyz;
209 | }
210 |
211 | bno055_vector_t bno055_getVectorAccelerometer() {
212 | return bno055_getVector(BNO055_VECTOR_ACCELEROMETER);
213 | }
214 | bno055_vector_t bno055_getVectorMagnetometer() {
215 | return bno055_getVector(BNO055_VECTOR_MAGNETOMETER);
216 | }
217 | bno055_vector_t bno055_getVectorGyroscope() {
218 | return bno055_getVector(BNO055_VECTOR_GYROSCOPE);
219 | }
220 | bno055_vector_t bno055_getVectorEuler() {
221 | return bno055_getVector(BNO055_VECTOR_EULER);
222 | }
223 | bno055_vector_t bno055_getVectorLinearAccel() {
224 | return bno055_getVector(BNO055_VECTOR_LINEARACCEL);
225 | }
226 | bno055_vector_t bno055_getVectorGravity() {
227 | return bno055_getVector(BNO055_VECTOR_GRAVITY);
228 | }
229 | bno055_vector_t bno055_getVectorQuaternion() {
230 | return bno055_getVector(BNO055_VECTOR_QUATERNION);
231 | }
232 |
233 | void bno055_setAxisMap(bno055_axis_map_t axis) {
234 | uint8_t axisRemap = (axis.z << 4) | (axis.y << 2) | (axis.x);
235 | uint8_t axisMapSign = (axis.x_sign << 2) | (axis.y_sign << 1) | (axis.z_sign);
236 | bno055_writeData(BNO055_AXIS_MAP_CONFIG, axisRemap);
237 | bno055_writeData(BNO055_AXIS_MAP_SIGN, axisMapSign);
238 | }
239 |
--------------------------------------------------------------------------------
/bno055.h:
--------------------------------------------------------------------------------
1 | #ifndef BNO055_H_
2 | #define BNO055_H_
3 |
4 | #ifdef __cplusplus
5 | extern "C" {
6 | #endif
7 | // #define FREERTOS_ENABLED true
8 |
9 | #include
10 | #include
11 | #include
12 |
13 | #define START_BYTE 0xAA
14 | #define RESPONSE_BYTE 0xBB
15 | #define ERROR_BYTE 0xEE
16 |
17 | #define BNO055_I2C_ADDR_HI 0x29
18 | #define BNO055_I2C_ADDR_LO 0x28
19 | #define BNO055_I2C_ADDR BNO055_I2C_ADDR_LO
20 |
21 | #define BNO055_READ_TIMEOUT 100
22 | #define BNO055_WRITE_TIMEOUT 10
23 |
24 | #define ERROR_WRITE_SUCCESS 0x01 // Everything working as expected
25 | #define ERROR_WRITE_FAIL \
26 | 0x03 // Check connection, protocol settings and operation more of BNO055
27 | #define ERROR_REGMAP_INV_ADDR 0x04 // Invalid register address
28 | #define ERROR_REGMAP_WRITE_DIS 0x05 // Register is read-only
29 | #define ERROR_WRONG_START_BYTE 0x06 // Check if the first byte
30 | #define ERROR_BUS_OVERRUN_ERR \
31 | 0x07 // Resend the command, BNO055 was not able to clear the receive buffer
32 | #define ERROR_MAX_LEN_ERR \
33 | 0x08 // Split the command, max fire size can be up to 128 bytes
34 | #define ERROR_MIN_LEN_ERR 0x09 // Min length of data is less than 1
35 | #define ERROR_RECV_CHAR_TIMEOUT \
36 | 0x0A // Decrease the waiting time between sending of two bytes of one frame
37 |
38 | #define REG_WRITE 0x00
39 | #define REG_READ 0x01
40 |
41 | // Page 0
42 | #define BNO055_ID (0xA0)
43 | #define BNO055_CHIP_ID 0x00 // value: 0xA0
44 | #define BNO055_ACC_ID 0x01 // value: 0xFB
45 | #define BNO055_MAG_ID 0x02 // value: 0x32
46 | #define BNO055_GYRO_ID 0x03 // value: 0x0F
47 | #define BNO055_SW_REV_ID_LSB 0x04 // value: 0x08
48 | #define BNO055_SW_REV_ID_MSB 0x05 // value: 0x03
49 | #define BNO055_BL_REV_ID 0x06 // N/A
50 | #define BNO055_PAGE_ID 0x07
51 | #define BNO055_ACC_DATA_X_LSB 0x08
52 | #define BNO055_ACC_DATA_X_MSB 0x09
53 | #define BNO055_ACC_DATA_Y_LSB 0x0A
54 | #define BNO055_ACC_DATA_Y_MSB 0x0B
55 | #define BNO055_ACC_DATA_Z_LSB 0x0C
56 | #define BNO055_ACC_DATA_Z_MSB 0x0D
57 | #define BNO055_MAG_DATA_X_LSB 0x0E
58 | #define BNO055_MAG_DATA_X_MSB 0x0F
59 | #define BNO055_MAG_DATA_Y_LSB 0x10
60 | #define BNO055_MAG_DATA_Y_MSB 0x11
61 | #define BNO055_MAG_DATA_Z_LSB 0x12
62 | #define BNO055_MAG_DATA_Z_MSB 0x13
63 | #define BNO055_GYR_DATA_X_LSB 0x14
64 | #define BNO055_GYR_DATA_X_MSB 0x15
65 | #define BNO055_GYR_DATA_Y_LSB 0x16
66 | #define BNO055_GYR_DATA_Y_MSB 0x17
67 | #define BNO055_GYR_DATA_Z_LSB 0x18
68 | #define BNO055_GYR_DATA_Z_MSB 0x19
69 | #define BNO055_EUL_HEADING_LSB 0x1A
70 | #define BNO055_EUL_HEADING_MSB 0x1B
71 | #define BNO055_EUL_ROLL_LSB 0x1C
72 | #define BNO055_EUL_ROLL_MSB 0x1D
73 | #define BNO055_EUL_PITCH_LSB 0x1E
74 | #define BNO055_EUL_PITCH_MSB 0x1F
75 | #define BNO055_QUA_DATA_W_LSB 0x20
76 | #define BNO055_QUA_DATA_W_MSB 0x21
77 | #define BNO055_QUA_DATA_X_LSB 0x22
78 | #define BNO055_QUA_DATA_X_MSB 0x23
79 | #define BNO055_QUA_DATA_Y_LSB 0x24
80 | #define BNO055_QUA_DATA_Y_MSB 0x25
81 | #define BNO055_QUA_DATA_Z_LSB 0x26
82 | #define BNO055_QUA_DATA_Z_MSB 0x27
83 | #define BNO055_LIA_DATA_X_LSB 0x28
84 | #define BNO055_LIA_DATA_X_MSB 0x29
85 | #define BNO055_LIA_DATA_Y_LSB 0x2A
86 | #define BNO055_LIA_DATA_Y_MSB 0x2B
87 | #define BNO055_LIA_DATA_Z_LSB 0x2C
88 | #define BNO055_LIA_DATA_Z_MSB 0x2D
89 | #define BNO055_GRV_DATA_X_LSB 0x2E
90 | #define BNO055_GRV_DATA_X_MSB 0x2F
91 | #define BNO055_GRV_DATA_Y_LSB 0x30
92 | #define BNO055_GRV_DATA_Y_MSB 0x31
93 | #define BNO055_GRV_DATA_Z_LSB 0x32
94 | #define BNO055_GRV_DATA_Z_MSB 0x33
95 | #define BNO055_TEMP 0x34
96 | #define BNO055_CALIB_STAT 0x35
97 | #define BNO055_ST_RESULT 0x36
98 | #define BNO055_INT_STATUS 0x37
99 | #define BNO055_SYS_CLK_STATUS 0x38
100 | #define BNO055_SYS_STATUS 0x39
101 | #define BNO055_SYS_ERR 0x3A
102 | #define BNO055_UNIT_SEL 0x3B
103 | #define BNO055_OPR_MODE 0x3D
104 | #define BNO055_PWR_MODE 0x3E
105 | #define BNO055_SYS_TRIGGER 0x3F
106 | #define BNO055_TEMP_SOURCE 0x40
107 | #define BNO055_AXIS_MAP_CONFIG 0x41
108 | #define BNO055_AXIS_MAP_SIGN 0x42
109 | #define BNO055_ACC_OFFSET_X_LSB 0x55
110 | #define BNO055_ACC_OFFSET_X_MSB 0x56
111 | #define BNO055_ACC_OFFSET_Y_LSB 0x57
112 | #define BNO055_ACC_OFFSET_Y_MSB 0x58
113 | #define BNO055_ACC_OFFSET_Z_LSB 0x59
114 | #define BNO055_ACC_OFFSET_Z_MSB 0x5A
115 | #define BNO055_MAG_OFFSET_X_LSB 0x5B
116 | #define BNO055_MAG_OFFSET_X_MSB 0x5C
117 | #define BNO055_MAG_OFFSET_Y_LSB 0x5D
118 | #define BNO055_MAG_OFFSET_Y_MSB 0x5E
119 | #define BNO055_MAG_OFFSET_Z_LSB 0x5F
120 | #define BNO055_MAG_OFFSET_Z_MSB 0x60
121 | #define BNO055_GYR_OFFSET_X_LSB 0x61
122 | #define BNO055_GYR_OFFSET_X_MSB 0x62
123 | #define BNO055_GYR_OFFSET_Y_LSB 0x63
124 | #define BNO055_GYR_OFFSET_Y_MSB 0x64
125 | #define BNO055_GYR_OFFSET_Z_LSB 0x65
126 | #define BNO055_GYR_OFFSET_Z_MSB 0x66
127 | #define BNO055_ACC_RADIUS_LSB 0x67
128 | #define BNO055_ACC_RADIUS_MSB 0x68
129 | #define BNO055_MAG_RADIUS_LSB 0x69
130 | #define BNO055_MAG_RADIUS_MSB 0x6A
131 | //
132 | // BNO055 Page 1
133 | #define BNO055_PAGE_ID 0x07
134 | #define BNO055_ACC_CONFIG 0x08
135 | #define BNO055_MAG_CONFIG 0x09
136 | #define BNO055_GYRO_CONFIG_0 0x0A
137 | #define BNO055_GYRO_CONFIG_1 0x0B
138 | #define BNO055_ACC_SLEEP_CONFIG 0x0C
139 | #define BNO055_GYR_SLEEP_CONFIG 0x0D
140 | #define BNO055_INT_MSK 0x0F
141 | #define BNO055_INT_EN 0x10
142 | #define BNO055_ACC_AM_THRES 0x11
143 | #define BNO055_ACC_INT_SETTINGS 0x12
144 | #define BNO055_ACC_HG_DURATION 0x13
145 | #define BNO055_ACC_HG_THRESH 0x14
146 | #define BNO055_ACC_NM_THRESH 0x15
147 | #define BNO055_ACC_NM_SET 0x16
148 | #define BNO055_GYR_INT_SETTINGS 0x17
149 | #define BNO055_GYR_HR_X_SET 0x18
150 | #define BNO055_GYR_DUR_X 0x19
151 | #define BNO055_GYR_HR_Y_SET 0x1A
152 | #define BNO055_GYR_DUR_Y 0x1B
153 | #define BNO055_GYR_HR_Z_SET 0x1C
154 | #define BNO055_GYR_DUR_Z 0x1D
155 | #define BNO055_GYR_AM_THRESH 0x1E
156 | #define BNO055_GYR_AM_SET 0x1F
157 |
158 | enum bno055_system_status_t {
159 | BNO055_SYSTEM_STATUS_IDLE = 0x00,
160 | BNO055_SYSTEM_STATUS_SYSTEM_ERROR = 0x01,
161 | BNO055_SYSTEM_STATUS_INITIALIZING_PERIPHERALS = 0x02,
162 | BNO055_SYSTEM_STATUS_SYSTEM_INITIALIZATION = 0x03,
163 | BNO055_SYSTEM_STATUS_EXECUTING_SELF_TEST = 0x04,
164 | BNO055_SYSTEM_STATUS_FUSION_ALGO_RUNNING = 0x05,
165 | BNO055_SYSTEM_STATUS_FUSION_ALOG_NOT_RUNNING = 0x06
166 | };
167 |
168 | typedef enum { // BNO-55 operation modes
169 | BNO055_OPERATION_MODE_CONFIG = 0x00,
170 | // Sensor Mode
171 | BNO055_OPERATION_MODE_ACCONLY,
172 | BNO055_OPERATION_MODE_MAGONLY,
173 | BNO055_OPERATION_MODE_GYRONLY,
174 | BNO055_OPERATION_MODE_ACCMAG,
175 | BNO055_OPERATION_MODE_ACCGYRO,
176 | BNO055_OPERATION_MODE_MAGGYRO,
177 | BNO055_OPERATION_MODE_AMG, // 0x07
178 | // Fusion Mode
179 | BNO055_OPERATION_MODE_IMU,
180 | BNO055_OPERATION_MODE_COMPASS,
181 | BNO055_OPERATION_MODE_M4G,
182 | BNO055_OPERATION_MODE_NDOF_FMC_OFF,
183 | BNO055_OPERATION_MODE_NDOF // 0x0C
184 | } bno055_opmode_t;
185 |
186 | typedef struct {
187 | uint8_t mcuState;
188 | uint8_t gyrState;
189 | uint8_t magState;
190 | uint8_t accState;
191 | } bno055_self_test_result_t;
192 |
193 | typedef struct {
194 | uint8_t sys;
195 | uint8_t gyro;
196 | uint8_t mag;
197 | uint8_t accel;
198 | } bno055_calibration_state_t;
199 |
200 | typedef struct {
201 | int16_t x;
202 | int16_t y;
203 | int16_t z;
204 | } bno055_vector_xyz_int16_t;
205 |
206 | typedef struct {
207 | bno055_vector_xyz_int16_t gyro;
208 | bno055_vector_xyz_int16_t mag;
209 | bno055_vector_xyz_int16_t accel;
210 | } bno055_calibration_offset_t;
211 |
212 | typedef struct {
213 | uint16_t mag;
214 | uint16_t accel;
215 | } bno055_calibration_radius_t;
216 |
217 | typedef struct {
218 | bno055_calibration_offset_t offset;
219 | bno055_calibration_radius_t radius;
220 | } bno055_calibration_data_t;
221 |
222 | typedef struct {
223 | double w;
224 | double x;
225 | double y;
226 | double z;
227 | } bno055_vector_t;
228 |
229 | typedef struct {
230 | uint8_t x;
231 | uint8_t x_sign;
232 | uint8_t y;
233 | uint8_t y_sign;
234 | uint8_t z;
235 | uint8_t z_sign;
236 | } bno055_axis_map_t;
237 |
238 | typedef enum {
239 | BNO055_VECTOR_ACCELEROMETER = 0x08, // Default: m/s²
240 | BNO055_VECTOR_MAGNETOMETER = 0x0E, // Default: uT
241 | BNO055_VECTOR_GYROSCOPE = 0x14, // Default: rad/s
242 | BNO055_VECTOR_EULER = 0x1A, // Default: degrees
243 | BNO055_VECTOR_QUATERNION = 0x20, // No units
244 | BNO055_VECTOR_LINEARACCEL = 0x28, // Default: m/s²
245 | BNO055_VECTOR_GRAVITY = 0x2E // Default: m/s²
246 | } bno055_vector_type_t;
247 |
248 | enum bno055_system_error_t {
249 | BNO055_SYSTEM_ERROR_NO_ERROR = 0x00,
250 | BNO055_SYSTEM_ERROR_PERIPHERAL_INITIALIZATION_ERROR = 0x01,
251 | BNO055_SYSTEM_ERROR_SYSTEM_INITIALIZATION_ERROR = 0x02,
252 | BNO055_SYSTEM_ERROR_SELF_TEST_FAILED = 0x03,
253 | BNO055_SYSTEM_ERROR_REG_MAP_VAL_OUT_OF_RANGE = 0x04,
254 | BNO055_SYSTEM_ERROR_REG_MAP_ADDR_OUT_OF_RANGE = 0x05,
255 | BNO055_SYSTEM_ERROR_REG_MAP_WRITE_ERROR = 0x06,
256 | BNO055_SYSTEM_ERROR_LOW_PWR_MODE_NOT_AVAILABLE_FOR_SELECTED_OPR_MODE = 0x07,
257 | BNO055_SYSTEM_ERROR_ACCEL_PWR_MODE_NOT_AVAILABLE = 0x08,
258 | BNO055_SYSTEM_ERROR_FUSION_ALGO_CONF_ERROR = 0x09,
259 | BNO055_SYSTEM_ERROR_SENSOR_CONF_ERROR = 0x0A
260 | };
261 |
262 | enum bno055_axis_map_representation_t {
263 | BNO055_AXIS_X = 0x00,
264 | BNO055_AXIS_Y = 0x01,
265 | BNO055_AXIS_Z = 0x02
266 | };
267 |
268 | enum bno055_axis_map_sign_t {
269 | BNO055_AXIS_SIGN_POSITIVE = 0x00,
270 | BNO055_AXIS_SIGN_NEGATIVE = 0x01
271 | };
272 |
273 | void bno055_writeData(uint8_t reg, uint8_t data);
274 | void bno055_readData(uint8_t reg, uint8_t *data, uint8_t len);
275 | void bno055_delay(int time);
276 |
277 | void bno055_reset();
278 | bno055_opmode_t bno055_getOperationMode();
279 | void bno055_setOperationMode(bno055_opmode_t mode);
280 | void bno055_setOperationModeConfig();
281 | void bno055_setOperationModeNDOF();
282 | void bno055_enableExternalCrystal();
283 | void bno055_disableExternalCrystal();
284 | void bno055_setup();
285 |
286 | int8_t bno055_getTemp();
287 |
288 | uint8_t bno055_getBootloaderRevision();
289 | uint8_t bno055_getSystemStatus();
290 | uint8_t bno055_getSystemError();
291 | int16_t bno055_getSWRevision();
292 |
293 | bno055_self_test_result_t bno055_getSelfTestResult();
294 | bno055_calibration_state_t bno055_getCalibrationState();
295 | bno055_calibration_data_t bno055_getCalibrationData();
296 | void bno055_setCalibrationData(bno055_calibration_data_t calData);
297 | bno055_vector_t bno055_getVectorAccelerometer();
298 | bno055_vector_t bno055_getVectorMagnetometer();
299 | bno055_vector_t bno055_getVectorGyroscope();
300 | bno055_vector_t bno055_getVectorEuler();
301 | bno055_vector_t bno055_getVectorLinearAccel();
302 | bno055_vector_t bno055_getVectorGravity();
303 | bno055_vector_t bno055_getVectorQuaternion();
304 | void bno055_setAxisMap(bno055_axis_map_t axis);
305 |
306 | #ifdef __cplusplus
307 | }
308 | #endif
309 | #endif // BNO055_H_
310 |
--------------------------------------------------------------------------------
/bno055_stm32.h:
--------------------------------------------------------------------------------
1 | #ifndef BNO055_STM32_H_
2 | #define BNO055_STM32_H_
3 |
4 | #ifdef __cplusplus
5 | extern "C" {
6 | #endif
7 |
8 | #include "i2c.h"
9 |
10 | #ifdef FREERTOS_ENABLED
11 | #include "FreeRTOS.h"
12 | #include "task.h"
13 | #include "cmsis_os.h"
14 | #endif
15 |
16 | #include "bno055.h"
17 |
18 | I2C_HandleTypeDef *_bno055_i2c_port;
19 |
20 | void bno055_assignI2C(I2C_HandleTypeDef *hi2c_device) {
21 | _bno055_i2c_port = hi2c_device;
22 | }
23 |
24 | void bno055_delay(int time) {
25 | #ifdef FREERTOS_ENABLED
26 | osDelay(time);
27 | #else
28 | HAL_Delay(time);
29 | #endif
30 | }
31 |
32 | void bno055_writeData(uint8_t reg, uint8_t data) {
33 | uint8_t txdata[2] = {reg, data};
34 | uint8_t status;
35 | status = HAL_I2C_Master_Transmit(_bno055_i2c_port, BNO055_I2C_ADDR << 1,
36 | txdata, sizeof(txdata), 10);
37 | if (status == HAL_OK) {
38 | return;
39 | }
40 |
41 | if (status == HAL_ERROR) {
42 | printf("HAL_I2C_Master_Transmit HAL_ERROR\r\n");
43 | } else if (status == HAL_TIMEOUT) {
44 | printf("HAL_I2C_Master_Transmit HAL_TIMEOUT\r\n");
45 | } else if (status == HAL_BUSY) {
46 | printf("HAL_I2C_Master_Transmit HAL_BUSY\r\n");
47 | } else {
48 | printf("Unknown status data %d", status);
49 | }
50 |
51 | uint32_t error = HAL_I2C_GetError(_bno055_i2c_port);
52 | if (error == HAL_I2C_ERROR_NONE) {
53 | return;
54 | } else if (error == HAL_I2C_ERROR_BERR) {
55 | printf("HAL_I2C_ERROR_BERR\r\n");
56 | } else if (error == HAL_I2C_ERROR_ARLO) {
57 | printf("HAL_I2C_ERROR_ARLO\r\n");
58 | } else if (error == HAL_I2C_ERROR_AF) {
59 | printf("HAL_I2C_ERROR_AF\r\n");
60 | } else if (error == HAL_I2C_ERROR_OVR) {
61 | printf("HAL_I2C_ERROR_OVR\r\n");
62 | } else if (error == HAL_I2C_ERROR_DMA) {
63 | printf("HAL_I2C_ERROR_DMA\r\n");
64 | } else if (error == HAL_I2C_ERROR_TIMEOUT) {
65 | printf("HAL_I2C_ERROR_TIMEOUT\r\n");
66 | }
67 |
68 | HAL_I2C_StateTypeDef state = HAL_I2C_GetState(_bno055_i2c_port);
69 | if (state == HAL_I2C_STATE_RESET) {
70 | printf("HAL_I2C_STATE_RESET\r\n");
71 | } else if (state == HAL_I2C_STATE_READY) {
72 | printf("HAL_I2C_STATE_RESET\r\n");
73 | } else if (state == HAL_I2C_STATE_BUSY) {
74 | printf("HAL_I2C_STATE_BUSY\r\n");
75 | } else if (state == HAL_I2C_STATE_BUSY_TX) {
76 | printf("HAL_I2C_STATE_BUSY_TX\r\n");
77 | } else if (state == HAL_I2C_STATE_BUSY_RX) {
78 | printf("HAL_I2C_STATE_BUSY_RX\r\n");
79 | } else if (state == HAL_I2C_STATE_LISTEN) {
80 | printf("HAL_I2C_STATE_LISTEN\r\n");
81 | } else if (state == HAL_I2C_STATE_BUSY_TX_LISTEN) {
82 | printf("HAL_I2C_STATE_BUSY_TX_LISTEN\r\n");
83 | } else if (state == HAL_I2C_STATE_BUSY_RX_LISTEN) {
84 | printf("HAL_I2C_STATE_BUSY_RX_LISTEN\r\n");
85 | } else if (state == HAL_I2C_STATE_ABORT) {
86 | printf("HAL_I2C_STATE_ABORT\r\n");
87 | } else if (state == HAL_I2C_STATE_TIMEOUT) {
88 | printf("HAL_I2C_STATE_TIMEOUT\r\n");
89 | } else if (state == HAL_I2C_STATE_ERROR) {
90 | printf("HAL_I2C_STATE_ERROR\r\n");
91 | }
92 | // while (HAL_I2C_GetState(_bno055_i2c_port) != HAL_I2C_STATE_READY) {}
93 | // return;
94 | }
95 |
96 | void bno055_readData(uint8_t reg, uint8_t *data, uint8_t len) {
97 | HAL_I2C_Master_Transmit(_bno055_i2c_port, BNO055_I2C_ADDR << 1, ®, 1,
98 | 100);
99 | HAL_I2C_Master_Receive(_bno055_i2c_port, BNO055_I2C_ADDR << 1, data, len,
100 | 100);
101 | // HAL_I2C_Mem_Read(_bno055_i2c_port, BNO055_I2C_ADDR_LO<<1, reg,
102 | // I2C_MEMADD_SIZE_8BIT, data, len, 100);
103 | }
104 |
105 | #ifdef __cplusplus
106 | }
107 | #endif
108 |
109 | #endif // BNO055_STM32_H_
110 |
--------------------------------------------------------------------------------
/test.c:
--------------------------------------------------------------------------------
1 | #include "bno055.h"
2 |
3 | #define I2C_HandleTypeDef int;
4 | // I2C_HandleTypeDef *_bno055_i2c_port;
5 |
6 | void bno055_delay(int time) {
7 | }
8 |
9 | void bno055_writeData(uint8_t reg, uint8_t data) {
10 | }
11 |
12 | void bno055_readData(uint8_t reg, uint8_t *data, uint8_t len) {
13 | }
14 |
15 | int main() {
16 | bno055_setup();
17 | }
18 |
--------------------------------------------------------------------------------