diff --git a/BNO08x.cpp b/BNO08x.cpp index 21bd5c6..72c3977 100644 --- a/BNO08x.cpp +++ b/BNO08x.cpp @@ -14,9 +14,11 @@ bno08x_config_t BNO08x::default_imu_config; */ BNO08x::BNO08x(bno08x_config_t imu_config) : tx_packet_queued(0U) + , tx_semaphore(xSemaphoreCreateRecursiveMutex()) + , int_asserted_semaphore(xSemaphoreCreateBinary()) , imu_config(imu_config) , calibration_status(1) - , int_asserted(false) + { // clear all buffers memset(tx_buffer, 0, sizeof(tx_buffer)); @@ -103,7 +105,6 @@ BNO08x::BNO08x(bno08x_config_t imu_config) spi_transaction.flags = 0; spi_device_polling_transmit(spi_hdl, &spi_transaction); // send data packet - tx_semaphore = xSemaphoreCreateRecursiveMutex(); spi_task_hdl = NULL; xTaskCreate(&spi_task_trampoline, "spi_task", 4096, this, 8, &spi_task_hdl); // launch SPI task } @@ -190,31 +191,21 @@ bool BNO08x::initialize() */ bool BNO08x::wait_for_device_int() { - int64_t start_time = esp_timer_get_time(); // get start time to manager timeout period - gpio_intr_enable(imu_config.io_int); // re-enable interrupts + gpio_intr_enable(imu_config.io_int); // re-enable interrupts // wait until an interrupt has been asserted or timeout has occured - while (!int_asserted) - { - vTaskDelay(10 / portTICK_PERIOD_MS); - - if ((esp_timer_get_time() - start_time) > HOST_INT_TIMEOUT_US) - break; - } - - if (int_asserted) + if (xSemaphoreTake(int_asserted_semaphore, HOST_INT_TIMEOUT_MS / portTICK_PERIOD_MS) == pdTRUE) { if (imu_config.debug_en) ESP_LOGI(TAG, "int asserted"); - int_asserted = false; // reset HINT ISR flag return true; } - - if (!int_asserted) + else + { ESP_LOGE(TAG, "Interrupt to host device never asserted."); - - return false; + return false; + } } /** @@ -2445,9 +2436,8 @@ void BNO08x::spi_task() else receive_packet(); // receive packet - int_asserted = true; // SPI completed, set interrupt asserted flag as true - - xSemaphoreGive(tx_semaphore); // give back the semaphore such that queue packet be blocked + xSemaphoreGive(int_asserted_semaphore); // SPI completed, give int_asserted_semaphore to notify wait_for_int() + xSemaphoreGive(tx_semaphore); // give back the semaphore such that queue packet be blocked } } diff --git a/BNO08x.hpp b/BNO08x.hpp index 70340f4..dd8c360 100644 --- a/BNO08x.hpp +++ b/BNO08x.hpp @@ -289,6 +289,8 @@ class BNO08x volatile uint8_t tx_packet_queued; /// - + -esp32_BNO08x: D:/development/git Directory Reference +esp32_BNO08x: esp32_BNO08x/BNO08x.cpp File Reference + + @@ -21,7 +23,7 @@ -
esp32_BNO08x 1.00 +
esp32_BNO08x 1.01
C++ BNO08x IMU driver component for esp-idf.
@@ -30,7 +32,7 @@
- + @@ -70,23 +72,18 @@ $(function() {
-
git Directory Reference
+
BNO08x.cpp File Reference
- - - - -

-Directories

 esp32_BNO08x
 
-
+
#include "BNO08x.hpp"
+
diff --git a/documentation/html/_b_n_o08x_8hpp.html b/documentation/html/_b_n_o08x_8hpp.html new file mode 100644 index 0000000..7376bd2 --- /dev/null +++ b/documentation/html/_b_n_o08x_8hpp.html @@ -0,0 +1,215 @@ + + + + + + + +esp32_BNO08x: esp32_BNO08x/BNO08x.hpp File Reference + + + + + + + + + + + +
+
+ + + + + + +
+
esp32_BNO08x 1.01 +
+
C++ BNO08x IMU driver component for esp-idf.
+
+
+ + + + + + + + +
+
+ + +
+
+
+
+
+
Loading...
+
Searching...
+
No Matches
+
+
+
+
+ + +
+
+ +
BNO08x.hpp File Reference
+
+
+
#include <driver/gpio.h>
+#include <driver/spi_common.h>
+#include <driver/spi_master.h>
+#include <esp_log.h>
+#include <esp_rom_gpio.h>
+#include <esp_timer.h>
+#include <freertos/FreeRTOS.h>
+#include <freertos/semphr.h>
+#include <freertos/task.h>
+#include <rom/ets_sys.h>
+#include <inttypes.h>
+#include <math.h>
+#include <stdio.h>
+#include <cstring>
+
+

Go to the source code of this file.

+ + + + + + + +

+Classes

struct  bno08x_config_t
 IMU configuration settings passed into constructor. More...
 
class  BNO08x
 
+ + + + +

+Typedefs

typedef struct bno08x_config_t bno08x_config_t
 IMU configuration settings passed into constructor.
 
+ + + + + + + +

+Enumerations

enum  channels_t {
+  CHANNEL_COMMAND +, CHANNEL_EXECUTABLE +, CHANNEL_CONTROL +, CHANNEL_REPORTS +,
+  CHANNEL_WAKE_REPORTS +, CHANNEL_GYRO +
+ }
 SHTP protocol channels. More...
 
enum class  IMUAccuracy { LOW = 1 +, MED +, HIGH + }
 Sensor accuracy returned during sensor calibration. More...
 
+

Typedef Documentation

+ +

◆ bno08x_config_t

+ +
+
+ + + + +
typedef struct bno08x_config_t bno08x_config_t
+
+ +

IMU configuration settings passed into constructor.

+ +
+
+

Enumeration Type Documentation

+ +

◆ channels_t

+ +
+
+ + + + +
enum channels_t
+
+ +

SHTP protocol channels.

+ + + + + + + +
Enumerator
CHANNEL_COMMAND 
CHANNEL_EXECUTABLE 
CHANNEL_CONTROL 
CHANNEL_REPORTS 
CHANNEL_WAKE_REPORTS 
CHANNEL_GYRO 
+ +
+
+ +

◆ IMUAccuracy

+ +
+
+ + + + + +
+ + + + +
enum class IMUAccuracy
+
+strong
+
+ +

Sensor accuracy returned during sensor calibration.

+ + + + +
Enumerator
LOW 
MED 
HIGH 
+ +
+
+
+ + + + diff --git a/documentation/html/_b_n_o08x_8hpp_source.html b/documentation/html/_b_n_o08x_8hpp_source.html index a619000..f19852a 100644 --- a/documentation/html/_b_n_o08x_8hpp_source.html +++ b/documentation/html/_b_n_o08x_8hpp_source.html @@ -3,12 +3,14 @@ - + -esp32_BNO08x: D:/development/git/esp32_BNO08x/BNO08x.hpp Source File +esp32_BNO08x: esp32_BNO08x/BNO08x.hpp Source File + + @@ -21,7 +23,7 @@ -
esp32_BNO08x 1.00 +
esp32_BNO08x 1.01
C++ BNO08x IMU driver component for esp-idf.
@@ -30,7 +32,7 @@
- + +
BNO08x.hpp
-
1#pragma once
-
2
-
3//standard library includes
-
4#include <stdio.h>
-
5#include <cstring>
-
6#include <inttypes.h>
-
7#include <math.h>
-
8
-
9//esp-idf includes
-
10#include "driver/gpio.h"
-
11#include "esp_rom_gpio.h"
-
12#include "driver/spi_common.h"
-
13#include "driver/spi_master.h"
-
14#include "freertos/FreeRTOS.h"
-
15#include "freertos/task.h"
-
16#include "freertos/semphr.h"
-
17#include "esp_log.h"
-
18#include "esp_timer.h"
-
19#include "rom/ets_sys.h"
-
20
-
22enum channels_t
-
23{
-
24 CHANNEL_COMMAND,
-
25 CHANNEL_EXECUTABLE,
-
26 CHANNEL_CONTROL,
-
27 CHANNEL_REPORTS,
-
28 CHANNEL_WAKE_REPORTS,
-
29 CHANNEL_GYRO
-
30};
-
31
-
33enum sensor_accuracy_t
-
34{
-
35 LOW_ACCURACY = 1,
-
36 MED_ACCURACY,
-
37 HIGH_ACCURACY
-
38};
-
39
-
41typedef struct bno08x_config_t
-
42{
-
43 spi_host_device_t spi_peripheral;
-
44 gpio_num_t io_mosi;
-
45 gpio_num_t io_miso;
-
46 gpio_num_t io_sclk;
-
47 gpio_num_t io_cs;
-
48 gpio_num_t io_int;
-
49 gpio_num_t io_rst;
-
50 gpio_num_t io_wake;
-
51 uint64_t sclk_speed;
-
52 bool debug_en;
-
53
- -
56 spi_peripheral(SPI3_HOST),
-
57 io_mosi(GPIO_NUM_23),
-
58 io_miso(GPIO_NUM_19),
-
59 io_sclk(GPIO_NUM_18),
-
60 io_cs(GPIO_NUM_33),
-
61 io_int(GPIO_NUM_26),
-
62 io_rst(GPIO_NUM_32),
-
63 io_wake(GPIO_NUM_4),
-
64 //sclk_speed(10000U), //clock slowed to see on AD2
-
65 sclk_speed(2000000U), //1MHz SCLK speed
-
66 debug_en(false)
-
67
-
68 {
-
69 }
-
70
- -
72
-
73class BNO08x
-
74{
-
75 public:
- -
77 bool initialize();
-
78
-
79 bool hard_reset();
-
80 bool soft_reset();
-
81 uint8_t get_reset_reason();
-
82 bool mode_sleep();
-
83 bool mode_on();
-
84
-
85 float q_to_float(int16_t fixed_point_value, uint8_t q_point);
-
86
- -
88 void calibrate_all();
- -
90 void calibrate_gyro();
- - - - -
95 void end_calibration();
-
96 void save_calibration();
-
97
-
98 void enable_rotation_vector(uint16_t time_between_reports);
-
99 void enable_game_rotation_vector(uint16_t time_between_reports);
-
100 void enable_ARVR_stabilized_rotation_vector(uint16_t time_between_reports);
-
101 void enable_ARVR_stabilized_game_rotation_vector(uint16_t time_between_reports);
-
102 void enable_gyro_integrated_rotation_vector(uint16_t timeBetweenReports);
-
103 void enable_accelerometer(uint16_t time_between_reports);
-
104 void enable_linear_accelerometer(uint16_t time_between_reports);
-
105 void enable_gravity(uint16_t time_between_reports);
-
106 void enable_gyro(uint16_t time_between_reports);
-
107 void enable_uncalibrated_gyro(uint16_t time_between_reports);
-
108 void enable_magnetometer(uint16_t time_between_reports);
-
109 void enable_tap_detector(uint16_t time_between_reports);
-
110 void enable_step_counter(uint16_t time_between_reports);
-
111 void enable_stability_classifier(uint16_t time_between_reports);
-
112 void enable_activity_classifier(uint16_t time_between_reports, uint32_t activities_to_enable, uint8_t (&activity_confidence_vals)[9]);
-
113 void enable_raw_accelerometer(uint16_t time_between_reports);
-
114 void enable_raw_gyro(uint16_t time_between_reports);
-
115 void enable_raw_magnetometer(uint16_t time_between_reports);
-
116
-
117 void tare_now(uint8_t axis_sel = TARE_AXIS_ALL, uint8_t rotation_vector_basis = TARE_ROTATION_VECTOR);
-
118 void save_tare();
-
119 void clear_tare();
-
120
-
121 bool data_available();
-
122 uint16_t parse_input_report();
-
123 uint16_t parse_command_report();
-
124 uint16_t get_readings();
-
125
-
126 uint32_t get_time_stamp();
+Go to the documentation of this file.
1#pragma once
+
2#include <driver/gpio.h>
+
3#include <driver/spi_common.h>
+
4#include <driver/spi_master.h>
+
5#include <esp_log.h>
+
6#include <esp_rom_gpio.h>
+
7#include <esp_timer.h>
+
8#include <freertos/FreeRTOS.h>
+
9#include <freertos/semphr.h>
+
10#include <freertos/task.h>
+
11#include <rom/ets_sys.h>
+
12
+
13#include <inttypes.h>
+
14#include <math.h>
+
15#include <stdio.h>
+
16#include <cstring>
+
17
+ +
28
+
+
30enum class IMUAccuracy
+
31{
+
32 LOW = 1,
+
33 MED,
+
34 HIGH
+
35};
+
+
36
+
+
38typedef struct bno08x_config_t
+
39{
+
40 spi_host_device_t spi_peripheral;
+
41 gpio_num_t io_mosi;
+
42 gpio_num_t io_miso;
+
43 gpio_num_t io_sclk;
+
44 gpio_num_t io_cs;
+
45 gpio_num_t io_int;
+
46 gpio_num_t io_rst;
+
47 gpio_num_t io_wake;
+
48 uint64_t sclk_speed;
+
49 bool debug_en;
+
50
+
51#ifdef ESP32C3_IMU_CONFIG
+ +
55 : spi_peripheral(SPI2_HOST)
+
56 , io_mosi(GPIO_NUM_4)
+
57 , io_miso(GPIO_NUM_19)
+
58 , io_sclk(GPIO_NUM_18)
+
59 , io_cs(GPIO_NUM_5)
+
60 , io_int(GPIO_NUM_6)
+
61 , io_rst(GPIO_NUM_7)
+
62 , io_wake(GPIO_NUM_NC)
+
63 , sclk_speed(2000000UL) // 2MHz SCLK speed
+
64 , debug_en(false)
+
65 {
+
66 }
+
67#else
+
+ +
70 : spi_peripheral(SPI3_HOST)
+
71 , io_mosi(GPIO_NUM_23)
+
72 , io_miso(GPIO_NUM_19)
+
73 , io_sclk(GPIO_NUM_18)
+
74 , io_cs(GPIO_NUM_33)
+
75 , io_int(GPIO_NUM_26)
+
76 , io_rst(GPIO_NUM_32)
+
77 , io_wake(GPIO_NUM_NC)
+
78 , sclk_speed(2000000UL) // 2MHz SCLK speed
+
79 // , sclk_speed(10000U), //clock slowed to see on AD2
+
80 , debug_en(false)
+
81
+
82 {
+
83 }
+
+
84#endif
+
+
86 bno08x_config_t(spi_host_device_t spi_peripheral, gpio_num_t io_mosi, gpio_num_t io_miso, gpio_num_t io_sclk, gpio_num_t io_cs,
+
87 gpio_num_t io_int, gpio_num_t io_rst, gpio_num_t io_wake, uint64_t sclk_speed, bool debug)
+ + + + +
92 , io_cs(io_cs)
+
93 , io_int(io_int)
+
94 , io_rst(io_rst)
+ + +
97 , debug_en(false)
+
98
+
99 {
+
100 }
+
+ +
+
102
+
+ +
104{
+
105 public:
+ +
107 bool initialize();
+
108
+
109 bool hard_reset();
+
110 bool soft_reset();
+
111 uint8_t get_reset_reason();
+
112
+
113 bool mode_sleep();
+
114 bool mode_on();
+
115 float q_to_float(int16_t fixed_point_value, uint8_t q_point);
+
116
+ +
118 void calibrate_all();
+ +
120 void calibrate_gyro();
+ + + + +
125 void end_calibration();
+
126 void save_calibration();
127
-
128 void get_magf(float &x, float &y, float &z, uint8_t &accuracy);
-
129 float get_magf_X();
-
130 float get_magf_Y();
-
131 float get_magf_Z();
-
132 uint8_t get_magf_accuracy();
-
133
-
134 void get_gravity(float &x, float &y, float &z, uint8_t &accuracy);
-
135 float get_gravity_X();
-
136 float get_gravity_Y();
-
137 float get_gravity_Z();
-
138 uint8_t get_gravity_accuracy();
-
139
-
140 float get_roll();
-
141 float get_pitch();
-
142 float get_yaw();
-
143
-
144 float get_roll_deg();
-
145 float get_pitch_deg();
-
146 float get_yaw_deg();
-
147
-
148 void get_quat(float &i, float &j, float &k, float &real, float &rad_accuracy, uint8_t &accuracy);
-
149 float get_quat_I();
-
150 float get_quat_J();
-
151 float get_quat_K();
-
152 float get_quat_real();
- -
154 uint8_t get_quat_accuracy();
+
128 void enable_rotation_vector(uint16_t time_between_reports);
+
129 void enable_game_rotation_vector(uint16_t time_between_reports);
+
130 void enable_ARVR_stabilized_rotation_vector(uint16_t time_between_reports);
+
131 void enable_ARVR_stabilized_game_rotation_vector(uint16_t time_between_reports);
+
132 void enable_gyro_integrated_rotation_vector(uint16_t timeBetweenReports);
+
133 void enable_accelerometer(uint16_t time_between_reports);
+
134 void enable_linear_accelerometer(uint16_t time_between_reports);
+
135 void enable_gravity(uint16_t time_between_reports);
+
136 void enable_gyro(uint16_t time_between_reports);
+
137 void enable_uncalibrated_gyro(uint16_t time_between_reports);
+
138 void enable_magnetometer(uint16_t time_between_reports);
+
139 void enable_tap_detector(uint16_t time_between_reports);
+
140 void enable_step_counter(uint16_t time_between_reports);
+
141 void enable_stability_classifier(uint16_t time_between_reports);
+
142 void enable_activity_classifier(uint16_t time_between_reports, uint32_t activities_to_enable, uint8_t (&activity_confidence_vals)[9]);
+
143 void enable_raw_accelerometer(uint16_t time_between_reports);
+
144 void enable_raw_gyro(uint16_t time_between_reports);
+
145 void enable_raw_magnetometer(uint16_t time_between_reports);
+
146
+
147 void tare_now(uint8_t axis_sel = TARE_AXIS_ALL, uint8_t rotation_vector_basis = TARE_ROTATION_VECTOR);
+
148 void save_tare();
+
149 void clear_tare();
+
150
+
151 bool data_available();
+
152 uint16_t parse_input_report();
+
153 uint16_t parse_command_report();
+
154 uint16_t get_readings();
155
-
156 void get_accel(float &x, float &y, float &z, uint8_t &accuracy);
-
157 float get_accel_X();
-
158 float get_accel_Y();
-
159 float get_accel_Z();
-
160 uint8_t get_accel_accuracy();
-
161
-
162 void get_linear_accel(float &x, float &y, float &z, uint8_t &accuracy);
-
163 float get_linear_accel_X();
-
164 float get_linear_accel_Y();
-
165 float get_linear_accel_Z();
- -
167
-
168 int16_t get_raw_accel_X();
-
169 int16_t get_raw_accel_Y();
-
170 int16_t get_raw_accel_Z();
-
171
-
172 int16_t get_raw_gyro_X();
-
173 int16_t get_raw_gyro_Y();
-
174 int16_t get_raw_gyro_Z();
-
175
-
176 int16_t get_raw_magf_X();
-
177 int16_t get_raw_magf_Y();
-
178 int16_t get_raw_magf_Z();
-
179
-
180 void get_gyro_calibrated_velocity(float &x, float &y, float &z, uint8_t &accuracy);
- - - -
184 uint8_t get_gyro_accuracy();
+
156 uint32_t get_time_stamp();
+
157
+
158 void get_magf(float& x, float& y, float& z, uint8_t& accuracy);
+
159 float get_magf_X();
+
160 float get_magf_Y();
+
161 float get_magf_Z();
+
162 uint8_t get_magf_accuracy();
+
163
+
164 void get_gravity(float& x, float& y, float& z, uint8_t& accuracy);
+
165 float get_gravity_X();
+
166 float get_gravity_Y();
+
167 float get_gravity_Z();
+
168 uint8_t get_gravity_accuracy();
+
169
+
170 float get_roll();
+
171 float get_pitch();
+
172 float get_yaw();
+
173
+
174 float get_roll_deg();
+
175 float get_pitch_deg();
+
176 float get_yaw_deg();
+
177
+
178 void get_quat(float& i, float& j, float& k, float& real, float& rad_accuracy, uint8_t& accuracy);
+
179 float get_quat_I();
+
180 float get_quat_J();
+
181 float get_quat_K();
+
182 float get_quat_real();
+ +
184 uint8_t get_quat_accuracy();
185
-
186 void get_uncalibrated_gyro(float &x, float &y, float &z, float &bx, float &by, float &bz, uint8_t &accuracy);
- - - - - - - -
194
-
195 void get_gyro_velocity(float &x, float &y, float &z);
-
196 float get_gyro_velocity_X();
-
197 float get_gyro_velocity_Y();
-
198 float get_gyro_velocity_Z();
-
199
-
200 uint8_t get_tap_detector();
-
201 uint16_t get_step_count();
- -
203 uint8_t get_activity_classifier();
-
204
-
205 void print_header();
-
206 void print_packet();
-
207
-
208 //Metadata functions
-
209 int16_t get_Q1(uint16_t record_ID);
-
210 int16_t get_Q2(uint16_t record_ID);
-
211 int16_t get_Q3(uint16_t record_ID);
-
212 float get_resolution(uint16_t record_ID);
-
213 float get_range(uint16_t record_ID);
-
214 uint32_t FRS_read_word(uint16_t record_ID, uint8_t word_number);
-
215 bool FRS_read_request(uint16_t record_ID, uint16_t read_offset, uint16_t block_size);
-
216 bool FRS_read_data(uint16_t record_ID, uint8_t start_location, uint8_t words_to_read);
-
217
-
218 //Record IDs from figure 29, page 29 reference manual
-
219 //These are used to read the metadata for each sensor type
-
220 static const constexpr uint16_t FRS_RECORDID_ACCELEROMETER = 0xE302;
-
221 static const constexpr uint16_t FRS_RECORDID_GYROSCOPE_CALIBRATED = 0xE306;
-
222 static const constexpr uint16_t FRS_RECORDID_MAGNETIC_FIELD_CALIBRATED = 0xE309;
-
223 static const constexpr uint16_t FRS_RECORDID_ROTATION_VECTOR = 0xE30B;
+
186 void get_accel(float& x, float& y, float& z, uint8_t& accuracy);
+
187 float get_accel_X();
+
188 float get_accel_Y();
+
189 float get_accel_Z();
+
190 uint8_t get_accel_accuracy();
+
191
+
192 void get_linear_accel(float& x, float& y, float& z, uint8_t& accuracy);
+
193 float get_linear_accel_X();
+
194 float get_linear_accel_Y();
+
195 float get_linear_accel_Z();
+ +
197
+
198 int16_t get_raw_accel_X();
+
199 int16_t get_raw_accel_Y();
+
200 int16_t get_raw_accel_Z();
+
201
+
202 int16_t get_raw_gyro_X();
+
203 int16_t get_raw_gyro_Y();
+
204 int16_t get_raw_gyro_Z();
+
205
+
206 int16_t get_raw_magf_X();
+
207 int16_t get_raw_magf_Y();
+
208 int16_t get_raw_magf_Z();
+
209
+
210 void get_gyro_calibrated_velocity(float& x, float& y, float& z, uint8_t& accuracy);
+ + + +
214 uint8_t get_gyro_accuracy();
+
215
+
216 void get_uncalibrated_gyro(float& x, float& y, float& z, float& bx, float& by, float& bz, uint8_t& accuracy);
+ + + + + + +
224
-
225
-
226 private:
-
227 bool wait_for_device_int();
-
228 bool receive_packet();
-
229 void send_packet();
-
230 void queue_packet(uint8_t channel_number, uint8_t data_length);
-
231 void queue_command(uint8_t command);
-
232 void queue_feature_command(uint8_t report_ID, uint16_t time_between_reports);
-
233 void queue_feature_command(uint8_t report_ID, uint16_t time_between_reports, uint32_t specific_config);
-
234 void queue_calibrate_command(uint8_t _to_calibrate);
-
235 void queue_tare_command(uint8_t command, uint8_t axis = TARE_AXIS_ALL, uint8_t rotation_vector_basis = TARE_ROTATION_VECTOR);
- +
225 void get_gyro_velocity(float& x, float& y, float& z);
+
226 float get_gyro_velocity_X();
+
227 float get_gyro_velocity_Y();
+
228 float get_gyro_velocity_Z();
+
229
+
230 uint8_t get_tap_detector();
+
231 uint16_t get_step_count();
+ +
233 uint8_t get_activity_classifier();
+
234
+
235 void print_header();
+
236 void print_packet();
237
- -
239
-
240 volatile uint8_t tx_packet_queued;
-
241 SemaphoreHandle_t tx_semaphore;
-
242 uint8_t rx_buffer[300];
-
243 uint8_t tx_buffer[50];
-
244 uint8_t packet_header_rx[4];
-
245 uint8_t commands[20];
-
246 uint8_t sequence_number[6];
-
247 uint32_t meta_data[9];
- -
249 uint16_t packet_length_tx = 0;
-
250 uint16_t packet_length_rx = 0;
-
251
- -
253 spi_bus_config_t bus_config{};
-
254 spi_device_interface_config_t imu_spi_config{};
-
255 spi_device_handle_t spi_hdl{};
-
256 spi_transaction_t spi_transaction{};
+
238 // Metadata functions
+
239 int16_t get_Q1(uint16_t record_ID);
+
240 int16_t get_Q2(uint16_t record_ID);
+
241 int16_t get_Q3(uint16_t record_ID);
+
242 float get_resolution(uint16_t record_ID);
+
243 float get_range(uint16_t record_ID);
+
244 uint32_t FRS_read_word(uint16_t record_ID, uint8_t word_number);
+
245 bool FRS_read_request(uint16_t record_ID, uint16_t read_offset, uint16_t block_size);
+
246 bool FRS_read_data(uint16_t record_ID, uint8_t start_location, uint8_t words_to_read);
+
247
+
248 // Record IDs from figure 29, page 29 reference manual
+
249 // These are used to read the metadata for each sensor type
+
250 static const constexpr uint16_t FRS_RECORDID_ACCELEROMETER = 0xE302;
+
251 static const constexpr uint16_t FRS_RECORDID_GYROSCOPE_CALIBRATED = 0xE306;
+
252 static const constexpr uint16_t FRS_RECORDID_MAGNETIC_FIELD_CALIBRATED = 0xE309;
+
253 static const constexpr uint16_t FRS_RECORDID_ROTATION_VECTOR = 0xE30B;
+
254
+
255 static const constexpr uint8_t TARE_AXIS_ALL = 0x07;
+
256 static const constexpr uint8_t TARE_AXIS_Z = 0x04;
257
-
258 //These are the raw sensor values (without Q applied) pulled from the user requested Input Report
-
259 uint32_t time_stamp;
-
260 uint16_t raw_accel_X, raw_accel_Y, raw_accel_Z, accel_accuracy;
-
261 uint16_t raw_lin_accel_X, raw_lin_accel_Y, raw_lin_accel_Z, accel_lin_accuracy;
-
262 uint16_t raw_gyro_X, raw_gyro_Y, raw_gyro_Z, gyro_accuracy;
-
263 uint16_t raw_quat_I, raw_quat_J, raw_quat_K, raw_quat_real, raw_quat_radian_accuracy, quat_accuracy;
-
264 uint16_t raw_velocity_gyro_X, raw_velocity_gyro_Y, raw_velocity_gyro_Z;
-
265 uint16_t gravity_X, gravity_Y, gravity_Z, gravity_accuracy;
-
266 uint16_t raw_uncalib_gyro_X, raw_uncalib_gyro_Y, raw_uncalib_gyro_Z, raw_bias_X, raw_bias_Y, raw_bias_Z, uncalib_gyro_accuracy;
-
267 uint16_t raw_magf_X, raw_magf_Y, raw_magf_Z, magf_accuracy;
-
268 uint8_t tap_detector;
-
269 uint16_t step_count;
- - - - -
274 uint16_t mems_raw_accel_X, mems_raw_accel_Y, mems_raw_accel_Z;
-
275 uint16_t mems_raw_gyro_X, mems_raw_gyro_Y, mems_raw_gyro_Z;
-
276 uint16_t mems_raw_magf_X, mems_raw_magf_Y, mems_raw_magf_Z;
-
277
-
278 //spi task
-
279 TaskHandle_t spi_task_hdl;
-
280 static void spi_task_trampoline(void *arg);
-
281 void spi_task();
-
282
-
283 volatile bool int_asserted;
-
284 static void IRAM_ATTR hint_handler(void *arg);
- -
286
-
287
-
288 static const constexpr int16_t ROTATION_VECTOR_Q1 = 14;
-
289 static const constexpr int16_t ROTATION_VECTOR_ACCURACY_Q1 = 12;
-
290 static const constexpr int16_t ACCELEROMETER_Q1 = 8;
-
291 static const constexpr int16_t LINEAR_ACCELEROMETER_Q1 = 8;
-
292 static const constexpr int16_t GYRO_Q1 = 9;
-
293 static const constexpr int16_t MAGNETOMETER_Q1 = 4;
-
294 static const constexpr int16_t ANGULAR_VELOCITY_Q1 = 10;
-
295 static const constexpr int16_t GRAVITY_Q1 = 8;
-
296
-
297 static const constexpr uint64_t HOST_INT_TIMEOUT_US = 150000ULL;
-
298
-
299 //Higher level calibration commands, used by queue_calibrate_command
-
300 static const constexpr uint8_t CALIBRATE_ACCEL = 0;
-
301 static const constexpr uint8_t CALIBRATE_GYRO = 1;
-
302 static const constexpr uint8_t CALIBRATE_MAG = 2;
-
303 static const constexpr uint8_t CALIBRATE_PLANAR_ACCEL = 3;
-
304 static const constexpr uint8_t CALIBRATE_ACCEL_GYRO_MAG = 4;
-
305 static const constexpr uint8_t CALIBRATE_STOP = 5;
-
306
-
307 //Command IDs (see Ref. Manual 6.4)
-
308 static const constexpr uint8_t COMMAND_ERRORS = 1;
-
309 static const constexpr uint8_t COMMAND_COUNTER = 2;
-
310 static const constexpr uint8_t COMMAND_TARE = 3;
-
311 static const constexpr uint8_t COMMAND_INITIALIZE = 4;
-
312 static const constexpr uint8_t COMMAND_DCD = 6;
-
313 static const constexpr uint8_t COMMAND_ME_CALIBRATE = 7;
-
314 static const constexpr uint8_t COMMAND_DCD_PERIOD_SAVE = 9;
-
315 static const constexpr uint8_t COMMAND_OSCILLATOR = 10;
-
316 static const constexpr uint8_t COMMAND_CLEAR_DCD = 11;
-
317
-
318 //SHTP channel 2 control report IDs, used in communication with sensor (See Ref. Manual 6.2)
-
319 static const constexpr uint8_t SHTP_REPORT_COMMAND_RESPONSE = 0xF1;
-
320 static const constexpr uint8_t SHTP_REPORT_COMMAND_REQUEST = 0xF2;
-
321 static const constexpr uint8_t SHTP_REPORT_FRS_READ_RESPONSE = 0xF3;
-
322 static const constexpr uint8_t SHTP_REPORT_FRS_READ_REQUEST = 0xF4;
-
323 static const constexpr uint8_t SHTP_REPORT_PRODUCT_ID_RESPONSE = 0xF8;
-
324 static const constexpr uint8_t SHTP_REPORT_PRODUCT_ID_REQUEST = 0xF9;
-
325 static const constexpr uint8_t SHTP_REPORT_BASE_TIMESTAMP = 0xFB;
-
326 static const constexpr uint8_t SHTP_REPORT_SET_FEATURE_COMMAND = 0xFD;
-
327
-
328
-
329 //Sensor report IDs, used when enabling and reading BNO08x reports
-
330 static const constexpr uint8_t SENSOR_REPORTID_ACCELEROMETER = 0x01;
-
331 static const constexpr uint8_t SENSOR_REPORTID_GYROSCOPE = 0x02;
-
332 static const constexpr uint8_t SENSOR_REPORTID_MAGNETIC_FIELD = 0x03;
-
333 static const constexpr uint8_t SENSOR_REPORTID_LINEAR_ACCELERATION = 0x04;
-
334 static const constexpr uint8_t SENSOR_REPORTID_ROTATION_VECTOR = 0x05;
-
335 static const constexpr uint8_t SENSOR_REPORTID_GRAVITY = 0x06;
-
336 static const constexpr uint8_t SENSOR_REPORTID_UNCALIBRATED_GYRO = 0x07;
-
337 static const constexpr uint8_t SENSOR_REPORTID_GAME_ROTATION_VECTOR = 0x08;
-
338 static const constexpr uint8_t SENSOR_REPORTID_GEOMAGNETIC_ROTATION_VECTOR = 0x09;
-
339 static const constexpr uint8_t SENSOR_REPORTID_GYRO_INTEGRATED_ROTATION_VECTOR = 0x2A;
-
340 static const constexpr uint8_t SENSOR_REPORTID_TAP_DETECTOR = 0x10;
-
341 static const constexpr uint8_t SENSOR_REPORTID_STEP_COUNTER = 0x11;
-
342 static const constexpr uint8_t SENSOR_REPORTID_STABILITY_CLASSIFIER = 0x13;
-
343 static const constexpr uint8_t SENSOR_REPORTID_RAW_ACCELEROMETER = 0x14;
-
344 static const constexpr uint8_t SENSOR_REPORTID_RAW_GYROSCOPE = 0x15;
-
345 static const constexpr uint8_t SENSOR_REPORTID_RAW_MAGNETOMETER = 0x16;
-
346 static const constexpr uint8_t SENSOR_REPORTID_PERSONAL_ACTIVITY_CLASSIFIER = 0x1E;
-
347 static const constexpr uint8_t SENSOR_REPORTID_AR_VR_STABILIZED_ROTATION_VECTOR = 0x28;
-
348 static const constexpr uint8_t SENSOR_REPORTID_AR_VR_STABILIZED_GAME_ROTATION_VECTOR = 0x29;
-
349
-
350 //Tare commands used by queue_tare_command
-
351 static const constexpr uint8_t TARE_NOW = 0;
-
352 static const constexpr uint8_t TARE_PERSIST = 1;
-
353 static const constexpr uint8_t TARE_SET_REORIENTATION = 2;
-
354
-
355 static const constexpr uint8_t TARE_AXIS_ALL = 0x07;
-
356 static const constexpr uint8_t TARE_AXIS_Z = 0x04;
-
357
-
358 //Which rotation vector to tare, BNO08x saves them seperately
-
359 static const constexpr uint8_t TARE_ROTATION_VECTOR = 0;
-
360 static const constexpr uint8_t TARE_GAME_ROTATION_VECTOR = 1;
-
361 static const constexpr uint8_t TARE_GEOMAGNETIC_ROTATION_VECTOR = 2;
-
362 static const constexpr uint8_t TARE_GYRO_INTEGRATED_ROTATION_VECTOR = 3;
-
363 static const constexpr uint8_t TARE_AR_VR_STABILIZED_ROTATION_VECTOR = 4;
-
364 static const constexpr uint8_t TARE_AR_VR_STABILIZED_GAME_ROTATION_VECTOR = 5;
-
365
-
366 static const constexpr char *TAG = "BNO08x";
-
367};
-
Definition BNO08x.hpp:74
-
static const constexpr uint8_t SENSOR_REPORTID_PERSONAL_ACTIVITY_CLASSIFIER
See SH2 Ref. Manual 6.5.36.
Definition BNO08x.hpp:346
-
static const constexpr uint8_t SHTP_REPORT_PRODUCT_ID_RESPONSE
See SH2 Ref. Manual 6.3.2.
Definition BNO08x.hpp:323
-
void enable_ARVR_stabilized_rotation_vector(uint16_t time_between_reports)
Sends command to enable ARVR stabilized rotation vector reports (See Ref. Manual 6....
Definition BNO08x.cpp:1022
-
static const constexpr int16_t ACCELEROMETER_Q1
Acceleration Q point (See SH-2 Ref. Manual 6.5.9)
Definition BNO08x.hpp:290
-
uint16_t uncalib_gyro_accuracy
Uncalibrated gyro reading (See SH-2 Ref. Manual 6.5.14)
Definition BNO08x.hpp:266
-
void print_header()
Prints the most recently received SHTP header to serial console with ESP_LOG statement.
Definition BNO08x.cpp:2074
-
void enable_activity_classifier(uint16_t time_between_reports, uint32_t activities_to_enable, uint8_t(&activity_confidence_vals)[9])
Sends command to enable activity classifier reports (See Ref. Manual 6.5.36)
Definition BNO08x.cpp:1180
-
void enable_gyro_integrated_rotation_vector(uint16_t timeBetweenReports)
Sends command to enable gyro integrated rotation vector reports (See Ref. Manual 6....
Definition BNO08x.cpp:1048
-
static const constexpr uint8_t SENSOR_REPORTID_AR_VR_STABILIZED_GAME_ROTATION_VECTOR
See SH2 Ref. Manual 6.5.43.
Definition BNO08x.hpp:348
-
static const constexpr uint8_t COMMAND_TARE
Command and response to tare command (See Sh2 Ref. Manual 6.4.4)
Definition BNO08x.hpp:310
-
float get_accel_Z()
Get z axis acceleration (total acceleration of device, units in m/s^2).
Definition BNO08x.cpp:1656
-
float get_uncalibrated_gyro_Z()
Get uncalibrated gyro Z axis angular velocity measurement.
Definition BNO08x.cpp:1926
-
static const constexpr int16_t ROTATION_VECTOR_Q1
Rotation vector Q point (See SH-2 Ref. Manual 6.5.18)
Definition BNO08x.hpp:288
-
static void spi_task_trampoline(void *arg)
Static function used to launch spi task.
Definition BNO08x.cpp:2421
-
int8_t get_stability_classifier()
Get the current stability classifier (Seee Ref. Manual 6.5.31)
Definition BNO08x.cpp:2045
-
void send_packet()
Sends a queued SHTP packet via SPI.
Definition BNO08x.cpp:421
-
float get_range(uint16_t record_ID)
Gets range from BNO08x FRS (flash record system).
Definition BNO08x.cpp:2218
-
float get_linear_accel_Y()
Get y axis linear acceleration (acceleration of device minus gravity, units in m/s^2)
Definition BNO08x.cpp:1704
-
float get_magf_X()
Get X component of magnetic field vector.
Definition BNO08x.cpp:1314
-
static const constexpr uint8_t TARE_PERSIST
See SH2 Ref. Manual 6.4.4.2.
Definition BNO08x.hpp:352
-
uint8_t tap_detector
Tap detector reading (See SH-2 Ref. Manual 6.5.27)
Definition BNO08x.hpp:268
-
uint8_t get_reset_reason()
Get the reason for the most recent reset.
Definition BNO08x.cpp:269
-
float get_quat_I()
Get I component of reported quaternion.
Definition BNO08x.cpp:1553
-
int16_t get_Q3(uint16_t record_ID)
Gets Q3 point from BNO08x FRS (flash record system).
Definition BNO08x.cpp:2188
-
float get_gyro_calibrated_velocity_Z()
Get calibrated gyro z axis angular velocity measurement.
Definition BNO08x.cpp:1862
-
void queue_command(uint8_t command)
Queues a packet containing a command.
Definition BNO08x.cpp:444
-
bool mode_sleep()
Puts BNO08x sensor into sleep/low power mode using executable channel.
Definition BNO08x.cpp:315
-
float get_uncalibrated_gyro_Y()
Get uncalibrated gyro Y axis angular velocity measurement.
Definition BNO08x.cpp:1916
-
uint8_t stability_classifier
Stability status reading (See SH-2 Ref. Manual 6.5.31)
Definition BNO08x.hpp:270
-
float get_pitch()
Get the reported rotation about y axis.
Definition BNO08x.cpp:1443
-
void get_uncalibrated_gyro(float &x, float &y, float &z, float &bx, float &by, float &bz, uint8_t &accuracy)
Get full rotational velocity without drift compensation (units in Rad/s). An estimate of drift is giv...
Definition BNO08x.cpp:1890
-
void calibrate_planar_accelerometer()
Sends command to calibrate planar accelerometer.
Definition BNO08x.cpp:518
-
static const constexpr uint8_t SHTP_REPORT_SET_FEATURE_COMMAND
See SH2 Ref. Manual 6.5.4.
Definition BNO08x.hpp:326
-
void enable_accelerometer(uint16_t time_between_reports)
Sends command to enable accelerometer reports (See Ref. Manual 6.5.9)
Definition BNO08x.cpp:1061
-
float get_resolution(uint16_t record_ID)
Gets resolution from BNO08x FRS (flash record system).
Definition BNO08x.cpp:2201
-
int16_t get_raw_accel_X()
Get raw accelerometer x axis reading from physical accelerometer MEMs sensor (See Ref....
Definition BNO08x.cpp:1734
-
static const constexpr uint8_t SHTP_REPORT_COMMAND_RESPONSE
See SH2 Ref. Manual 6.3.9.
Definition BNO08x.hpp:319
-
static const constexpr uint8_t TARE_AXIS_ALL
Tare all axes (used with tare now command)
Definition BNO08x.hpp:355
-
static const constexpr uint8_t TARE_GEOMAGNETIC_ROTATION_VECTOR
tare geomagnetic rotation vector
Definition BNO08x.hpp:361
-
uint8_t get_quat_accuracy()
Get accuracy of reported quaternion.
Definition BNO08x.cpp:1608
-
static const constexpr uint8_t SENSOR_REPORTID_AR_VR_STABILIZED_ROTATION_VECTOR
See SH2 Ref. Manual 6.5.42.
Definition BNO08x.hpp:347
-
static const constexpr uint8_t TARE_NOW
See SH2 Ref. Manual 6.4.4.1.
Definition BNO08x.hpp:351
-
uint32_t FRS_read_word(uint16_t record_ID, uint8_t word_number)
Reads meta data word from BNO08x FRS (flash record system) given the record ID and word number....
Definition BNO08x.cpp:2238
-
float q_to_float(int16_t fixed_point_value, uint8_t q_point)
Converts a register value to a float using its associated Q point. (See https://en....
Definition BNO08x.cpp:1273
-
float get_uncalibrated_gyro_X()
Get uncalibrated gyro x axis angular velocity measurement.
Definition BNO08x.cpp:1906
-
bool hard_reset()
Hard resets BNO08x sensor.
Definition BNO08x.cpp:225
-
static const constexpr uint8_t SENSOR_REPORTID_GYROSCOPE
See SH2 Ref. Manual 6.5.13.
Definition BNO08x.hpp:331
-
int16_t get_raw_magf_Y()
Get raw magnetometer y axis reading from physical magnetometer sensor (See Ref. Manual 6....
Definition BNO08x.cpp:1804
-
static const constexpr char * TAG
Class tag used for serial print statements.
Definition BNO08x.hpp:366
-
void enable_gravity(uint16_t time_between_reports)
Sends command to enable gravity reading reports (See Ref. Manual 6.5.11)
Definition BNO08x.cpp:1087
-
int16_t get_raw_gyro_Z()
Get raw gyroscope z axis reading from physical gyroscope MEMs sensor (See Ref. Manual 6....
Definition BNO08x.cpp:1784
-
void spi_task()
Task responsible for SPI transactions. Executed when HINT in is asserted by BNO08x.
Definition BNO08x.cpp:2432
-
static const constexpr uint8_t COMMAND_OSCILLATOR
Retrieve oscillator type command (See SH2 Ref. Manual 6.4)
Definition BNO08x.hpp:315
-
static const constexpr uint8_t COMMAND_INITIALIZE
Reinitialize sensor hub components See (SH2 Ref. Manual 6.4.5)
Definition BNO08x.hpp:311
-
static const constexpr uint8_t TARE_AR_VR_STABILIZED_ROTATION_VECTOR
Tare ARVR stabilized rotation vector.
Definition BNO08x.hpp:363
-
uint8_t get_uncalibrated_gyro_accuracy()
Get uncalibrated gyro accuracy.
Definition BNO08x.cpp:1966
-
uint16_t accel_accuracy
Raw acceleration readings (See SH-2 Ref. Manual 6.5.8)
Definition BNO08x.hpp:260
-
uint8_t get_linear_accel_accuracy()
Get accuracy of linear acceleration.
Definition BNO08x.cpp:1724
-
void get_magf(float &x, float &y, float &z, uint8_t &accuracy)
Get the full magnetic field vector.
Definition BNO08x.cpp:1301
-
uint16_t accel_lin_accuracy
Raw linear acceleration (See SH-2 Ref. Manual 6.5.10)
Definition BNO08x.hpp:261
-
uint16_t quat_accuracy
Raw quaternion reading (See SH-2 Ref. Manual 6.5.44)
Definition BNO08x.hpp:263
+
258 // Which rotation vector to tare, BNO08x saves them seperately
+
259 static const constexpr uint8_t TARE_ROTATION_VECTOR = 0;
+
260 static const constexpr uint8_t TARE_GAME_ROTATION_VECTOR = 1;
+
261 static const constexpr uint8_t TARE_GEOMAGNETIC_ROTATION_VECTOR = 2;
+
262 static const constexpr uint8_t TARE_GYRO_INTEGRATED_ROTATION_VECTOR = 3;
+
263 static const constexpr uint8_t TARE_AR_VR_STABILIZED_ROTATION_VECTOR = 4;
+
264 static const constexpr uint8_t TARE_AR_VR_STABILIZED_GAME_ROTATION_VECTOR = 5;
+
265
+
266 static const constexpr int16_t ROTATION_VECTOR_Q1 = 14;
+
267 static const constexpr int16_t ROTATION_VECTOR_ACCURACY_Q1 = 12;
+
268 static const constexpr int16_t ACCELEROMETER_Q1 = 8;
+
269 static const constexpr int16_t LINEAR_ACCELEROMETER_Q1 = 8;
+
270 static const constexpr int16_t GYRO_Q1 = 9;
+
271 static const constexpr int16_t MAGNETOMETER_Q1 = 4;
+
272 static const constexpr int16_t ANGULAR_VELOCITY_Q1 = 10;
+
273 static const constexpr int16_t GRAVITY_Q1 = 8;
+
274
+
275 private:
+
276 bool wait_for_device_int();
+
277 bool receive_packet();
+
278 void send_packet();
+
279 void queue_packet(uint8_t channel_number, uint8_t data_length);
+
280 void queue_command(uint8_t command);
+
281 void queue_feature_command(uint8_t report_ID, uint16_t time_between_reports);
+
282 void queue_feature_command(uint8_t report_ID, uint16_t time_between_reports, uint32_t specific_config);
+
283 void queue_calibrate_command(uint8_t _to_calibrate);
+
284 void queue_tare_command(uint8_t command, uint8_t axis = TARE_AXIS_ALL, uint8_t rotation_vector_basis = TARE_ROTATION_VECTOR);
+ +
286
+ +
288
+
289 volatile uint8_t
+ +
291 SemaphoreHandle_t tx_semaphore;
+
292 SemaphoreHandle_t
+ +
294 uint8_t rx_buffer[300];
+
295 uint8_t tx_buffer[50];
+
296 uint8_t packet_header_rx[4];
+
297 uint8_t commands[20];
+
298 uint8_t sequence_number[6];
+
299 uint32_t meta_data[9];
+ +
301 uint16_t packet_length_tx = 0;
+
302 uint16_t packet_length_rx = 0;
+
303
+ +
305 spi_bus_config_t bus_config{};
+
306 spi_device_interface_config_t imu_spi_config{};
+
307 spi_device_handle_t spi_hdl{};
+
308 spi_transaction_t spi_transaction{};
+
309
+
310 // These are the raw sensor values (without Q applied) pulled from the user requested Input Report
+
311 uint32_t time_stamp;
+ + + + + + + + + + + + + + + +
327 uint8_t tap_detector;
+
328 uint16_t step_count;
+ + + + + + + + + + +
339
+
340 // spi task
+
341 TaskHandle_t spi_task_hdl;
+
342 static void spi_task_trampoline(void* arg);
+
343 void spi_task();
+
344
+
345 static void IRAM_ATTR hint_handler(void* arg);
+
346 static bool
+ +
348
+
349 static const constexpr uint64_t HOST_INT_TIMEOUT_MS =
+
350 150ULL;
+
351
+
352 // Higher level calibration commands, used by queue_calibrate_command
+
353 static const constexpr uint8_t CALIBRATE_ACCEL = 0;
+
354 static const constexpr uint8_t CALIBRATE_GYRO = 1;
+
355 static const constexpr uint8_t CALIBRATE_MAG = 2;
+
356 static const constexpr uint8_t CALIBRATE_PLANAR_ACCEL = 3;
+
357 static const constexpr uint8_t CALIBRATE_ACCEL_GYRO_MAG =
+
358 4;
+
359 static const constexpr uint8_t CALIBRATE_STOP = 5;
+
360
+
361 // Command IDs (see Ref. Manual 6.4)
+
362 static const constexpr uint8_t COMMAND_ERRORS = 1;
+
363 static const constexpr uint8_t COMMAND_COUNTER = 2;
+
364 static const constexpr uint8_t COMMAND_TARE = 3;
+
365 static const constexpr uint8_t COMMAND_INITIALIZE = 4;
+
366 static const constexpr uint8_t COMMAND_DCD = 6;
+
367 static const constexpr uint8_t COMMAND_ME_CALIBRATE = 7;
+
368 static const constexpr uint8_t COMMAND_DCD_PERIOD_SAVE = 9;
+
369 static const constexpr uint8_t COMMAND_OSCILLATOR = 10;
+
370 static const constexpr uint8_t COMMAND_CLEAR_DCD = 11;
+
371
+
372 // SHTP channel 2 control report IDs, used in communication with sensor (See Ref. Manual 6.2)
+
373 static const constexpr uint8_t SHTP_REPORT_COMMAND_RESPONSE = 0xF1;
+
374 static const constexpr uint8_t SHTP_REPORT_COMMAND_REQUEST = 0xF2;
+
375 static const constexpr uint8_t SHTP_REPORT_FRS_READ_RESPONSE = 0xF3;
+
376 static const constexpr uint8_t SHTP_REPORT_FRS_READ_REQUEST = 0xF4;
+
377 static const constexpr uint8_t SHTP_REPORT_PRODUCT_ID_RESPONSE = 0xF8;
+
378 static const constexpr uint8_t SHTP_REPORT_PRODUCT_ID_REQUEST = 0xF9;
+
379 static const constexpr uint8_t SHTP_REPORT_BASE_TIMESTAMP = 0xFB;
+
380 static const constexpr uint8_t SHTP_REPORT_SET_FEATURE_COMMAND = 0xFD;
+
381
+
382 // Sensor report IDs, used when enabling and reading BNO08x reports
+
383 static const constexpr uint8_t SENSOR_REPORTID_ACCELEROMETER = 0x01;
+
384 static const constexpr uint8_t SENSOR_REPORTID_GYROSCOPE = 0x02;
+
385 static const constexpr uint8_t SENSOR_REPORTID_MAGNETIC_FIELD = 0x03;
+
386 static const constexpr uint8_t SENSOR_REPORTID_LINEAR_ACCELERATION = 0x04;
+
387 static const constexpr uint8_t SENSOR_REPORTID_ROTATION_VECTOR = 0x05;
+
388 static const constexpr uint8_t SENSOR_REPORTID_GRAVITY = 0x06;
+
389 static const constexpr uint8_t SENSOR_REPORTID_UNCALIBRATED_GYRO = 0x07;
+
390 static const constexpr uint8_t SENSOR_REPORTID_GAME_ROTATION_VECTOR = 0x08;
+
391 static const constexpr uint8_t SENSOR_REPORTID_GEOMAGNETIC_ROTATION_VECTOR = 0x09;
+
392 static const constexpr uint8_t SENSOR_REPORTID_GYRO_INTEGRATED_ROTATION_VECTOR = 0x2A;
+
393 static const constexpr uint8_t SENSOR_REPORTID_TAP_DETECTOR = 0x10;
+
394 static const constexpr uint8_t SENSOR_REPORTID_STEP_COUNTER = 0x11;
+
395 static const constexpr uint8_t SENSOR_REPORTID_STABILITY_CLASSIFIER = 0x13;
+
396 static const constexpr uint8_t SENSOR_REPORTID_RAW_ACCELEROMETER = 0x14;
+
397 static const constexpr uint8_t SENSOR_REPORTID_RAW_GYROSCOPE = 0x15;
+
398 static const constexpr uint8_t SENSOR_REPORTID_RAW_MAGNETOMETER = 0x16;
+
399 static const constexpr uint8_t SENSOR_REPORTID_PERSONAL_ACTIVITY_CLASSIFIER = 0x1E;
+
400 static const constexpr uint8_t SENSOR_REPORTID_AR_VR_STABILIZED_ROTATION_VECTOR = 0x28;
+
401 static const constexpr uint8_t SENSOR_REPORTID_AR_VR_STABILIZED_GAME_ROTATION_VECTOR = 0x29;
+
402
+
403 // Tare commands used by queue_tare_command
+
404 static const constexpr uint8_t TARE_NOW = 0;
+
405 static const constexpr uint8_t TARE_PERSIST = 1;
+
406 static const constexpr uint8_t TARE_SET_REORIENTATION = 2;
+
407
+
408 static const constexpr char* TAG = "BNO08x";
+
409};
+
+
struct bno08x_config_t bno08x_config_t
IMU configuration settings passed into constructor.
+
channels_t
SHTP protocol channels.
Definition BNO08x.hpp:20
+
@ CHANNEL_COMMAND
Definition BNO08x.hpp:21
+
@ CHANNEL_REPORTS
Definition BNO08x.hpp:24
+
@ CHANNEL_CONTROL
Definition BNO08x.hpp:23
+
@ CHANNEL_EXECUTABLE
Definition BNO08x.hpp:22
+
@ CHANNEL_WAKE_REPORTS
Definition BNO08x.hpp:25
+
@ CHANNEL_GYRO
Definition BNO08x.hpp:26
+
IMUAccuracy
Sensor accuracy returned during sensor calibration.
Definition BNO08x.hpp:31
+ + + +
Definition BNO08x.hpp:104
+
static const constexpr uint8_t SENSOR_REPORTID_PERSONAL_ACTIVITY_CLASSIFIER
See SH2 Ref. Manual 6.5.36.
Definition BNO08x.hpp:399
+
static const constexpr uint8_t SHTP_REPORT_PRODUCT_ID_RESPONSE
See SH2 Ref. Manual 6.3.2.
Definition BNO08x.hpp:377
+
uint16_t raw_quat_radian_accuracy
Definition BNO08x.hpp:317
+
uint16_t raw_gyro_Z
Definition BNO08x.hpp:316
+
void enable_ARVR_stabilized_rotation_vector(uint16_t time_between_reports)
Sends command to enable ARVR stabilized rotation vector reports (See Ref. Manual 6....
Definition BNO08x.cpp:1028
+
static const constexpr int16_t ACCELEROMETER_Q1
Acceleration Q point (See SH-2 Ref. Manual 6.5.9)
Definition BNO08x.hpp:268
+
uint16_t uncalib_gyro_accuracy
Uncalibrated gyro reading (See SH-2 Ref. Manual 6.5.14)
Definition BNO08x.hpp:324
+
void print_header()
Prints the most recently received SHTP header to serial console with ESP_LOG statement.
Definition BNO08x.cpp:2078
+
void enable_activity_classifier(uint16_t time_between_reports, uint32_t activities_to_enable, uint8_t(&activity_confidence_vals)[9])
Sends command to enable activity classifier reports (See Ref. Manual 6.5.36)
Definition BNO08x.cpp:1186
+
uint16_t raw_bias_Z
Definition BNO08x.hpp:323
+
void enable_gyro_integrated_rotation_vector(uint16_t timeBetweenReports)
Sends command to enable gyro integrated rotation vector reports (See Ref. Manual 6....
Definition BNO08x.cpp:1054
+
static const constexpr uint8_t SENSOR_REPORTID_AR_VR_STABILIZED_GAME_ROTATION_VECTOR
See SH2 Ref. Manual 6.5.43.
Definition BNO08x.hpp:401
+
static const constexpr uint8_t COMMAND_TARE
Command and response to tare command (See Sh2 Ref. Manual 6.4.4)
Definition BNO08x.hpp:364
+
float get_accel_Z()
Get z axis acceleration (total acceleration of device, units in m/s^2).
Definition BNO08x.cpp:1660
+
float get_uncalibrated_gyro_Z()
Get uncalibrated gyro Z axis angular velocity measurement.
Definition BNO08x.cpp:1931
+
static const constexpr int16_t ROTATION_VECTOR_Q1
Rotation vector Q point (See SH-2 Ref. Manual 6.5.18)
Definition BNO08x.hpp:266
+
static void spi_task_trampoline(void *arg)
Static function used to launch spi task.
Definition BNO08x.cpp:2416
+
int8_t get_stability_classifier()
Get the current stability classifier (Seee Ref. Manual 6.5.31)
Definition BNO08x.cpp:2049
+
void send_packet()
Sends a queued SHTP packet via SPI.
Definition BNO08x.cpp:413
+
void print_packet()
Definition BNO08x.cpp:2099
+
float get_range(uint16_t record_ID)
Gets range from BNO08x FRS (flash record system).
Definition BNO08x.cpp:2210
+
float get_linear_accel_Y()
Get y axis linear acceleration (acceleration of device minus gravity, units in m/s^2)
Definition BNO08x.cpp:1708
+
float get_magf_X()
Get X component of magnetic field vector.
Definition BNO08x.cpp:1321
+
static const constexpr uint8_t TARE_PERSIST
See SH2 Ref. Manual 6.4.4.2.
Definition BNO08x.hpp:405
+
uint8_t tap_detector
Tap detector reading (See SH-2 Ref. Manual 6.5.27)
Definition BNO08x.hpp:327
+
uint8_t get_reset_reason()
Get the reason for the most recent reset.
Definition BNO08x.cpp:264
+
float get_quat_I()
Get I component of reported quaternion.
Definition BNO08x.cpp:1557
+
int16_t get_Q3(uint16_t record_ID)
Gets Q3 point from BNO08x FRS (flash record system).
Definition BNO08x.cpp:2180
+
float get_gyro_calibrated_velocity_Z()
Get calibrated gyro z axis angular velocity measurement.
Definition BNO08x.cpp:1866
+
void queue_command(uint8_t command)
Queues a packet containing a command.
Definition BNO08x.cpp:436
+
bool mode_sleep()
Puts BNO08x sensor into sleep/low power mode using executable channel.
Definition BNO08x.cpp:310
+
float get_uncalibrated_gyro_Y()
Get uncalibrated gyro Y axis angular velocity measurement.
Definition BNO08x.cpp:1921
+
uint16_t raw_gyro_X
Definition BNO08x.hpp:316
+
uint8_t stability_classifier
Stability status reading (See SH-2 Ref. Manual 6.5.31)
Definition BNO08x.hpp:329
+
float get_pitch()
Get the reported rotation about y axis.
Definition BNO08x.cpp:1449
+
void get_uncalibrated_gyro(float &x, float &y, float &z, float &bx, float &by, float &bz, uint8_t &accuracy)
Get full rotational velocity without drift compensation (units in Rad/s). An estimate of drift is giv...
Definition BNO08x.cpp:1895
+
void calibrate_planar_accelerometer()
Sends command to calibrate planar accelerometer.
Definition BNO08x.cpp:510
+
static const constexpr uint8_t SHTP_REPORT_SET_FEATURE_COMMAND
See SH2 Ref. Manual 6.5.4.
Definition BNO08x.hpp:380
+
void enable_accelerometer(uint16_t time_between_reports)
Sends command to enable accelerometer reports (See Ref. Manual 6.5.9)
Definition BNO08x.cpp:1067
+
float get_resolution(uint16_t record_ID)
Gets resolution from BNO08x FRS (flash record system).
Definition BNO08x.cpp:2193
+
int16_t get_raw_accel_X()
Get raw accelerometer x axis reading from physical accelerometer MEMs sensor (See Ref....
Definition BNO08x.cpp:1738
+
static const constexpr uint8_t SHTP_REPORT_COMMAND_RESPONSE
See SH2 Ref. Manual 6.3.9.
Definition BNO08x.hpp:373
+
static const constexpr uint8_t TARE_AXIS_ALL
Tare all axes (used with tare now command)
Definition BNO08x.hpp:255
+
static const constexpr uint8_t TARE_GEOMAGNETIC_ROTATION_VECTOR
tare geomagnetic rotation vector
Definition BNO08x.hpp:261
+
uint8_t get_quat_accuracy()
Get accuracy of reported quaternion.
Definition BNO08x.cpp:1612
+
static const constexpr uint8_t SENSOR_REPORTID_AR_VR_STABILIZED_ROTATION_VECTOR
See SH2 Ref. Manual 6.5.42.
Definition BNO08x.hpp:400
+
static const constexpr uint8_t TARE_NOW
See SH2 Ref. Manual 6.4.4.1.
Definition BNO08x.hpp:404
+
uint32_t FRS_read_word(uint16_t record_ID, uint8_t word_number)
Reads meta data word from BNO08x FRS (flash record system) given the record ID and word number....
Definition BNO08x.cpp:2231
+
float q_to_float(int16_t fixed_point_value, uint8_t q_point)
Converts a register value to a float using its associated Q point. (See https://en....
Definition BNO08x.cpp:1281
+
float get_uncalibrated_gyro_X()
Get uncalibrated gyro x axis angular velocity measurement.
Definition BNO08x.cpp:1911
+
bool hard_reset()
Hard resets BNO08x sensor.
Definition BNO08x.cpp:216
+
static const constexpr uint8_t SENSOR_REPORTID_GYROSCOPE
See SH2 Ref. Manual 6.5.13.
Definition BNO08x.hpp:384
+
int16_t get_raw_magf_Y()
Get raw magnetometer y axis reading from physical magnetometer sensor (See Ref. Manual 6....
Definition BNO08x.cpp:1808
+
static const constexpr char * TAG
Class tag used for serial print statements.
Definition BNO08x.hpp:408
+
void enable_gravity(uint16_t time_between_reports)
Sends command to enable gravity reading reports (See Ref. Manual 6.5.11)
Definition BNO08x.cpp:1093
+
int16_t get_raw_gyro_Z()
Get raw gyroscope z axis reading from physical gyroscope MEMs sensor (See Ref. Manual 6....
Definition BNO08x.cpp:1788
+
void spi_task()
Task responsible for SPI transactions. Executed when HINT in is asserted by BNO08x.
Definition BNO08x.cpp:2427
+
static const constexpr uint8_t COMMAND_OSCILLATOR
Retrieve oscillator type command (See SH2 Ref. Manual 6.4)
Definition BNO08x.hpp:369
+
static const constexpr uint8_t COMMAND_INITIALIZE
Reinitialize sensor hub components See (SH2 Ref. Manual 6.4.5)
Definition BNO08x.hpp:365
+
static const constexpr uint8_t TARE_AR_VR_STABILIZED_ROTATION_VECTOR
Tare ARVR stabilized rotation vector.
Definition BNO08x.hpp:263
+
uint8_t get_uncalibrated_gyro_accuracy()
Get uncalibrated gyro accuracy.
Definition BNO08x.cpp:1971
+
uint16_t accel_accuracy
Raw acceleration readings (See SH-2 Ref. Manual 6.5.8)
Definition BNO08x.hpp:313
+
SemaphoreHandle_t int_asserted_semaphore
Binary semaphore used to synchronize spi_task() calling wait_for_device_int(), given after hint_handl...
Definition BNO08x.hpp:293
+
uint8_t get_linear_accel_accuracy()
Get accuracy of linear acceleration.
Definition BNO08x.cpp:1728
+
void get_magf(float &x, float &y, float &z, uint8_t &accuracy)
Get the full magnetic field vector.
Definition BNO08x.cpp:1308
+
uint16_t accel_lin_accuracy
Raw linear acceleration (See SH-2 Ref. Manual 6.5.10)
Definition BNO08x.hpp:315
+
uint16_t quat_accuracy
Raw quaternion reading (See SH-2 Ref. Manual 6.5.44)
Definition BNO08x.hpp:318
bool data_available()
Checks if BNO08x has asserted interrupt and sent data.
Definition BNO08x.cpp:725
-
uint16_t parse_command_report()
Parses received command report sent by BNO08x (See Ref. Manual 6.3.9)
Definition BNO08x.cpp:966
-
void get_gravity(float &x, float &y, float &z, uint8_t &accuracy)
Get full reported gravity vector, units in m/s^2.
Definition BNO08x.cpp:1362
-
uint8_t get_accel_accuracy()
Get accuracy of linear acceleration.
Definition BNO08x.cpp:1666
-
bool FRS_read_data(uint16_t record_ID, uint8_t start_location, uint8_t words_to_read)
Read meta data from BNO08x FRS (flash record system) given the record ID. Contains Q points and other...
Definition BNO08x.cpp:2286
-
spi_device_interface_config_t imu_spi_config
SPI slave device settings.
Definition BNO08x.hpp:254
-
static const constexpr uint8_t SENSOR_REPORTID_TAP_DETECTOR
See SH2 Ref. Manual 6.5.27.
Definition BNO08x.hpp:340
-
int16_t get_Q1(uint16_t record_ID)
Gets Q1 point from BNO08x FRS (flash record system).
Definition BNO08x.cpp:2158
-
void tare_now(uint8_t axis_sel=TARE_AXIS_ALL, uint8_t rotation_vector_basis=TARE_ROTATION_VECTOR)
Sends command to tare an axis (See Ref. Manual 6.4.4.1)
Definition BNO08x.cpp:1234
-
static const constexpr uint8_t SENSOR_REPORTID_ACCELEROMETER
See SH2 Ref. Manual 6.5.9.
Definition BNO08x.hpp:330
-
uint8_t get_tap_detector()
Get if tap has occured.
Definition BNO08x.cpp:2023
-
uint8_t get_magf_accuracy()
Get accuracy of reported magnetic field vector.
Definition BNO08x.cpp:1347
-
static bool isr_service_installed
true of the isr service has been installed, only has to be done once regardless of how many devices a...
Definition BNO08x.hpp:285
-
volatile bool int_asserted
Interrupt asserted flag, sets true after hint_handler ISR launches SPI task and it has run to complet...
Definition BNO08x.hpp:283
-
void queue_tare_command(uint8_t command, uint8_t axis=TARE_AXIS_ALL, uint8_t rotation_vector_basis=TARE_ROTATION_VECTOR)
Queues a packet containing a command related to zeroing sensor's axes. (See Ref. Manual 6....
Definition BNO08x.cpp:2385
-
void get_gyro_calibrated_velocity(float &x, float &y, float &z, uint8_t &accuracy)
Get full rotational velocity with drift compensation (units in Rad/s).
Definition BNO08x.cpp:1829
-
static const constexpr uint8_t COMMAND_CLEAR_DCD
Clear DCD & Reset command (See SH2 Ref. Manual 6.4)
Definition BNO08x.hpp:316
-
uint8_t get_activity_classifier()
Get the current activity classifier (Seee Ref. Manual 6.5.36)
Definition BNO08x.cpp:2064
-
float get_uncalibrated_gyro_bias_Z()
Get uncalibrated gyro Z axis drift estimate.
Definition BNO08x.cpp:1956
-
void get_quat(float &i, float &j, float &k, float &real, float &rad_accuracy, uint8_t &accuracy)
Get the full quaternion reading.
Definition BNO08x.cpp:1538
-
void enable_stability_classifier(uint16_t time_between_reports)
Sends command to enable activity stability classifier reports (See Ref. Manual 6.5....
Definition BNO08x.cpp:1165
-
static const constexpr uint8_t SENSOR_REPORTID_LINEAR_ACCELERATION
See SH2 Ref. Manual 6.5.10.
Definition BNO08x.hpp:333
-
static const constexpr uint64_t HOST_INT_TIMEOUT_US
Max wait between HINT being asserted by BNO08x before transaction is considered failed.
Definition BNO08x.hpp:297
-
static const constexpr uint8_t SHTP_REPORT_PRODUCT_ID_REQUEST
See SH2 Ref. Manual 6.3.1.
Definition BNO08x.hpp:324
-
float get_gravity_Z()
Get the reported z axis gravity.
Definition BNO08x.cpp:1395
-
static const constexpr uint8_t CALIBRATE_STOP
Stop calibration command used by queue_calibrate_command.
Definition BNO08x.hpp:305
-
uint16_t mems_raw_accel_Z
Raw accelerometer readings from MEMS sensor (See SH2 Ref. Manual 6.5.8)
Definition BNO08x.hpp:274
-
static const constexpr uint8_t TARE_SET_REORIENTATION
See SH2 Ref. Manual 6.4.4.3.
Definition BNO08x.hpp:353
-
float get_quat_real()
Get real component of reported quaternion.
Definition BNO08x.cpp:1586
-
volatile uint8_t tx_packet_queued
Whether or not a packet is currently waiting to be sent, a queued packet is sent on assertion of BNO0...
Definition BNO08x.hpp:240
-
TaskHandle_t spi_task_hdl
SPI task handle.
Definition BNO08x.hpp:279
-
float get_quat_radian_accuracy()
Get radian accuracy of reported quaternion.
Definition BNO08x.cpp:1597
-
static bno08x_config_t default_imu_config
default imu config settings
Definition BNO08x.hpp:238
-
void enable_game_rotation_vector(uint16_t time_between_reports)
Sends command to enable game rotation vector reports (See Ref. Manual 6.5.19)
Definition BNO08x.cpp:996
-
float get_yaw()
Get the reported rotation about z axis.
Definition BNO08x.cpp:1473
-
void queue_packet(uint8_t channel_number, uint8_t data_length)
Queues an SHTP packet to be sent via SPI.
Definition BNO08x.cpp:390
-
void queue_feature_command(uint8_t report_ID, uint16_t time_between_reports)
Queues a packet containing a command with a request for sensor reports, reported periodically....
Definition BNO08x.cpp:2409
-
static const constexpr uint8_t SENSOR_REPORTID_MAGNETIC_FIELD
See SH2 Ref. Manual 6.5.16.
Definition BNO08x.hpp:332
-
uint16_t packet_length_tx
Packet length to be sent with send_packet()
Definition BNO08x.hpp:249
-
float get_roll_deg()
Get the reported rotation about x axis.
Definition BNO08x.cpp:1500
-
int16_t get_raw_accel_Z()
Get raw accelerometer z axis reading from physical accelerometer MEMs sensor (See Ref....
Definition BNO08x.cpp:1754
-
bool calibration_complete()
Returns true if calibration has completed.
Definition BNO08x.cpp:597
-
float get_uncalibrated_gyro_bias_Y()
Get uncalibrated gyro Y axis drift estimate.
Definition BNO08x.cpp:1946
-
static const constexpr uint8_t SHTP_REPORT_FRS_READ_REQUEST
See SH2 Ref. Manual 6.3.6.
Definition BNO08x.hpp:322
-
uint8_t tx_buffer[50]
buffer used for sending packet with send_packet()
Definition BNO08x.hpp:243
-
uint8_t activity_classifier
Activity status reading (See SH-2 Ref. Manual 6.5.36)
Definition BNO08x.hpp:271
-
void enable_gyro(uint16_t time_between_reports)
Sends command to enable gyro reports (See Ref. Manual 6.5.13)
Definition BNO08x.cpp:1100
-
float get_linear_accel_X()
Get x axis linear acceleration (acceleration of device minus gravity, units in m/s^2)
Definition BNO08x.cpp:1694
-
static const constexpr uint8_t COMMAND_DCD_PERIOD_SAVE
Configure DCD periodic saving (See SH2 Ref. Manual 6.4)
Definition BNO08x.hpp:314
-
uint8_t rx_buffer[300]
buffer used to receive packet with receive_packet()
Definition BNO08x.hpp:242
-
uint16_t parse_input_report()
Parses received input report sent by BNO08x.
Definition BNO08x.cpp:788
-
uint32_t meta_data[9]
First 9 bytes of meta data returned from FRS read operation (we don't really need the rest) (See Ref....
Definition BNO08x.hpp:247
-
static void IRAM_ATTR hint_handler(void *arg)
HINT interrupt service routine, handles falling edge of BNO08x HINT pin.
Definition BNO08x.cpp:2457
-
uint8_t get_gyro_accuracy()
Get calibrated gyro accuracy.
Definition BNO08x.cpp:1872
-
float get_magf_Y()
Get Y component of magnetic field vector.
Definition BNO08x.cpp:1325
-
static const constexpr uint8_t COMMAND_ME_CALIBRATE
Command and response to configure ME calibration (See SH2 Ref. Manual 6.4.7)
Definition BNO08x.hpp:313
-
float get_gravity_X()
Get the reported x axis gravity.
Definition BNO08x.cpp:1375
-
float get_roll()
Get the reported rotation about x axis.
Definition BNO08x.cpp:1415
-
float get_gravity_Y()
Get the reported y axis gravity.
Definition BNO08x.cpp:1385
-
static const constexpr uint8_t SENSOR_REPORTID_GYRO_INTEGRATED_ROTATION_VECTOR
See SH2 Ref. Manual 6.5.44.
Definition BNO08x.hpp:339
-
static const constexpr uint8_t TARE_ROTATION_VECTOR
Tare rotation vector.
Definition BNO08x.hpp:359
-
uint8_t packet_header_rx[4]
SHTP header received with receive_packet()
Definition BNO08x.hpp:244
-
uint16_t mems_raw_magf_Z
Raw magnetometer (compass) readings from MEMS sensor (See SH-2 Ref. Manual 6.5.15)
Definition BNO08x.hpp:276
-
void enable_tap_detector(uint16_t time_between_reports)
Sends command to enable tap detector reports (See Ref. Manual 6.5.27)
Definition BNO08x.cpp:1139
-
static const constexpr int16_t ROTATION_VECTOR_ACCURACY_Q1
Rotation vector accuracy estimate Q point (See SH-2 Ref. Manual 6.5.18)
Definition BNO08x.hpp:289
-
void get_accel(float &x, float &y, float &z, uint8_t &accuracy)
Get full acceleration (total acceleration of device, units in m/s^2).
Definition BNO08x.cpp:1623
-
int16_t get_Q2(uint16_t record_ID)
Gets Q2 point from BNO08x FRS (flash record system).
Definition BNO08x.cpp:2173
-
static const constexpr uint8_t CALIBRATE_PLANAR_ACCEL
Calibrate planar acceleration command used by queue_calibrate_command.
Definition BNO08x.hpp:303
-
int16_t get_raw_accel_Y()
Get raw accelerometer y axis reading from physical accelerometer MEMs sensor (See Ref....
Definition BNO08x.cpp:1744
-
bool soft_reset()
Soft resets BNO08x sensor using executable channel.
Definition BNO08x.cpp:247
-
spi_bus_config_t bus_config
SPI bus GPIO configuration settings.
Definition BNO08x.hpp:253
-
bool wait_for_device_int()
Re-enables interrupts and waits for BNO08x to assert HINT pin.
Definition BNO08x.cpp:191
-
uint16_t gyro_accuracy
Raw gyro reading (See SH-2 Ref. Manual 6.5.13)
Definition BNO08x.hpp:262
-
int16_t get_raw_magf_Z()
Get raw magnetometer z axis reading from physical magnetometer sensor (See Ref. Manual 6....
Definition BNO08x.cpp:1814
-
void calibrate_gyro()
Sends command to calibrate gyro.
Definition BNO08x.cpp:494
+
uint16_t parse_command_report()
Parses received command report sent by BNO08x (See Ref. Manual 6.3.9)
Definition BNO08x.cpp:972
+
static const constexpr uint8_t COMMAND_ERRORS
Definition BNO08x.hpp:362
+
void get_gravity(float &x, float &y, float &z, uint8_t &accuracy)
Get full reported gravity vector, units in m/s^2.
Definition BNO08x.cpp:1369
+
uint16_t mems_raw_gyro_X
Definition BNO08x.hpp:335
+
uint8_t get_accel_accuracy()
Get accuracy of linear acceleration.
Definition BNO08x.cpp:1670
+
bool FRS_read_data(uint16_t record_ID, uint8_t start_location, uint8_t words_to_read)
Read meta data from BNO08x FRS (flash record system) given the record ID. Contains Q points and other...
Definition BNO08x.cpp:2281
+
BNO08x(bno08x_config_t imu_config=default_imu_config)
BNO08x imu constructor.
Definition BNO08x.cpp:15
+
spi_device_interface_config_t imu_spi_config
SPI slave device settings.
Definition BNO08x.hpp:306
+
static const constexpr uint8_t SENSOR_REPORTID_TAP_DETECTOR
See SH2 Ref. Manual 6.5.27.
Definition BNO08x.hpp:393
+
int16_t get_Q1(uint16_t record_ID)
Gets Q1 point from BNO08x FRS (flash record system).
Definition BNO08x.cpp:2150
+
void tare_now(uint8_t axis_sel=TARE_AXIS_ALL, uint8_t rotation_vector_basis=TARE_ROTATION_VECTOR)
Sends command to tare an axis (See Ref. Manual 6.4.4.1)
Definition BNO08x.cpp:1241
+
static const constexpr uint8_t SENSOR_REPORTID_ACCELEROMETER
See SH2 Ref. Manual 6.5.9.
Definition BNO08x.hpp:383
+
uint8_t get_tap_detector()
Get if tap has occured.
Definition BNO08x.cpp:2027
+
uint8_t get_magf_accuracy()
Get accuracy of reported magnetic field vector.
Definition BNO08x.cpp:1354
+
static bool isr_service_installed
true of the isr service has been installed, only has to be done once regardless of how many devices a...
Definition BNO08x.hpp:3
+
void queue_tare_command(uint8_t command, uint8_t axis=TARE_AXIS_ALL, uint8_t rotation_vector_basis=TARE_ROTATION_VECTOR)
Queues a packet containing a command related to zeroing sensor's axes. (See Ref. Manual 6....
Definition BNO08x.cpp:2380
+
void get_gyro_calibrated_velocity(float &x, float &y, float &z, uint8_t &accuracy)
Get full rotational velocity with drift compensation (units in Rad/s).
Definition BNO08x.cpp:1833
+
uint16_t raw_velocity_gyro_Y
Definition BNO08x.hpp:319
+
static const constexpr uint8_t COMMAND_CLEAR_DCD
Clear DCD & Reset command (See SH2 Ref. Manual 6.4)
Definition BNO08x.hpp:370
+
uint8_t get_activity_classifier()
Get the current activity classifier (Seee Ref. Manual 6.5.36)
Definition BNO08x.cpp:2068
+
float get_uncalibrated_gyro_bias_Z()
Get uncalibrated gyro Z axis drift estimate.
Definition BNO08x.cpp:1961
+
void get_quat(float &i, float &j, float &k, float &real, float &rad_accuracy, uint8_t &accuracy)
Get the full quaternion reading.
Definition BNO08x.cpp:1542
+
void enable_stability_classifier(uint16_t time_between_reports)
Sends command to enable activity stability classifier reports (See Ref. Manual 6.5....
Definition BNO08x.cpp:1171
+
static const constexpr uint8_t SENSOR_REPORTID_LINEAR_ACCELERATION
See SH2 Ref. Manual 6.5.10.
Definition BNO08x.hpp:386
+
static const constexpr uint8_t SHTP_REPORT_PRODUCT_ID_REQUEST
See SH2 Ref. Manual 6.3.1.
Definition BNO08x.hpp:378
+
float get_gravity_Z()
Get the reported z axis gravity.
Definition BNO08x.cpp:1402
+
static const constexpr uint8_t CALIBRATE_STOP
Stop calibration command used by queue_calibrate_command.
Definition BNO08x.hpp:359
+
static const constexpr uint16_t FRS_RECORDID_ROTATION_VECTOR
Definition BNO08x.hpp:253
+
uint16_t mems_raw_accel_Z
Raw accelerometer readings from MEMS sensor (See SH2 Ref. Manual 6.5.8)
Definition BNO08x.hpp:334
+
static const constexpr uint8_t TARE_SET_REORIENTATION
See SH2 Ref. Manual 6.4.4.3.
Definition BNO08x.hpp:406
+
float get_quat_real()
Get real component of reported quaternion.
Definition BNO08x.cpp:1590
+
volatile uint8_t tx_packet_queued
Whether or not a packet is currently waiting to be sent, a queued packet is sent on assertion of BNO0...
Definition BNO08x.hpp:290
+
TaskHandle_t spi_task_hdl
SPI task handle.
Definition BNO08x.hpp:341
+
uint16_t raw_quat_J
Definition BNO08x.hpp:317
+
float get_quat_radian_accuracy()
Get radian accuracy of reported quaternion.
Definition BNO08x.cpp:1601
+
uint16_t raw_gyro_Y
Definition BNO08x.hpp:316
+
static bno08x_config_t default_imu_config
default imu config settings
Definition BNO08x.hpp:287
+
void enable_game_rotation_vector(uint16_t time_between_reports)
Sends command to enable game rotation vector reports (See Ref. Manual 6.5.19)
Definition BNO08x.cpp:1002
+
float get_yaw()
Get the reported rotation about z axis.
Definition BNO08x.cpp:1478
+
void queue_packet(uint8_t channel_number, uint8_t data_length)
Queues an SHTP packet to be sent via SPI.
Definition BNO08x.cpp:383
+
uint16_t raw_quat_I
Definition BNO08x.hpp:317
+
void queue_feature_command(uint8_t report_ID, uint16_t time_between_reports)
Queues a packet containing a command with a request for sensor reports, reported periodically....
Definition BNO08x.cpp:2404
+
static const constexpr uint16_t FRS_RECORDID_GYROSCOPE_CALIBRATED
Definition BNO08x.hpp:251
+
static const constexpr uint8_t SENSOR_REPORTID_MAGNETIC_FIELD
See SH2 Ref. Manual 6.5.16.
Definition BNO08x.hpp:385
+
uint16_t packet_length_tx
Packet length to be sent with send_packet()
Definition BNO08x.hpp:301
+
float get_roll_deg()
Get the reported rotation about x axis.
Definition BNO08x.cpp:1505
+
int16_t get_raw_accel_Z()
Get raw accelerometer z axis reading from physical accelerometer MEMs sensor (See Ref....
Definition BNO08x.cpp:1758
+
bool calibration_complete()
Returns true if calibration has completed.
Definition BNO08x.cpp:587
+
static const constexpr uint16_t FRS_RECORDID_ACCELEROMETER
Definition BNO08x.hpp:250
+
float get_uncalibrated_gyro_bias_Y()
Get uncalibrated gyro Y axis drift estimate.
Definition BNO08x.cpp:1951
+
static const constexpr uint8_t SHTP_REPORT_FRS_READ_REQUEST
See SH2 Ref. Manual 6.3.6.
Definition BNO08x.hpp:376
+
uint8_t tx_buffer[50]
buffer used for sending packet with send_packet()
Definition BNO08x.hpp:295
+
uint8_t activity_classifier
Activity status reading (See SH-2 Ref. Manual 6.5.36)
Definition BNO08x.hpp:330
+
uint16_t raw_accel_X
Definition BNO08x.hpp:312
+
void enable_gyro(uint16_t time_between_reports)
Sends command to enable gyro reports (See Ref. Manual 6.5.13)
Definition BNO08x.cpp:1106
+
float get_linear_accel_X()
Get x axis linear acceleration (acceleration of device minus gravity, units in m/s^2)
Definition BNO08x.cpp:1698
+
uint16_t raw_quat_K
Definition BNO08x.hpp:317
+
static const constexpr uint8_t COMMAND_DCD_PERIOD_SAVE
Configure DCD periodic saving (See SH2 Ref. Manual 6.4)
Definition BNO08x.hpp:368
+
uint8_t rx_buffer[300]
buffer used to receive packet with receive_packet()
Definition BNO08x.hpp:294
+
uint16_t parse_input_report()
Parses received input report sent by BNO08x.
Definition BNO08x.cpp:791
+
uint32_t meta_data[9]
First 9 bytes of meta data returned from FRS read operation (we don't really need the rest) (See Ref....
Definition BNO08x.hpp:299
+
static void IRAM_ATTR hint_handler(void *arg)
HINT interrupt service routine, handles falling edge of BNO08x HINT pin.
Definition BNO08x.cpp:2451
+
uint8_t get_gyro_accuracy()
Get calibrated gyro accuracy.
Definition BNO08x.cpp:1876
+
float get_magf_Y()
Get Y component of magnetic field vector.
Definition BNO08x.cpp:1332
+
static const constexpr uint8_t COMMAND_ME_CALIBRATE
Command and response to configure ME calibration (See SH2 Ref. Manual 6.4.7)
Definition BNO08x.hpp:367
+
uint16_t raw_quat_real
Definition BNO08x.hpp:317
+
float get_gravity_X()
Get the reported x axis gravity.
Definition BNO08x.cpp:1382
+
float get_roll()
Get the reported rotation about x axis.
Definition BNO08x.cpp:1422
+
uint16_t raw_bias_X
Definition BNO08x.hpp:323
+
float get_gravity_Y()
Get the reported y axis gravity.
Definition BNO08x.cpp:1392
+
static const constexpr uint8_t SENSOR_REPORTID_GYRO_INTEGRATED_ROTATION_VECTOR
See SH2 Ref. Manual 6.5.44.
Definition BNO08x.hpp:392
+
static const constexpr uint8_t TARE_ROTATION_VECTOR
Tare rotation vector.
Definition BNO08x.hpp:259
+
uint8_t packet_header_rx[4]
SHTP header received with receive_packet()
Definition BNO08x.hpp:296
+
uint16_t mems_raw_magf_Z
Raw magnetometer (compass) readings from MEMS sensor (See SH-2 Ref. Manual 6.5.15)
Definition BNO08x.hpp:338
+
void enable_tap_detector(uint16_t time_between_reports)
Sends command to enable tap detector reports (See Ref. Manual 6.5.27)
Definition BNO08x.cpp:1145
+
static const constexpr int16_t ROTATION_VECTOR_ACCURACY_Q1
Rotation vector accuracy estimate Q point (See SH-2 Ref. Manual 6.5.18)
Definition BNO08x.hpp:267
+
void get_accel(float &x, float &y, float &z, uint8_t &accuracy)
Get full acceleration (total acceleration of device, units in m/s^2).
Definition BNO08x.cpp:1627
+
uint16_t mems_raw_accel_X
Definition BNO08x.hpp:333
+
static const constexpr uint8_t COMMAND_COUNTER
Definition BNO08x.hpp:363
+
int16_t get_Q2(uint16_t record_ID)
Gets Q2 point from BNO08x FRS (flash record system).
Definition BNO08x.cpp:2165
+
static const constexpr uint8_t CALIBRATE_PLANAR_ACCEL
Calibrate planar acceleration command used by queue_calibrate_command.
Definition BNO08x.hpp:356
+
int16_t get_raw_accel_Y()
Get raw accelerometer y axis reading from physical accelerometer MEMs sensor (See Ref....
Definition BNO08x.cpp:1748
+
bool soft_reset()
Soft resets BNO08x sensor using executable channel.
Definition BNO08x.cpp:241
+
spi_bus_config_t bus_config
SPI bus GPIO configuration settings.
Definition BNO08x.hpp:305
+
bool wait_for_device_int()
Re-enables interrupts and waits for BNO08x to assert HINT pin.
Definition BNO08x.cpp:192
+
uint16_t gyro_accuracy
Raw gyro reading (See SH-2 Ref. Manual 6.5.13)
Definition BNO08x.hpp:316
+
int16_t get_raw_magf_Z()
Get raw magnetometer z axis reading from physical magnetometer sensor (See Ref. Manual 6....
Definition BNO08x.cpp:1818
+
void calibrate_gyro()
Sends command to calibrate gyro.
Definition BNO08x.cpp:486
uint16_t get_readings()
Waits for BNO08x HINT pin to assert, and parses the received data.
Definition BNO08x.cpp:735
-
static const constexpr uint8_t TARE_GYRO_INTEGRATED_ROTATION_VECTOR
Tare gyro integrated rotation vector.
Definition BNO08x.hpp:362
-
float get_quat_K()
Get K component of reported quaternion.
Definition BNO08x.cpp:1575
-
float get_quat_J()
Get J component of reported quaternion.
Definition BNO08x.cpp:1564
-
static const constexpr int16_t MAGNETOMETER_Q1
Magnetometer Q point (See SH-2 Ref. Manual 6.5.16)
Definition BNO08x.hpp:293
-
void save_calibration()
Sends command to save internal calibration data (See Ref. Manual 6.4.7).
Definition BNO08x.cpp:622
-
static const constexpr int16_t GYRO_Q1
Gyro Q point (See SH-2 Ref. Manual 6.5.13)
Definition BNO08x.hpp:292
-
uint8_t sequence_number[6]
Sequence num of each com channel, 6 in total.
Definition BNO08x.hpp:246
-
static const constexpr uint8_t SENSOR_REPORTID_RAW_ACCELEROMETER
See SH2 Ref. Manual 6.5.8.
Definition BNO08x.hpp:343
-
static const constexpr uint8_t SENSOR_REPORTID_RAW_GYROSCOPE
See SH2 Ref. Manual 6.5.12.
Definition BNO08x.hpp:344
-
static const constexpr int16_t ANGULAR_VELOCITY_Q1
Angular velocity Q point (See SH-2 Ref. Manual 6.5.44)
Definition BNO08x.hpp:294
-
static const constexpr uint8_t SENSOR_REPORTID_STEP_COUNTER
See SH2 Ref. Manual 6.5.29.
Definition BNO08x.hpp:341
-
static const constexpr uint8_t SENSOR_REPORTID_ROTATION_VECTOR
See SH2 Ref. Manual 6.5.18.
Definition BNO08x.hpp:334
-
static const constexpr uint8_t SHTP_REPORT_COMMAND_REQUEST
See SH2 Ref. Manual 6.3.8.
Definition BNO08x.hpp:320
-
static const constexpr uint8_t SENSOR_REPORTID_GAME_ROTATION_VECTOR
See SH2 Ref. Manual 6.5.19.
Definition BNO08x.hpp:337
-
uint16_t raw_velocity_gyro_Z
Raw gyro angular velocity reading (See SH-2 Ref. Manual 6.5.44)
Definition BNO08x.hpp:264
-
float get_magf_Z()
Get Z component of magnetic field vector.
Definition BNO08x.cpp:1336
-
void queue_request_product_id_command()
Queues a packet containing the request product ID command.
Definition BNO08x.cpp:458
-
float get_gyro_calibrated_velocity_X()
Get calibrated gyro x axis angular velocity measurement.
Definition BNO08x.cpp:1842
-
static const constexpr uint8_t SENSOR_REPORTID_UNCALIBRATED_GYRO
See SH2 Ref. Manual 6.5.14.
Definition BNO08x.hpp:336
-
static const constexpr uint8_t TARE_GAME_ROTATION_VECTOR
Tare game rotation vector.
Definition BNO08x.hpp:360
-
uint32_t time_stamp
Report timestamp (see datasheet 1.3.5.3)
Definition BNO08x.hpp:259
-
float get_accel_X()
Get x axis acceleration (total acceleration of device, units in m/s^2).
Definition BNO08x.cpp:1636
-
void enable_rotation_vector(uint16_t time_between_reports)
Sends command to enable rotation vector reports (See Ref. Manual 6.5.18)
Definition BNO08x.cpp:1009
-
static const constexpr uint8_t CALIBRATE_MAG
Calibrate magnetometer command used by queue_calibrate_command.
Definition BNO08x.hpp:302
-
spi_transaction_t spi_transaction
SPI transaction handle.
Definition BNO08x.hpp:256
-
bool mode_on()
Turns on/ brings BNO08x sensor out of sleep mode using executable channel.
Definition BNO08x.cpp:293
-
uint8_t command_sequence_number
Sequence num of command, sent within command packet.
Definition BNO08x.hpp:248
-
void calibrate_magnetometer()
Sends command to calibrate magnetometer.
Definition BNO08x.cpp:506
-
uint16_t mems_raw_gyro_Z
Raw gyro readings from MEMS sensor (See SH-2 Ref. Manual 6.5.12)
Definition BNO08x.hpp:275
-
uint16_t magf_accuracy
Calibrated magnetic field reading in uTesla (See SH-2 Ref. Manual 6.5.16)
Definition BNO08x.hpp:267
-
static const constexpr uint8_t SENSOR_REPORTID_RAW_MAGNETOMETER
See SH2 Ref. Manual 6.5.15.
Definition BNO08x.hpp:345
-
void enable_uncalibrated_gyro(uint16_t time_between_reports)
Sends command to enable uncalibrated gyro reports (See Ref. Manual 6.5.14)
Definition BNO08x.cpp:1113
-
void end_calibration()
Sends command to end calibration procedure.
Definition BNO08x.cpp:610
-
uint8_t commands[20]
Command to be sent with send_packet()
Definition BNO08x.hpp:245
-
spi_device_handle_t spi_hdl
SPI device handle.
Definition BNO08x.hpp:255
-
uint8_t get_gravity_accuracy()
Get the reported gravity accuracy.
Definition BNO08x.cpp:1405
-
float get_gyro_velocity_Y()
Get y axis angular velocity from gyro-integrated rotation vector. (See Ref. Manual 6....
Definition BNO08x.cpp:2003
-
float get_gyro_velocity_X()
Get x axis angular velocity from gyro-integrated rotation vector. (See Ref. Manual 6....
Definition BNO08x.cpp:1993
-
static const constexpr uint8_t CALIBRATE_ACCEL
Calibrate accelerometer command used by queue_calibrate_command.
Definition BNO08x.hpp:300
-
void enable_magnetometer(uint16_t time_between_reports)
Sends command to enable magnetometer reports (See Ref. Manual 6.5.16)
Definition BNO08x.cpp:1126
-
void queue_calibrate_command(uint8_t _to_calibrate)
Queues a packet containing a command to calibrate the specified sensor.
Definition BNO08x.cpp:532
-
static const constexpr int16_t LINEAR_ACCELEROMETER_Q1
Linear acceleration Q point (See SH-2 Ref. Manual 6.5.10)
Definition BNO08x.hpp:291
-
void enable_raw_magnetometer(uint16_t time_between_reports)
Sends command to enable raw magnetometer reports (See Ref. Manual 6.5.15)
Definition BNO08x.cpp:1220
-
uint8_t calibration_status
Calibration status of device (See SH-2 Ref. Manual 6.4.7.1 & 6.4.7.2)
Definition BNO08x.hpp:273
-
float get_uncalibrated_gyro_bias_X()
Get uncalibrated gyro x axis drift estimate.
Definition BNO08x.cpp:1936
-
void enable_linear_accelerometer(uint16_t time_between_reports)
Sends command to enable linear accelerometer reports (See Ref. Manual 6.5.10)
Definition BNO08x.cpp:1074
-
float get_gyro_calibrated_velocity_Y()
Get calibrated gyro y axis angular velocity measurement.
Definition BNO08x.cpp:1852
-
void enable_step_counter(uint16_t time_between_reports)
Sends command to enable step counter reports (See Ref. Manual 6.5.29)
Definition BNO08x.cpp:1152
-
void get_linear_accel(float &x, float &y, float &z, uint8_t &accuracy)
Get full linear acceleration (acceleration of the device minus gravity, units in m/s^2).
Definition BNO08x.cpp:1681
-
void enable_raw_accelerometer(uint16_t time_between_reports)
Sends command to enable raw accelerometer reports (See Ref. Manual 6.5.8)
Definition BNO08x.cpp:1194
-
uint16_t step_count
Step counter reading (See SH-2 Ref. Manual 6.5.29)
Definition BNO08x.hpp:269
-
uint32_t get_time_stamp()
Return timestamp of most recent report.
Definition BNO08x.cpp:1286
-
void enable_ARVR_stabilized_game_rotation_vector(uint16_t time_between_reports)
Sends command to enable ARVR stabilized game rotation vector reports (See Ref. Manual 6....
Definition BNO08x.cpp:1035
-
uint16_t get_step_count()
Get the counted amount of steps.
Definition BNO08x.cpp:2035
-
int16_t get_raw_magf_X()
Get raw magnetometer x axis reading from physical magnetometer sensor (See Ref. Manual 6....
Definition BNO08x.cpp:1794
-
bool FRS_read_request(uint16_t record_ID, uint16_t read_offset, uint16_t block_size)
Requests meta data from BNO08x FRS (flash record system) given the record ID. Contains Q points and o...
Definition BNO08x.cpp:2257
-
uint16_t gravity_accuracy
Gravity reading in m/s^2 (See SH-2 Ref. Manual 6.5.11)
Definition BNO08x.hpp:265
-
static const constexpr int16_t GRAVITY_Q1
Gravity Q point (See SH-2 Ref. Manual 6.5.11)
Definition BNO08x.hpp:295
-
float get_gyro_velocity_Z()
Get z axis angular velocity from gyro-integrated rotation vector. (See Ref. Manual 6....
Definition BNO08x.cpp:2013
-
static const constexpr uint8_t SHTP_REPORT_BASE_TIMESTAMP
See SH2 Ref. Manual 7.2.1.
Definition BNO08x.hpp:325
-
bool receive_packet()
Receives a SHTP packet via SPI.
Definition BNO08x.cpp:337
-
bool run_full_calibration_routine()
Runs full calibration routine.
Definition BNO08x.cpp:640
-
bool initialize()
Initializes BNO08x sensor.
Definition BNO08x.cpp:114
-
static const constexpr uint8_t CALIBRATE_GYRO
Calibrate gyro command used by queue_calibrate_command.
Definition BNO08x.hpp:301
-
static const constexpr uint8_t SHTP_REPORT_FRS_READ_RESPONSE
See SH2 Ref. Manual 6.3.7.
Definition BNO08x.hpp:321
-
static const constexpr uint8_t SENSOR_REPORTID_GEOMAGNETIC_ROTATION_VECTOR
See SH2 Ref. Manual 6.5.20.
Definition BNO08x.hpp:338
-
static const constexpr uint8_t TARE_AXIS_Z
Tar yaw axis only (used with tare now command)
Definition BNO08x.hpp:356
-
static const constexpr uint8_t TARE_AR_VR_STABILIZED_GAME_ROTATION_VECTOR
Tare ARVR stabilized game rotation vector.
Definition BNO08x.hpp:364
-
bno08x_config_t imu_config
IMU configuration settings.
Definition BNO08x.hpp:252
-
SemaphoreHandle_t tx_semaphore
Mutex semaphore used to prevent sending or receiving of packets if packet is currently being queued.
Definition BNO08x.hpp:241
-
static const constexpr uint8_t SENSOR_REPORTID_GRAVITY
See SH2 Ref. Manual 6.5.11.
Definition BNO08x.hpp:335
-
void calibrate_accelerometer()
Sends command to calibrate accelerometer.
Definition BNO08x.cpp:482
-
static const constexpr uint8_t COMMAND_DCD
Save DCD command (See SH2 Ref. Manual 6.4.7)
Definition BNO08x.hpp:312
-
int16_t get_raw_gyro_X()
Get raw gyroscope x axis reading from physical gyroscope MEMs sensor (See Ref. Manual 6....
Definition BNO08x.cpp:1764
-
float get_pitch_deg()
Get the reported rotation about y axis.
Definition BNO08x.cpp:1510
-
static const constexpr uint8_t CALIBRATE_ACCEL_GYRO_MAG
Calibrate accelerometer, gyro, & magnetometer command used by queue_calibrate_command.
Definition BNO08x.hpp:304
-
uint16_t packet_length_rx
Packet length received (calculated from packet_header_rx)
Definition BNO08x.hpp:250
-
float get_yaw_deg()
Get the reported rotation about z axis.
Definition BNO08x.cpp:1520
-
uint8_t * activity_confidences
Confidence of read activities (See SH-2 Ref. Manual 6.5.36)
Definition BNO08x.hpp:272
-
void enable_raw_gyro(uint16_t time_between_reports)
Sends command to enable raw gyro reports (See Ref. Manual 6.5.12)
Definition BNO08x.cpp:1207
-
static const constexpr uint8_t SENSOR_REPORTID_STABILITY_CLASSIFIER
See SH2 Ref. Manual 6.5.31.
Definition BNO08x.hpp:342
-
void save_tare()
Sends command to save tare into non-volatile memory of BNO08x (See Ref. Manual 6.4....
Definition BNO08x.cpp:1246
-
void calibrate_all()
Sends command to calibrate accelerometer, gyro, and magnetometer.
Definition BNO08x.cpp:470
-
float get_accel_Y()
Get y axis acceleration (total acceleration of device, units in m/s^2).
Definition BNO08x.cpp:1646
-
float get_linear_accel_Z()
Get z axis linear acceleration (acceleration of device minus gravity, units in m/s^2)
Definition BNO08x.cpp:1714
-
void clear_tare()
Sends command to clear persistent tare settings in non-volatile memory of BNO08x (See Ref....
Definition BNO08x.cpp:1258
-
void get_gyro_velocity(float &x, float &y, float &z)
Full rotational velocity from gyro-integrated rotation vector (See Ref. Manual 6.5....
Definition BNO08x.cpp:1981
-
int16_t get_raw_gyro_Y()
Get raw gyroscope y axis reading from physical gyroscope MEMs sensor (See Ref. Manual 6....
Definition BNO08x.cpp:1774
-
void request_calibration_status()
Requests ME calibration status from BNO08x (see Ref. Manual 6.4.7.2)
Definition BNO08x.cpp:579
-
IMU configuration settings passed into constructor.
Definition BNO08x.hpp:42
-
spi_host_device_t spi_peripheral
SPI peripheral to be used.
Definition BNO08x.hpp:43
-
gpio_num_t io_int
Chip select pin (connects to BNO08x CS pin)
Definition BNO08x.hpp:48
-
gpio_num_t io_rst
Host interrupt pin (connects to BNO08x INT pin)
Definition BNO08x.hpp:49
-
gpio_num_t io_sclk
SCLK pin (connects to BNO08x SCL pin)
Definition BNO08x.hpp:46
-
uint64_t sclk_speed
Desired SPI SCLK speed in Hz (max 3MHz)
Definition BNO08x.hpp:51
-
bool debug_en
Whether or not debugging print statements are enabled.
Definition BNO08x.hpp:52
-
gpio_num_t io_mosi
MOSI GPIO pin (connects to BNO08x DI pin)
Definition BNO08x.hpp:44
-
gpio_num_t io_wake
Reset pin (connects to BNO08x RST pin)
Definition BNO08x.hpp:50
-
gpio_num_t io_miso
MISO GPIO pin (connects to BNO08x SDA pin)
Definition BNO08x.hpp:45
-
bno08x_config_t()
Default IMU configuration settings
Definition BNO08x.hpp:55
+
static const constexpr uint8_t TARE_GYRO_INTEGRATED_ROTATION_VECTOR
Tare gyro integrated rotation vector.
Definition BNO08x.hpp:262
+
float get_quat_K()
Get K component of reported quaternion.
Definition BNO08x.cpp:1579
+
float get_quat_J()
Get J component of reported quaternion.
Definition BNO08x.cpp:1568
+
static const constexpr int16_t MAGNETOMETER_Q1
Magnetometer Q point (See SH-2 Ref. Manual 6.5.16)
Definition BNO08x.hpp:271
+
void save_calibration()
Sends command to save internal calibration data (See Ref. Manual 6.4.7).
Definition BNO08x.cpp:612
+
static const constexpr int16_t GYRO_Q1
Gyro Q point (See SH-2 Ref. Manual 6.5.13)
Definition BNO08x.hpp:270
+
uint16_t raw_velocity_gyro_X
Definition BNO08x.hpp:319
+
uint16_t raw_magf_X
Definition BNO08x.hpp:325
+
uint8_t sequence_number[6]
Sequence num of each com channel, 6 in total.
Definition BNO08x.hpp:298
+
static const constexpr uint8_t SENSOR_REPORTID_RAW_ACCELEROMETER
See SH2 Ref. Manual 6.5.8.
Definition BNO08x.hpp:396
+
uint16_t mems_raw_magf_Y
Definition BNO08x.hpp:337
+
static const constexpr uint8_t SENSOR_REPORTID_RAW_GYROSCOPE
See SH2 Ref. Manual 6.5.12.
Definition BNO08x.hpp:397
+
static const constexpr int16_t ANGULAR_VELOCITY_Q1
Angular velocity Q point (See SH-2 Ref. Manual 6.5.44)
Definition BNO08x.hpp:272
+
static const constexpr uint8_t SENSOR_REPORTID_STEP_COUNTER
See SH2 Ref. Manual 6.5.29.
Definition BNO08x.hpp:394
+
static const constexpr uint8_t SENSOR_REPORTID_ROTATION_VECTOR
See SH2 Ref. Manual 6.5.18.
Definition BNO08x.hpp:387
+
static const constexpr uint8_t SHTP_REPORT_COMMAND_REQUEST
See SH2 Ref. Manual 6.3.8.
Definition BNO08x.hpp:374
+
static const constexpr uint8_t SENSOR_REPORTID_GAME_ROTATION_VECTOR
See SH2 Ref. Manual 6.5.19.
Definition BNO08x.hpp:390
+
uint16_t raw_magf_Z
Definition BNO08x.hpp:325
+
uint16_t raw_velocity_gyro_Z
Raw gyro angular velocity reading (See SH-2 Ref. Manual 6.5.44)
Definition BNO08x.hpp:320
+
float get_magf_Z()
Get Z component of magnetic field vector.
Definition BNO08x.cpp:1343
+
uint16_t raw_accel_Y
Definition BNO08x.hpp:312
+
uint16_t mems_raw_magf_X
Definition BNO08x.hpp:337
+
void queue_request_product_id_command()
Queues a packet containing the request product ID command.
Definition BNO08x.cpp:450
+
uint16_t mems_raw_gyro_Y
Definition BNO08x.hpp:335
+
float get_gyro_calibrated_velocity_X()
Get calibrated gyro x axis angular velocity measurement.
Definition BNO08x.cpp:1846
+
static const constexpr uint8_t SENSOR_REPORTID_UNCALIBRATED_GYRO
See SH2 Ref. Manual 6.5.14.
Definition BNO08x.hpp:389
+
static const constexpr uint16_t FRS_RECORDID_MAGNETIC_FIELD_CALIBRATED
Definition BNO08x.hpp:252
+
static const constexpr uint8_t TARE_GAME_ROTATION_VECTOR
Tare game rotation vector.
Definition BNO08x.hpp:260
+
uint16_t raw_lin_accel_Z
Definition BNO08x.hpp:314
+
uint32_t time_stamp
Report timestamp (see datasheet 1.3.5.3)
Definition BNO08x.hpp:311
+
float get_accel_X()
Get x axis acceleration (total acceleration of device, units in m/s^2).
Definition BNO08x.cpp:1640
+
void enable_rotation_vector(uint16_t time_between_reports)
Sends command to enable rotation vector reports (See Ref. Manual 6.5.18)
Definition BNO08x.cpp:1015
+
static const constexpr uint8_t CALIBRATE_MAG
Calibrate magnetometer command used by queue_calibrate_command.
Definition BNO08x.hpp:355
+
spi_transaction_t spi_transaction
SPI transaction handle.
Definition BNO08x.hpp:308
+
bool mode_on()
Turns on/ brings BNO08x sensor out of sleep mode using executable channel.
Definition BNO08x.cpp:288
+
uint8_t command_sequence_number
Sequence num of command, sent within command packet.
Definition BNO08x.hpp:300
+
void calibrate_magnetometer()
Sends command to calibrate magnetometer.
Definition BNO08x.cpp:498
+
uint16_t mems_raw_gyro_Z
Raw gyro readings from MEMS sensor (See SH-2 Ref. Manual 6.5.12)
Definition BNO08x.hpp:336
+
uint16_t raw_bias_Y
Definition BNO08x.hpp:323
+
uint16_t magf_accuracy
Calibrated magnetic field reading in uTesla (See SH-2 Ref. Manual 6.5.16)
Definition BNO08x.hpp:326
+
static const constexpr uint8_t SENSOR_REPORTID_RAW_MAGNETOMETER
See SH2 Ref. Manual 6.5.15.
Definition BNO08x.hpp:398
+
void enable_uncalibrated_gyro(uint16_t time_between_reports)
Sends command to enable uncalibrated gyro reports (See Ref. Manual 6.5.14)
Definition BNO08x.cpp:1119
+
void end_calibration()
Sends command to end calibration procedure.
Definition BNO08x.cpp:600
+
uint8_t commands[20]
Command to be sent with send_packet()
Definition BNO08x.hpp:297
+
spi_device_handle_t spi_hdl
SPI device handle.
Definition BNO08x.hpp:307
+
uint16_t raw_uncalib_gyro_Y
Definition BNO08x.hpp:323
+
uint8_t get_gravity_accuracy()
Get the reported gravity accuracy.
Definition BNO08x.cpp:1412
+
float get_gyro_velocity_Y()
Get y axis angular velocity from gyro-integrated rotation vector. (See Ref. Manual 6....
Definition BNO08x.cpp:2007
+
uint16_t raw_magf_Y
Definition BNO08x.hpp:325
+
float get_gyro_velocity_X()
Get x axis angular velocity from gyro-integrated rotation vector. (See Ref. Manual 6....
Definition BNO08x.cpp:1997
+
static const constexpr uint8_t CALIBRATE_ACCEL
Calibrate accelerometer command used by queue_calibrate_command.
Definition BNO08x.hpp:353
+
void enable_magnetometer(uint16_t time_between_reports)
Sends command to enable magnetometer reports (See Ref. Manual 6.5.16)
Definition BNO08x.cpp:1132
+
void queue_calibrate_command(uint8_t _to_calibrate)
Queues a packet containing a command to calibrate the specified sensor.
Definition BNO08x.cpp:523
+
static const constexpr int16_t LINEAR_ACCELEROMETER_Q1
Linear acceleration Q point (See SH-2 Ref. Manual 6.5.10)
Definition BNO08x.hpp:269
+
void enable_raw_magnetometer(uint16_t time_between_reports)
Sends command to enable raw magnetometer reports (See Ref. Manual 6.5.15)
Definition BNO08x.cpp:1226
+
uint8_t calibration_status
Calibration status of device (See SH-2 Ref. Manual 6.4.7.1 & 6.4.7.2)
Definition BNO08x.hpp:332
+
float get_uncalibrated_gyro_bias_X()
Get uncalibrated gyro x axis drift estimate.
Definition BNO08x.cpp:1941
+
void enable_linear_accelerometer(uint16_t time_between_reports)
Sends command to enable linear accelerometer reports (See Ref. Manual 6.5.10)
Definition BNO08x.cpp:1080
+
float get_gyro_calibrated_velocity_Y()
Get calibrated gyro y axis angular velocity measurement.
Definition BNO08x.cpp:1856
+
void enable_step_counter(uint16_t time_between_reports)
Sends command to enable step counter reports (See Ref. Manual 6.5.29)
Definition BNO08x.cpp:1158
+
void get_linear_accel(float &x, float &y, float &z, uint8_t &accuracy)
Get full linear acceleration (acceleration of the device minus gravity, units in m/s^2).
Definition BNO08x.cpp:1685
+
void enable_raw_accelerometer(uint16_t time_between_reports)
Sends command to enable raw accelerometer reports (See Ref. Manual 6.5.8)
Definition BNO08x.cpp:1200
+
uint16_t step_count
Step counter reading (See SH-2 Ref. Manual 6.5.29)
Definition BNO08x.hpp:328
+
uint16_t mems_raw_accel_Y
Definition BNO08x.hpp:333
+
uint32_t get_time_stamp()
Return timestamp of most recent report.
Definition BNO08x.cpp:1293
+
void enable_ARVR_stabilized_game_rotation_vector(uint16_t time_between_reports)
Sends command to enable ARVR stabilized game rotation vector reports (See Ref. Manual 6....
Definition BNO08x.cpp:1041
+
uint16_t get_step_count()
Get the counted amount of steps.
Definition BNO08x.cpp:2039
+
int16_t get_raw_magf_X()
Get raw magnetometer x axis reading from physical magnetometer sensor (See Ref. Manual 6....
Definition BNO08x.cpp:1798
+
bool FRS_read_request(uint16_t record_ID, uint16_t read_offset, uint16_t block_size)
Requests meta data from BNO08x FRS (flash record system) given the record ID. Contains Q points and o...
Definition BNO08x.cpp:2251
+
uint16_t gravity_accuracy
Gravity reading in m/s^2 (See SH-2 Ref. Manual 6.5.11)
Definition BNO08x.hpp:322
+
static const constexpr int16_t GRAVITY_Q1
Gravity Q point (See SH-2 Ref. Manual 6.5.11)
Definition BNO08x.hpp:273
+
uint16_t raw_lin_accel_X
Definition BNO08x.hpp:314
+
float get_gyro_velocity_Z()
Get z axis angular velocity from gyro-integrated rotation vector. (See Ref. Manual 6....
Definition BNO08x.cpp:2017
+
static const constexpr uint8_t SHTP_REPORT_BASE_TIMESTAMP
See SH2 Ref. Manual 7.2.1.
Definition BNO08x.hpp:379
+
bool receive_packet()
Receives a SHTP packet via SPI.
Definition BNO08x.cpp:332
+
bool run_full_calibration_routine()
Runs full calibration routine.
Definition BNO08x.cpp:631
+
static const constexpr uint64_t HOST_INT_TIMEOUT_MS
Max wait between HINT being asserted by BNO08x before transaction is considered failed (in milisecond...
Definition BNO08x.hpp:349
+
bool initialize()
Initializes BNO08x sensor.
Definition BNO08x.cpp:119
+
static const constexpr uint8_t CALIBRATE_GYRO
Calibrate gyro command used by queue_calibrate_command.
Definition BNO08x.hpp:354
+
static const constexpr uint8_t SHTP_REPORT_FRS_READ_RESPONSE
See SH2 Ref. Manual 6.3.7.
Definition BNO08x.hpp:375
+
static const constexpr uint8_t SENSOR_REPORTID_GEOMAGNETIC_ROTATION_VECTOR
See SH2 Ref. Manual 6.5.20.
Definition BNO08x.hpp:391
+
static const constexpr uint8_t TARE_AXIS_Z
Tar yaw axis only (used with tare now command)
Definition BNO08x.hpp:256
+
static const constexpr uint8_t TARE_AR_VR_STABILIZED_GAME_ROTATION_VECTOR
Tare ARVR stabilized game rotation vector.
Definition BNO08x.hpp:264
+
bno08x_config_t imu_config
IMU configuration settings.
Definition BNO08x.hpp:304
+
SemaphoreHandle_t tx_semaphore
Mutex semaphore used to prevent sending or receiving of packets if packet is currently being queued.
Definition BNO08x.hpp:291
+
static const constexpr uint8_t SENSOR_REPORTID_GRAVITY
See SH2 Ref. Manual 6.5.11.
Definition BNO08x.hpp:388
+
void calibrate_accelerometer()
Sends command to calibrate accelerometer.
Definition BNO08x.cpp:474
+
static const constexpr uint8_t COMMAND_DCD
Save DCD command (See SH2 Ref. Manual 6.4.7)
Definition BNO08x.hpp:366
+
int16_t get_raw_gyro_X()
Get raw gyroscope x axis reading from physical gyroscope MEMs sensor (See Ref. Manual 6....
Definition BNO08x.cpp:1768
+
uint16_t gravity_Y
Definition BNO08x.hpp:321
+
uint16_t raw_accel_Z
Definition BNO08x.hpp:312
+
uint16_t gravity_X
Definition BNO08x.hpp:321
+
float get_pitch_deg()
Get the reported rotation about y axis.
Definition BNO08x.cpp:1515
+
static const constexpr uint8_t CALIBRATE_ACCEL_GYRO_MAG
Calibrate accelerometer, gyro, & magnetometer command used by queue_calibrate_command.
Definition BNO08x.hpp:357
+
uint16_t packet_length_rx
Packet length received (calculated from packet_header_rx)
Definition BNO08x.hpp:302
+
float get_yaw_deg()
Get the reported rotation about z axis.
Definition BNO08x.cpp:1525
+
uint8_t * activity_confidences
Confidence of read activities (See SH-2 Ref. Manual 6.5.36)
Definition BNO08x.hpp:331
+
void enable_raw_gyro(uint16_t time_between_reports)
Sends command to enable raw gyro reports (See Ref. Manual 6.5.12)
Definition BNO08x.cpp:1213
+
uint16_t gravity_Z
Definition BNO08x.hpp:321
+
uint16_t raw_uncalib_gyro_Z
Definition BNO08x.hpp:323
+
static const constexpr uint8_t SENSOR_REPORTID_STABILITY_CLASSIFIER
See SH2 Ref. Manual 6.5.31.
Definition BNO08x.hpp:395
+
void save_tare()
Sends command to save tare into non-volatile memory of BNO08x (See Ref. Manual 6.4....
Definition BNO08x.cpp:1253
+
void calibrate_all()
Sends command to calibrate accelerometer, gyro, and magnetometer.
Definition BNO08x.cpp:462
+
uint16_t raw_uncalib_gyro_X
Definition BNO08x.hpp:323
+
float get_accel_Y()
Get y axis acceleration (total acceleration of device, units in m/s^2).
Definition BNO08x.cpp:1650
+
float get_linear_accel_Z()
Get z axis linear acceleration (acceleration of device minus gravity, units in m/s^2)
Definition BNO08x.cpp:1718
+
void clear_tare()
Sends command to clear persistent tare settings in non-volatile memory of BNO08x (See Ref....
Definition BNO08x.cpp:1265
+
void get_gyro_velocity(float &x, float &y, float &z)
Full rotational velocity from gyro-integrated rotation vector (See Ref. Manual 6.5....
Definition BNO08x.cpp:1985
+
uint16_t raw_lin_accel_Y
Definition BNO08x.hpp:314
+
int16_t get_raw_gyro_Y()
Get raw gyroscope y axis reading from physical gyroscope MEMs sensor (See Ref. Manual 6....
Definition BNO08x.cpp:1778
+
void request_calibration_status()
Requests ME calibration status from BNO08x (see Ref. Manual 6.4.7.2)
Definition BNO08x.cpp:570
+
IMU configuration settings passed into constructor.
Definition BNO08x.hpp:39
+
spi_host_device_t spi_peripheral
SPI peripheral to be used.
Definition BNO08x.hpp:40
+
gpio_num_t io_int
Chip select pin (connects to BNO08x CS pin)
Definition BNO08x.hpp:45
+
gpio_num_t io_rst
Host interrupt pin (connects to BNO08x INT pin)
Definition BNO08x.hpp:46
+
gpio_num_t io_sclk
SCLK pin (connects to BNO08x SCL pin)
Definition BNO08x.hpp:43
+
uint64_t sclk_speed
Desired SPI SCLK speed in Hz (max 3MHz)
Definition BNO08x.hpp:48
+
bool debug_en
Whether or not debugging print statements are enabled.
Definition BNO08x.hpp:49
+
gpio_num_t io_mosi
MOSI GPIO pin (connects to BNO08x DI pin)
Definition BNO08x.hpp:41
+
gpio_num_t io_wake
Reset pin (connects to BNO08x RST pin)
Definition BNO08x.hpp:47
+
gpio_num_t io_miso
MISO GPIO pin (connects to BNO08x SDA pin)
Definition BNO08x.hpp:42
+
gpio_num_t io_cs
Definition BNO08x.hpp:44
+
bno08x_config_t()
Default IMU configuration settings constructor for ESP32.
Definition BNO08x.hpp:69
+
bno08x_config_t(spi_host_device_t spi_peripheral, gpio_num_t io_mosi, gpio_num_t io_miso, gpio_num_t io_sclk, gpio_num_t io_cs, gpio_num_t io_int, gpio_num_t io_rst, gpio_num_t io_wake, uint64_t sclk_speed, bool debug)
Overloaded IMU configuration settings constructor for custom pin settings.
Definition BNO08x.hpp:86
diff --git a/documentation/html/dir_275089585c7fc1b5fd5d7d42c69cb1da.html b/documentation/html/_r_e_a_d_m_e_8md.html similarity index 85% rename from documentation/html/dir_275089585c7fc1b5fd5d7d42c69cb1da.html rename to documentation/html/_r_e_a_d_m_e_8md.html index 9c8b04c..1136e92 100644 --- a/documentation/html/dir_275089585c7fc1b5fd5d7d42c69cb1da.html +++ b/documentation/html/_r_e_a_d_m_e_8md.html @@ -3,12 +3,14 @@ - + -esp32_BNO08x: D: Directory Reference +esp32_BNO08x: esp32_BNO08x/README.md File Reference + + @@ -21,7 +23,7 @@ -
esp32_BNO08x 1.00 +
esp32_BNO08x 1.01
C++ BNO08x IMU driver component for esp-idf.
@@ -30,7 +32,7 @@
- + @@ -68,19 +70,15 @@ $(function() {
-
-
D: Directory Reference
+
esp32_BNO08x/README.md File Reference
diff --git a/documentation/html/annotated.html b/documentation/html/annotated.html index c5fe971..a9cf35a 100644 --- a/documentation/html/annotated.html +++ b/documentation/html/annotated.html @@ -3,12 +3,14 @@ - + esp32_BNO08x: Class List + + @@ -21,7 +23,7 @@ -
esp32_BNO08x 1.00 +
esp32_BNO08x 1.01
C++ BNO08x IMU driver component for esp-idf.
@@ -30,7 +32,7 @@
- + @@ -82,7 +84,7 @@ $(function() { diff --git a/documentation/html/class_b_n_o08x-members.html b/documentation/html/class_b_n_o08x-members.html index 69e2e4f..0ea2a37 100644 --- a/documentation/html/class_b_n_o08x-members.html +++ b/documentation/html/class_b_n_o08x-members.html @@ -3,12 +3,14 @@ - + esp32_BNO08x: Member List + + @@ -21,7 +23,7 @@ -
esp32_BNO08x 1.00 +
esp32_BNO08x 1.01
C++ BNO08x IMU driver component for esp-idf.
@@ -30,7 +32,7 @@
- + @@ -78,10 +80,10 @@ $(function() { - + - + @@ -99,10 +101,10 @@ $(function() { - + - + @@ -133,10 +135,10 @@ $(function() { - - - - + + + + @@ -209,31 +211,31 @@ $(function() { - - - - + + + + - + - + - + - + - - - + + + - - + + - - + + @@ -244,7 +246,7 @@ $(function() { - + @@ -254,36 +256,36 @@ $(function() { - - - - - - - - - - - - - - - - - - - - - - - - - + + + + + + + + + + + + + + + + + + + + + + + + + - - + + @@ -327,17 +329,17 @@ $(function() { - - - - - - - - - + + + + + + + + + - + @@ -348,7 +350,7 @@ $(function() {
accel_accuracyBNO08xprivate
accel_lin_accuracyBNO08xprivate
ACCELEROMETER_Q1BNO08xprivatestatic
ACCELEROMETER_Q1BNO08xstatic
activity_classifierBNO08xprivate
activity_confidencesBNO08xprivate
ANGULAR_VELOCITY_Q1BNO08xprivatestatic
ANGULAR_VELOCITY_Q1BNO08xstatic
BNO08x(bno08x_config_t imu_config=default_imu_config)BNO08x
bus_configBNO08xprivate
CALIBRATE_ACCELBNO08xprivatestatic
calibration_statusBNO08xprivate
clear_tare()BNO08x
COMMAND_CLEAR_DCDBNO08xprivatestatic
COMMAND_COUNTER (defined in BNO08x)BNO08xprivatestatic
COMMAND_COUNTERBNO08xprivatestatic
COMMAND_DCDBNO08xprivatestatic
COMMAND_DCD_PERIOD_SAVEBNO08xprivatestatic
COMMAND_ERRORS (defined in BNO08x)BNO08xprivatestatic
COMMAND_ERRORSBNO08xprivatestatic
COMMAND_INITIALIZEBNO08xprivatestatic
COMMAND_ME_CALIBRATEBNO08xprivatestatic
COMMAND_OSCILLATORBNO08xprivatestatic
FRS_read_data(uint16_t record_ID, uint8_t start_location, uint8_t words_to_read)BNO08x
FRS_read_request(uint16_t record_ID, uint16_t read_offset, uint16_t block_size)BNO08x
FRS_read_word(uint16_t record_ID, uint8_t word_number)BNO08x
FRS_RECORDID_ACCELEROMETER (defined in BNO08x)BNO08xstatic
FRS_RECORDID_GYROSCOPE_CALIBRATED (defined in BNO08x)BNO08xstatic
FRS_RECORDID_MAGNETIC_FIELD_CALIBRATED (defined in BNO08x)BNO08xstatic
FRS_RECORDID_ROTATION_VECTOR (defined in BNO08x)BNO08xstatic
FRS_RECORDID_ACCELEROMETERBNO08xstatic
FRS_RECORDID_GYROSCOPE_CALIBRATEDBNO08xstatic
FRS_RECORDID_MAGNETIC_FIELD_CALIBRATEDBNO08xstatic
FRS_RECORDID_ROTATION_VECTORBNO08xstatic
get_accel(float &x, float &y, float &z, uint8_t &accuracy)BNO08x
get_accel_accuracy()BNO08x
get_accel_X()BNO08x
get_yaw()BNO08x
get_yaw_deg()BNO08x
gravity_accuracyBNO08xprivate
GRAVITY_Q1BNO08xprivatestatic
gravity_X (defined in BNO08x)BNO08xprivate
gravity_Y (defined in BNO08x)BNO08xprivate
gravity_Z (defined in BNO08x)BNO08xprivate
GRAVITY_Q1BNO08xstatic
gravity_XBNO08xprivate
gravity_YBNO08xprivate
gravity_ZBNO08xprivate
gyro_accuracyBNO08xprivate
GYRO_Q1BNO08xprivatestatic
GYRO_Q1BNO08xstatic
hard_reset()BNO08x
hint_handler(void *arg)BNO08xprivatestatic
HOST_INT_TIMEOUT_USBNO08xprivatestatic
HOST_INT_TIMEOUT_MSBNO08xprivatestatic
imu_configBNO08xprivate
imu_spi_configBNO08xprivate
initialize()BNO08x
int_assertedBNO08xprivate
int_asserted_semaphoreBNO08xprivate
isr_service_installedBNO08xprivatestatic
LINEAR_ACCELEROMETER_Q1BNO08xprivatestatic
LINEAR_ACCELEROMETER_Q1BNO08xstatic
magf_accuracyBNO08xprivate
MAGNETOMETER_Q1BNO08xprivatestatic
mems_raw_accel_X (defined in BNO08x)BNO08xprivate
mems_raw_accel_Y (defined in BNO08x)BNO08xprivate
MAGNETOMETER_Q1BNO08xstatic
mems_raw_accel_XBNO08xprivate
mems_raw_accel_YBNO08xprivate
mems_raw_accel_ZBNO08xprivate
mems_raw_gyro_X (defined in BNO08x)BNO08xprivate
mems_raw_gyro_Y (defined in BNO08x)BNO08xprivate
mems_raw_gyro_XBNO08xprivate
mems_raw_gyro_YBNO08xprivate
mems_raw_gyro_ZBNO08xprivate
mems_raw_magf_X (defined in BNO08x)BNO08xprivate
mems_raw_magf_Y (defined in BNO08x)BNO08xprivate
mems_raw_magf_XBNO08xprivate
mems_raw_magf_YBNO08xprivate
mems_raw_magf_ZBNO08xprivate
meta_dataBNO08xprivate
mode_on()BNO08x
parse_command_report()BNO08x
parse_input_report()BNO08x
print_header()BNO08x
print_packet() (defined in BNO08x)BNO08x
print_packet()BNO08x
q_to_float(int16_t fixed_point_value, uint8_t q_point)BNO08x
quat_accuracyBNO08xprivate
queue_calibrate_command(uint8_t _to_calibrate)BNO08xprivate
queue_packet(uint8_t channel_number, uint8_t data_length)BNO08xprivate
queue_request_product_id_command()BNO08xprivate
queue_tare_command(uint8_t command, uint8_t axis=TARE_AXIS_ALL, uint8_t rotation_vector_basis=TARE_ROTATION_VECTOR)BNO08xprivate
raw_accel_X (defined in BNO08x)BNO08xprivate
raw_accel_Y (defined in BNO08x)BNO08xprivate
raw_accel_Z (defined in BNO08x)BNO08xprivate
raw_bias_X (defined in BNO08x)BNO08xprivate
raw_bias_Y (defined in BNO08x)BNO08xprivate
raw_bias_Z (defined in BNO08x)BNO08xprivate
raw_gyro_X (defined in BNO08x)BNO08xprivate
raw_gyro_Y (defined in BNO08x)BNO08xprivate
raw_gyro_Z (defined in BNO08x)BNO08xprivate
raw_lin_accel_X (defined in BNO08x)BNO08xprivate
raw_lin_accel_Y (defined in BNO08x)BNO08xprivate
raw_lin_accel_Z (defined in BNO08x)BNO08xprivate
raw_magf_X (defined in BNO08x)BNO08xprivate
raw_magf_Y (defined in BNO08x)BNO08xprivate
raw_magf_Z (defined in BNO08x)BNO08xprivate
raw_quat_I (defined in BNO08x)BNO08xprivate
raw_quat_J (defined in BNO08x)BNO08xprivate
raw_quat_K (defined in BNO08x)BNO08xprivate
raw_quat_radian_accuracy (defined in BNO08x)BNO08xprivate
raw_quat_real (defined in BNO08x)BNO08xprivate
raw_uncalib_gyro_X (defined in BNO08x)BNO08xprivate
raw_uncalib_gyro_Y (defined in BNO08x)BNO08xprivate
raw_uncalib_gyro_Z (defined in BNO08x)BNO08xprivate
raw_velocity_gyro_X (defined in BNO08x)BNO08xprivate
raw_velocity_gyro_Y (defined in BNO08x)BNO08xprivate
raw_accel_XBNO08xprivate
raw_accel_YBNO08xprivate
raw_accel_ZBNO08xprivate
raw_bias_XBNO08xprivate
raw_bias_YBNO08xprivate
raw_bias_ZBNO08xprivate
raw_gyro_XBNO08xprivate
raw_gyro_YBNO08xprivate
raw_gyro_ZBNO08xprivate
raw_lin_accel_XBNO08xprivate
raw_lin_accel_YBNO08xprivate
raw_lin_accel_ZBNO08xprivate
raw_magf_XBNO08xprivate
raw_magf_YBNO08xprivate
raw_magf_ZBNO08xprivate
raw_quat_IBNO08xprivate
raw_quat_JBNO08xprivate
raw_quat_KBNO08xprivate
raw_quat_radian_accuracyBNO08xprivate
raw_quat_realBNO08xprivate
raw_uncalib_gyro_XBNO08xprivate
raw_uncalib_gyro_YBNO08xprivate
raw_uncalib_gyro_ZBNO08xprivate
raw_velocity_gyro_XBNO08xprivate
raw_velocity_gyro_YBNO08xprivate
raw_velocity_gyro_ZBNO08xprivate
receive_packet()BNO08xprivate
request_calibration_status()BNO08x
ROTATION_VECTOR_ACCURACY_Q1BNO08xprivatestatic
ROTATION_VECTOR_Q1BNO08xprivatestatic
ROTATION_VECTOR_ACCURACY_Q1BNO08xstatic
ROTATION_VECTOR_Q1BNO08xstatic
run_full_calibration_routine()BNO08x
rx_bufferBNO08xprivate
save_calibration()BNO08x
step_countBNO08xprivate
TAGBNO08xprivatestatic
tap_detectorBNO08xprivate
TARE_AR_VR_STABILIZED_GAME_ROTATION_VECTORBNO08xprivatestatic
TARE_AR_VR_STABILIZED_ROTATION_VECTORBNO08xprivatestatic
TARE_AXIS_ALLBNO08xprivatestatic
TARE_AXIS_ZBNO08xprivatestatic
TARE_GAME_ROTATION_VECTORBNO08xprivatestatic
TARE_GEOMAGNETIC_ROTATION_VECTORBNO08xprivatestatic
TARE_GYRO_INTEGRATED_ROTATION_VECTORBNO08xprivatestatic
TARE_NOWBNO08xprivatestatic
tare_now(uint8_t axis_sel=TARE_AXIS_ALL, uint8_t rotation_vector_basis=TARE_ROTATION_VECTOR)BNO08x
TARE_AR_VR_STABILIZED_GAME_ROTATION_VECTORBNO08xstatic
TARE_AR_VR_STABILIZED_ROTATION_VECTORBNO08xstatic
TARE_AXIS_ALLBNO08xstatic
TARE_AXIS_ZBNO08xstatic
TARE_GAME_ROTATION_VECTORBNO08xstatic
TARE_GEOMAGNETIC_ROTATION_VECTORBNO08xstatic
TARE_GYRO_INTEGRATED_ROTATION_VECTORBNO08xstatic
tare_now(uint8_t axis_sel=TARE_AXIS_ALL, uint8_t rotation_vector_basis=TARE_ROTATION_VECTOR)BNO08x
TARE_NOWBNO08xprivatestatic
TARE_PERSISTBNO08xprivatestatic
TARE_ROTATION_VECTORBNO08xprivatestatic
TARE_ROTATION_VECTORBNO08xstatic
TARE_SET_REORIENTATIONBNO08xprivatestatic
time_stampBNO08xprivate
tx_bufferBNO08xprivate
diff --git a/documentation/html/class_b_n_o08x.html b/documentation/html/class_b_n_o08x.html index 4b11a74..7426253 100644 --- a/documentation/html/class_b_n_o08x.html +++ b/documentation/html/class_b_n_o08x.html @@ -3,12 +3,14 @@ - + esp32_BNO08x: BNO08x Class Reference + + @@ -21,7 +23,7 @@ -
esp32_BNO08x 1.00 +
esp32_BNO08x 1.01
C++ BNO08x IMU driver component for esp-idf.
@@ -30,7 +32,7 @@
- + @@ -81,931 +83,791 @@ $(function() {
BNO08x Class Reference
+ +

#include <BNO08x.hpp>

- + - + - + - + - + - + - + - + - + - + - + - + - + - + - + - + - + - + - + - + - + - + - + - + - + - + - + - + - + - + - + - + - + - + - + - + - + - + - + - + - + - + - + - + - + - + - + - + - + - + - + - + - + - + - + - + - + - + - + - + - + - + - + - + - + - + - + - + - + - + - + - + - + - + - + - + - + - + - + - + - + - + - + - + - + - + - + - + - + - + - + - + - + - + - + - + - + - + - + - + - + - + - + - + - + - + - + - + - + - + - + - + - + - + - + - + - +

Public Member Functions

 BNO08x (bno08x_config_t imu_config=default_imu_config)
 BNO08x (bno08x_config_t imu_config=default_imu_config)
 BNO08x imu constructor.
 
bool initialize ()
bool initialize ()
 Initializes BNO08x sensor.
 
bool hard_reset ()
bool hard_reset ()
 Hard resets BNO08x sensor.
 
bool soft_reset ()
bool soft_reset ()
 Soft resets BNO08x sensor using executable channel.
 
uint8_t get_reset_reason ()
uint8_t get_reset_reason ()
 Get the reason for the most recent reset.
 
bool mode_sleep ()
bool mode_sleep ()
 Puts BNO08x sensor into sleep/low power mode using executable channel.
 
bool mode_on ()
bool mode_on ()
 Turns on/ brings BNO08x sensor out of sleep mode using executable channel.
 
float q_to_float (int16_t fixed_point_value, uint8_t q_point)
float q_to_float (int16_t fixed_point_value, uint8_t q_point)
 Converts a register value to a float using its associated Q point. (See https://en.wikipedia.org/wiki/Q_(number_format))
 
bool run_full_calibration_routine ()
bool run_full_calibration_routine ()
 Runs full calibration routine.
 
void calibrate_all ()
void calibrate_all ()
 Sends command to calibrate accelerometer, gyro, and magnetometer.
 
void calibrate_accelerometer ()
void calibrate_accelerometer ()
 Sends command to calibrate accelerometer.
 
void calibrate_gyro ()
void calibrate_gyro ()
 Sends command to calibrate gyro.
 
void calibrate_magnetometer ()
void calibrate_magnetometer ()
 Sends command to calibrate magnetometer.
 
void calibrate_planar_accelerometer ()
void calibrate_planar_accelerometer ()
 Sends command to calibrate planar accelerometer.
 
void request_calibration_status ()
void request_calibration_status ()
 Requests ME calibration status from BNO08x (see Ref. Manual 6.4.7.2)
 
bool calibration_complete ()
bool calibration_complete ()
 Returns true if calibration has completed.
 
void end_calibration ()
void end_calibration ()
 Sends command to end calibration procedure.
 
void save_calibration ()
void save_calibration ()
 Sends command to save internal calibration data (See Ref. Manual 6.4.7).
 
void enable_rotation_vector (uint16_t time_between_reports)
void enable_rotation_vector (uint16_t time_between_reports)
 Sends command to enable rotation vector reports (See Ref. Manual 6.5.18)
 
void enable_game_rotation_vector (uint16_t time_between_reports)
void enable_game_rotation_vector (uint16_t time_between_reports)
 Sends command to enable game rotation vector reports (See Ref. Manual 6.5.19)
 
void enable_ARVR_stabilized_rotation_vector (uint16_t time_between_reports)
void enable_ARVR_stabilized_rotation_vector (uint16_t time_between_reports)
 Sends command to enable ARVR stabilized rotation vector reports (See Ref. Manual 6.5.42)
 
void enable_ARVR_stabilized_game_rotation_vector (uint16_t time_between_reports)
void enable_ARVR_stabilized_game_rotation_vector (uint16_t time_between_reports)
 Sends command to enable ARVR stabilized game rotation vector reports (See Ref. Manual 6.5.43)
 
void enable_gyro_integrated_rotation_vector (uint16_t timeBetweenReports)
void enable_gyro_integrated_rotation_vector (uint16_t timeBetweenReports)
 Sends command to enable gyro integrated rotation vector reports (See Ref. Manual 6.5.44)
 
void enable_accelerometer (uint16_t time_between_reports)
void enable_accelerometer (uint16_t time_between_reports)
 Sends command to enable accelerometer reports (See Ref. Manual 6.5.9)
 
void enable_linear_accelerometer (uint16_t time_between_reports)
void enable_linear_accelerometer (uint16_t time_between_reports)
 Sends command to enable linear accelerometer reports (See Ref. Manual 6.5.10)
 
void enable_gravity (uint16_t time_between_reports)
void enable_gravity (uint16_t time_between_reports)
 Sends command to enable gravity reading reports (See Ref. Manual 6.5.11)
 
void enable_gyro (uint16_t time_between_reports)
void enable_gyro (uint16_t time_between_reports)
 Sends command to enable gyro reports (See Ref. Manual 6.5.13)
 
void enable_uncalibrated_gyro (uint16_t time_between_reports)
void enable_uncalibrated_gyro (uint16_t time_between_reports)
 Sends command to enable uncalibrated gyro reports (See Ref. Manual 6.5.14)
 
void enable_magnetometer (uint16_t time_between_reports)
void enable_magnetometer (uint16_t time_between_reports)
 Sends command to enable magnetometer reports (See Ref. Manual 6.5.16)
 
void enable_tap_detector (uint16_t time_between_reports)
void enable_tap_detector (uint16_t time_between_reports)
 Sends command to enable tap detector reports (See Ref. Manual 6.5.27)
 
void enable_step_counter (uint16_t time_between_reports)
void enable_step_counter (uint16_t time_between_reports)
 Sends command to enable step counter reports (See Ref. Manual 6.5.29)
 
void enable_stability_classifier (uint16_t time_between_reports)
void enable_stability_classifier (uint16_t time_between_reports)
 Sends command to enable activity stability classifier reports (See Ref. Manual 6.5.31)
 
void enable_activity_classifier (uint16_t time_between_reports, uint32_t activities_to_enable, uint8_t(&activity_confidence_vals)[9])
void enable_activity_classifier (uint16_t time_between_reports, uint32_t activities_to_enable, uint8_t(&activity_confidence_vals)[9])
 Sends command to enable activity classifier reports (See Ref. Manual 6.5.36)
 
void enable_raw_accelerometer (uint16_t time_between_reports)
void enable_raw_accelerometer (uint16_t time_between_reports)
 Sends command to enable raw accelerometer reports (See Ref. Manual 6.5.8)
 
void enable_raw_gyro (uint16_t time_between_reports)
void enable_raw_gyro (uint16_t time_between_reports)
 Sends command to enable raw gyro reports (See Ref. Manual 6.5.12)
 
void enable_raw_magnetometer (uint16_t time_between_reports)
void enable_raw_magnetometer (uint16_t time_between_reports)
 Sends command to enable raw magnetometer reports (See Ref. Manual 6.5.15)
 
void tare_now (uint8_t axis_sel=TARE_AXIS_ALL, uint8_t rotation_vector_basis=TARE_ROTATION_VECTOR)
void tare_now (uint8_t axis_sel=TARE_AXIS_ALL, uint8_t rotation_vector_basis=TARE_ROTATION_VECTOR)
 Sends command to tare an axis (See Ref. Manual 6.4.4.1)
 
void save_tare ()
void save_tare ()
 Sends command to save tare into non-volatile memory of BNO08x (See Ref. Manual 6.4.4.2)
 
void clear_tare ()
void clear_tare ()
 Sends command to clear persistent tare settings in non-volatile memory of BNO08x (See Ref. Manual 6.4.4.3)
 
bool data_available ()
bool data_available ()
 Checks if BNO08x has asserted interrupt and sent data.
 
uint16_t parse_input_report ()
uint16_t parse_input_report ()
 Parses received input report sent by BNO08x.
 
uint16_t parse_command_report ()
uint16_t parse_command_report ()
 Parses received command report sent by BNO08x (See Ref. Manual 6.3.9)
 
uint16_t get_readings ()
uint16_t get_readings ()
 Waits for BNO08x HINT pin to assert, and parses the received data.
 
uint32_t get_time_stamp ()
uint32_t get_time_stamp ()
 Return timestamp of most recent report.
 
void get_magf (float &x, float &y, float &z, uint8_t &accuracy)
void get_magf (float &x, float &y, float &z, uint8_t &accuracy)
 Get the full magnetic field vector.
 
float get_magf_X ()
float get_magf_X ()
 Get X component of magnetic field vector.
 
float get_magf_Y ()
float get_magf_Y ()
 Get Y component of magnetic field vector.
 
float get_magf_Z ()
float get_magf_Z ()
 Get Z component of magnetic field vector.
 
uint8_t get_magf_accuracy ()
uint8_t get_magf_accuracy ()
 Get accuracy of reported magnetic field vector.
 
void get_gravity (float &x, float &y, float &z, uint8_t &accuracy)
void get_gravity (float &x, float &y, float &z, uint8_t &accuracy)
 Get full reported gravity vector, units in m/s^2.
 
float get_gravity_X ()
float get_gravity_X ()
 Get the reported x axis gravity.
 
float get_gravity_Y ()
float get_gravity_Y ()
 Get the reported y axis gravity.
 
float get_gravity_Z ()
float get_gravity_Z ()
 Get the reported z axis gravity.
 
uint8_t get_gravity_accuracy ()
uint8_t get_gravity_accuracy ()
 Get the reported gravity accuracy.
 
float get_roll ()
float get_roll ()
 Get the reported rotation about x axis.
 
float get_pitch ()
float get_pitch ()
 Get the reported rotation about y axis.
 
float get_yaw ()
float get_yaw ()
 Get the reported rotation about z axis.
 
float get_roll_deg ()
float get_roll_deg ()
 Get the reported rotation about x axis.
 
float get_pitch_deg ()
float get_pitch_deg ()
 Get the reported rotation about y axis.
 
float get_yaw_deg ()
float get_yaw_deg ()
 Get the reported rotation about z axis.
 
void get_quat (float &i, float &j, float &k, float &real, float &rad_accuracy, uint8_t &accuracy)
void get_quat (float &i, float &j, float &k, float &real, float &rad_accuracy, uint8_t &accuracy)
 Get the full quaternion reading.
 
float get_quat_I ()
float get_quat_I ()
 Get I component of reported quaternion.
 
float get_quat_J ()
float get_quat_J ()
 Get J component of reported quaternion.
 
float get_quat_K ()
float get_quat_K ()
 Get K component of reported quaternion.
 
float get_quat_real ()
float get_quat_real ()
 Get real component of reported quaternion.
 
float get_quat_radian_accuracy ()
float get_quat_radian_accuracy ()
 Get radian accuracy of reported quaternion.
 
uint8_t get_quat_accuracy ()
uint8_t get_quat_accuracy ()
 Get accuracy of reported quaternion.
 
void get_accel (float &x, float &y, float &z, uint8_t &accuracy)
void get_accel (float &x, float &y, float &z, uint8_t &accuracy)
 Get full acceleration (total acceleration of device, units in m/s^2).
 
float get_accel_X ()
float get_accel_X ()
 Get x axis acceleration (total acceleration of device, units in m/s^2).
 
float get_accel_Y ()
float get_accel_Y ()
 Get y axis acceleration (total acceleration of device, units in m/s^2).
 
float get_accel_Z ()
float get_accel_Z ()
 Get z axis acceleration (total acceleration of device, units in m/s^2).
 
uint8_t get_accel_accuracy ()
uint8_t get_accel_accuracy ()
 Get accuracy of linear acceleration.
 
void get_linear_accel (float &x, float &y, float &z, uint8_t &accuracy)
void get_linear_accel (float &x, float &y, float &z, uint8_t &accuracy)
 Get full linear acceleration (acceleration of the device minus gravity, units in m/s^2).
 
float get_linear_accel_X ()
float get_linear_accel_X ()
 Get x axis linear acceleration (acceleration of device minus gravity, units in m/s^2)
 
float get_linear_accel_Y ()
float get_linear_accel_Y ()
 Get y axis linear acceleration (acceleration of device minus gravity, units in m/s^2)
 
float get_linear_accel_Z ()
float get_linear_accel_Z ()
 Get z axis linear acceleration (acceleration of device minus gravity, units in m/s^2)
 
uint8_t get_linear_accel_accuracy ()
uint8_t get_linear_accel_accuracy ()
 Get accuracy of linear acceleration.
 
int16_t get_raw_accel_X ()
int16_t get_raw_accel_X ()
 Get raw accelerometer x axis reading from physical accelerometer MEMs sensor (See Ref. Manual 6.5.8)
 
int16_t get_raw_accel_Y ()
int16_t get_raw_accel_Y ()
 Get raw accelerometer y axis reading from physical accelerometer MEMs sensor (See Ref. Manual 6.5.8)
 
int16_t get_raw_accel_Z ()
int16_t get_raw_accel_Z ()
 Get raw accelerometer z axis reading from physical accelerometer MEMs sensor (See Ref. Manual 6.5.8)
 
int16_t get_raw_gyro_X ()
int16_t get_raw_gyro_X ()
 Get raw gyroscope x axis reading from physical gyroscope MEMs sensor (See Ref. Manual 6.5.12)
 
int16_t get_raw_gyro_Y ()
int16_t get_raw_gyro_Y ()
 Get raw gyroscope y axis reading from physical gyroscope MEMs sensor (See Ref. Manual 6.5.12)
 
int16_t get_raw_gyro_Z ()
int16_t get_raw_gyro_Z ()
 Get raw gyroscope z axis reading from physical gyroscope MEMs sensor (See Ref. Manual 6.5.12)
 
int16_t get_raw_magf_X ()
int16_t get_raw_magf_X ()
 Get raw magnetometer x axis reading from physical magnetometer sensor (See Ref. Manual 6.5.15)
 
int16_t get_raw_magf_Y ()
int16_t get_raw_magf_Y ()
 Get raw magnetometer y axis reading from physical magnetometer sensor (See Ref. Manual 6.5.15)
 
int16_t get_raw_magf_Z ()
int16_t get_raw_magf_Z ()
 Get raw magnetometer z axis reading from physical magnetometer sensor (See Ref. Manual 6.5.15)
 
void get_gyro_calibrated_velocity (float &x, float &y, float &z, uint8_t &accuracy)
void get_gyro_calibrated_velocity (float &x, float &y, float &z, uint8_t &accuracy)
 Get full rotational velocity with drift compensation (units in Rad/s).
 
float get_gyro_calibrated_velocity_X ()
float get_gyro_calibrated_velocity_X ()
 Get calibrated gyro x axis angular velocity measurement.
 
float get_gyro_calibrated_velocity_Y ()
float get_gyro_calibrated_velocity_Y ()
 Get calibrated gyro y axis angular velocity measurement.
 
float get_gyro_calibrated_velocity_Z ()
float get_gyro_calibrated_velocity_Z ()
 Get calibrated gyro z axis angular velocity measurement.
 
uint8_t get_gyro_accuracy ()
uint8_t get_gyro_accuracy ()
 Get calibrated gyro accuracy.
 
void get_uncalibrated_gyro (float &x, float &y, float &z, float &bx, float &by, float &bz, uint8_t &accuracy)
void get_uncalibrated_gyro (float &x, float &y, float &z, float &bx, float &by, float &bz, uint8_t &accuracy)
 Get full rotational velocity without drift compensation (units in Rad/s). An estimate of drift is given but not applied.
 
float get_uncalibrated_gyro_X ()
float get_uncalibrated_gyro_X ()
 Get uncalibrated gyro x axis angular velocity measurement.
 
float get_uncalibrated_gyro_Y ()
float get_uncalibrated_gyro_Y ()
 Get uncalibrated gyro Y axis angular velocity measurement.
 
float get_uncalibrated_gyro_Z ()
float get_uncalibrated_gyro_Z ()
 Get uncalibrated gyro Z axis angular velocity measurement.
 
float get_uncalibrated_gyro_bias_X ()
float get_uncalibrated_gyro_bias_X ()
 Get uncalibrated gyro x axis drift estimate.
 
float get_uncalibrated_gyro_bias_Y ()
float get_uncalibrated_gyro_bias_Y ()
 Get uncalibrated gyro Y axis drift estimate.
 
float get_uncalibrated_gyro_bias_Z ()
float get_uncalibrated_gyro_bias_Z ()
 Get uncalibrated gyro Z axis drift estimate.
 
uint8_t get_uncalibrated_gyro_accuracy ()
uint8_t get_uncalibrated_gyro_accuracy ()
 Get uncalibrated gyro accuracy.
 
void get_gyro_velocity (float &x, float &y, float &z)
void get_gyro_velocity (float &x, float &y, float &z)
 Full rotational velocity from gyro-integrated rotation vector (See Ref. Manual 6.5.44)
 
float get_gyro_velocity_X ()
float get_gyro_velocity_X ()
 Get x axis angular velocity from gyro-integrated rotation vector. (See Ref. Manual 6.5.44)
 
float get_gyro_velocity_Y ()
float get_gyro_velocity_Y ()
 Get y axis angular velocity from gyro-integrated rotation vector. (See Ref. Manual 6.5.44)
 
float get_gyro_velocity_Z ()
float get_gyro_velocity_Z ()
 Get z axis angular velocity from gyro-integrated rotation vector. (See Ref. Manual 6.5.44)
 
uint8_t get_tap_detector ()
uint8_t get_tap_detector ()
 Get if tap has occured.
 
uint16_t get_step_count ()
uint16_t get_step_count ()
 Get the counted amount of steps.
 
int8_t get_stability_classifier ()
int8_t get_stability_classifier ()
 Get the current stability classifier (Seee Ref. Manual 6.5.31)
 
uint8_t get_activity_classifier ()
uint8_t get_activity_classifier ()
 Get the current activity classifier (Seee Ref. Manual 6.5.36)
 
void print_header ()
void print_header ()
 Prints the most recently received SHTP header to serial console with ESP_LOG statement.
 
-void print_packet ()
void print_packet ()
 
int16_t get_Q1 (uint16_t record_ID)
int16_t get_Q1 (uint16_t record_ID)
 Gets Q1 point from BNO08x FRS (flash record system).
 
int16_t get_Q2 (uint16_t record_ID)
int16_t get_Q2 (uint16_t record_ID)
 Gets Q2 point from BNO08x FRS (flash record system).
 
int16_t get_Q3 (uint16_t record_ID)
int16_t get_Q3 (uint16_t record_ID)
 Gets Q3 point from BNO08x FRS (flash record system).
 
float get_resolution (uint16_t record_ID)
float get_resolution (uint16_t record_ID)
 Gets resolution from BNO08x FRS (flash record system).
 
float get_range (uint16_t record_ID)
float get_range (uint16_t record_ID)
 Gets range from BNO08x FRS (flash record system).
 
uint32_t FRS_read_word (uint16_t record_ID, uint8_t word_number)
uint32_t FRS_read_word (uint16_t record_ID, uint8_t word_number)
 Reads meta data word from BNO08x FRS (flash record system) given the record ID and word number. (See Ref. Manual 5.1 & 6.3.7)
 
bool FRS_read_request (uint16_t record_ID, uint16_t read_offset, uint16_t block_size)
bool FRS_read_request (uint16_t record_ID, uint16_t read_offset, uint16_t block_size)
 Requests meta data from BNO08x FRS (flash record system) given the record ID. Contains Q points and other info. (See Ref. Manual 5.1 & 6.3.6)
 
bool FRS_read_data (uint16_t record_ID, uint8_t start_location, uint8_t words_to_read)
bool FRS_read_data (uint16_t record_ID, uint8_t start_location, uint8_t words_to_read)
 Read meta data from BNO08x FRS (flash record system) given the record ID. Contains Q points and other info. (See Ref. Manual 5.1 & 6.3.7)
 
- + - + - + - + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +

Static Public Attributes

-static const constexpr uint16_t FRS_RECORDID_ACCELEROMETER = 0xE302
static const constexpr uint16_t FRS_RECORDID_ACCELEROMETER = 0xE302
 
-static const constexpr uint16_t FRS_RECORDID_GYROSCOPE_CALIBRATED = 0xE306
static const constexpr uint16_t FRS_RECORDID_GYROSCOPE_CALIBRATED = 0xE306
 
-static const constexpr uint16_t FRS_RECORDID_MAGNETIC_FIELD_CALIBRATED = 0xE309
static const constexpr uint16_t FRS_RECORDID_MAGNETIC_FIELD_CALIBRATED = 0xE309
 
-static const constexpr uint16_t FRS_RECORDID_ROTATION_VECTOR = 0xE30B
static const constexpr uint16_t FRS_RECORDID_ROTATION_VECTOR = 0xE30B
 
static const constexpr uint8_t TARE_AXIS_ALL = 0x07
 Tare all axes (used with tare now command)
 
static const constexpr uint8_t TARE_AXIS_Z = 0x04
 Tar yaw axis only (used with tare now command)
 
static const constexpr uint8_t TARE_ROTATION_VECTOR = 0
 Tare rotation vector.
 
static const constexpr uint8_t TARE_GAME_ROTATION_VECTOR = 1
 Tare game rotation vector.
 
static const constexpr uint8_t TARE_GEOMAGNETIC_ROTATION_VECTOR = 2
 tare geomagnetic rotation vector
 
static const constexpr uint8_t TARE_GYRO_INTEGRATED_ROTATION_VECTOR = 3
 Tare gyro integrated rotation vector.
 
static const constexpr uint8_t TARE_AR_VR_STABILIZED_ROTATION_VECTOR = 4
 Tare ARVR stabilized rotation vector.
 
static const constexpr uint8_t TARE_AR_VR_STABILIZED_GAME_ROTATION_VECTOR = 5
 Tare ARVR stabilized game rotation vector.
 
static const constexpr int16_t ROTATION_VECTOR_Q1 = 14
 Rotation vector Q point (See SH-2 Ref. Manual 6.5.18)
 
static const constexpr int16_t ROTATION_VECTOR_ACCURACY_Q1 = 12
 Rotation vector accuracy estimate Q point (See SH-2 Ref. Manual 6.5.18)
 
static const constexpr int16_t ACCELEROMETER_Q1 = 8
 Acceleration Q point (See SH-2 Ref. Manual 6.5.9)
 
static const constexpr int16_t LINEAR_ACCELEROMETER_Q1 = 8
 Linear acceleration Q point (See SH-2 Ref. Manual 6.5.10)
 
static const constexpr int16_t GYRO_Q1 = 9
 Gyro Q point (See SH-2 Ref. Manual 6.5.13)
 
static const constexpr int16_t MAGNETOMETER_Q1 = 4
 Magnetometer Q point (See SH-2 Ref. Manual 6.5.16)
 
static const constexpr int16_t ANGULAR_VELOCITY_Q1 = 10
 Angular velocity Q point (See SH-2 Ref. Manual 6.5.44)
 
static const constexpr int16_t GRAVITY_Q1 = 8
 Gravity Q point (See SH-2 Ref. Manual 6.5.11)
 
- + - + - + - + - + - + - + - + - + - + - +

Private Member Functions

bool wait_for_device_int ()
bool wait_for_device_int ()
 Re-enables interrupts and waits for BNO08x to assert HINT pin.
 
bool receive_packet ()
bool receive_packet ()
 Receives a SHTP packet via SPI.
 
void send_packet ()
void send_packet ()
 Sends a queued SHTP packet via SPI.
 
void queue_packet (uint8_t channel_number, uint8_t data_length)
void queue_packet (uint8_t channel_number, uint8_t data_length)
 Queues an SHTP packet to be sent via SPI.
 
void queue_command (uint8_t command)
void queue_command (uint8_t command)
 Queues a packet containing a command.
 
void queue_feature_command (uint8_t report_ID, uint16_t time_between_reports)
void queue_feature_command (uint8_t report_ID, uint16_t time_between_reports)
 Queues a packet containing a command with a request for sensor reports, reported periodically. (See Ref. Manual 6.5.4)
 
void queue_feature_command (uint8_t report_ID, uint16_t time_between_reports, uint32_t specific_config)
void queue_feature_command (uint8_t report_ID, uint16_t time_between_reports, uint32_t specific_config)
 Queues a packet containing a command with a request for sensor reports, reported periodically. (See Ref. Manual 6.5.4)
 
void queue_calibrate_command (uint8_t _to_calibrate)
void queue_calibrate_command (uint8_t _to_calibrate)
 Queues a packet containing a command to calibrate the specified sensor.
 
void queue_tare_command (uint8_t command, uint8_t axis=TARE_AXIS_ALL, uint8_t rotation_vector_basis=TARE_ROTATION_VECTOR)
void queue_tare_command (uint8_t command, uint8_t axis=TARE_AXIS_ALL, uint8_t rotation_vector_basis=TARE_ROTATION_VECTOR)
 Queues a packet containing a command related to zeroing sensor's axes. (See Ref. Manual 6.4.4.1)
 
void queue_request_product_id_command ()
void queue_request_product_id_command ()
 Queues a packet containing the request product ID command.
 
void spi_task ()
void spi_task ()
 Task responsible for SPI transactions. Executed when HINT in is asserted by BNO08x.
 
- + - +

Static Private Member Functions

static void spi_task_trampoline (void *arg)
static void spi_task_trampoline (void *arg)
 Static function used to launch spi task.
 
static void IRAM_ATTR hint_handler (void *arg)
static void IRAM_ATTR hint_handler (void *arg)
 HINT interrupt service routine, handles falling edge of BNO08x HINT pin.
 
- - + + - - + + - - + + + + + - - + + - - + + - - + + - - + + - - + + - - + + - - + + - - + + - - + + - - + + - - + + - - + + - - + + - - + + - + - + - + - - + + - + - + - + - - + + - + - + - + - - + + - + - + - + - + - + - - + + - + - + - - + + - + - + - + - - + + - + - + - + - + - + - + - - + + - + - + - + - - + + - - + + - - + + - - + + - - + + - - + + - - + + - + - + - - + + - + - + - - + + - + - + - - + + - - + + - - -

Private Attributes

-volatile uint8_t tx_packet_queued
 Whether or not a packet is currently waiting to be sent, a queued packet is sent on assertion of BNO08x HINT pin)
volatile uint8_t tx_packet_queued
 Whether or not a packet is currently waiting to be sent, a queued packet is sent on assertion of BNO08x HINT pin)
 
-SemaphoreHandle_t tx_semaphore
 Mutex semaphore used to prevent sending or receiving of packets if packet is currently being queued.
SemaphoreHandle_t tx_semaphore
 Mutex semaphore used to prevent sending or receiving of packets if packet is currently being queued.
 
-uint8_t rx_buffer [300]
 buffer used to receive packet with receive_packet()
SemaphoreHandle_t int_asserted_semaphore
 Binary semaphore used to synchronize spi_task() calling wait_for_device_int(), given after hint_handler ISR launches SPI task and it has run to completion.
 
uint8_t rx_buffer [300]
 buffer used to receive packet with receive_packet()
 
-uint8_t tx_buffer [50]
 buffer used for sending packet with send_packet()
uint8_t tx_buffer [50]
 buffer used for sending packet with send_packet()
 
-uint8_t packet_header_rx [4]
 SHTP header received with receive_packet()
uint8_t packet_header_rx [4]
 SHTP header received with receive_packet()
 
-uint8_t commands [20]
 Command to be sent with send_packet()
uint8_t commands [20]
 Command to be sent with send_packet()
 
-uint8_t sequence_number [6]
 Sequence num of each com channel, 6 in total.
uint8_t sequence_number [6]
 Sequence num of each com channel, 6 in total.
 
-uint32_t meta_data [9]
 First 9 bytes of meta data returned from FRS read operation (we don't really need the rest) (See Ref. Manual 5.1)
uint32_t meta_data [9]
 First 9 bytes of meta data returned from FRS read operation (we don't really need the rest) (See Ref. Manual 5.1)
 
-uint8_t command_sequence_number = 0
 Sequence num of command, sent within command packet.
-
uint8_t command_sequence_number = 0
 Sequence num of command, sent within command packet.
 
-uint16_t packet_length_tx = 0
 Packet length to be sent with send_packet()
uint16_t packet_length_tx = 0
 Packet length to be sent with send_packet()
 
-uint16_t packet_length_rx = 0
 Packet length received (calculated from packet_header_rx)
uint16_t packet_length_rx = 0
 Packet length received (calculated from packet_header_rx)
 
-bno08x_config_t imu_config {}
 IMU configuration settings.
bno08x_config_t imu_config {}
 IMU configuration settings.
 
-spi_bus_config_t bus_config {}
 SPI bus GPIO configuration settings.
spi_bus_config_t bus_config {}
 SPI bus GPIO configuration settings.
 
-spi_device_interface_config_t imu_spi_config {}
 SPI slave device settings.
spi_device_interface_config_t imu_spi_config {}
 SPI slave device settings.
 
-spi_device_handle_t spi_hdl {}
 SPI device handle.
spi_device_handle_t spi_hdl {}
 SPI device handle.
 
-spi_transaction_t spi_transaction {}
 SPI transaction handle.
spi_transaction_t spi_transaction {}
 SPI transaction handle.
 
-uint32_t time_stamp
 Report timestamp (see datasheet 1.3.5.3)
uint32_t time_stamp
 Report timestamp (see datasheet 1.3.5.3)
 
-uint16_t raw_accel_X
uint16_t raw_accel_X
 
-uint16_t raw_accel_Y
uint16_t raw_accel_Y
 
-uint16_t raw_accel_Z
uint16_t raw_accel_Z
 
-uint16_t accel_accuracy
 Raw acceleration readings (See SH-2 Ref. Manual 6.5.8)
uint16_t accel_accuracy
 Raw acceleration readings (See SH-2 Ref. Manual 6.5.8)
 
-uint16_t raw_lin_accel_X
uint16_t raw_lin_accel_X
 
-uint16_t raw_lin_accel_Y
uint16_t raw_lin_accel_Y
 
-uint16_t raw_lin_accel_Z
uint16_t raw_lin_accel_Z
 
-uint16_t accel_lin_accuracy
 Raw linear acceleration (See SH-2 Ref. Manual 6.5.10)
uint16_t accel_lin_accuracy
 Raw linear acceleration (See SH-2 Ref. Manual 6.5.10)
 
-uint16_t raw_gyro_X
uint16_t raw_gyro_X
 
-uint16_t raw_gyro_Y
uint16_t raw_gyro_Y
 
-uint16_t raw_gyro_Z
uint16_t raw_gyro_Z
 
-uint16_t gyro_accuracy
 Raw gyro reading (See SH-2 Ref. Manual 6.5.13)
uint16_t gyro_accuracy
 Raw gyro reading (See SH-2 Ref. Manual 6.5.13)
 
-uint16_t raw_quat_I
uint16_t raw_quat_I
 
-uint16_t raw_quat_J
uint16_t raw_quat_J
 
-uint16_t raw_quat_K
uint16_t raw_quat_K
 
-uint16_t raw_quat_real
uint16_t raw_quat_real
 
-uint16_t raw_quat_radian_accuracy
uint16_t raw_quat_radian_accuracy
 
-uint16_t quat_accuracy
 Raw quaternion reading (See SH-2 Ref. Manual 6.5.44)
uint16_t quat_accuracy
 Raw quaternion reading (See SH-2 Ref. Manual 6.5.44)
 
-uint16_t raw_velocity_gyro_X
uint16_t raw_velocity_gyro_X
 
-uint16_t raw_velocity_gyro_Y
uint16_t raw_velocity_gyro_Y
 
-uint16_t raw_velocity_gyro_Z
 Raw gyro angular velocity reading (See SH-2 Ref. Manual 6.5.44)
uint16_t raw_velocity_gyro_Z
 Raw gyro angular velocity reading (See SH-2 Ref. Manual 6.5.44)
 
-uint16_t gravity_X
uint16_t gravity_X
 
-uint16_t gravity_Y
uint16_t gravity_Y
 
-uint16_t gravity_Z
uint16_t gravity_Z
 
-uint16_t gravity_accuracy
 Gravity reading in m/s^2 (See SH-2 Ref. Manual 6.5.11)
uint16_t gravity_accuracy
 Gravity reading in m/s^2 (See SH-2 Ref. Manual 6.5.11)
 
-uint16_t raw_uncalib_gyro_X
uint16_t raw_uncalib_gyro_X
 
-uint16_t raw_uncalib_gyro_Y
uint16_t raw_uncalib_gyro_Y
 
-uint16_t raw_uncalib_gyro_Z
uint16_t raw_uncalib_gyro_Z
 
-uint16_t raw_bias_X
uint16_t raw_bias_X
 
-uint16_t raw_bias_Y
uint16_t raw_bias_Y
 
-uint16_t raw_bias_Z
uint16_t raw_bias_Z
 
-uint16_t uncalib_gyro_accuracy
 Uncalibrated gyro reading (See SH-2 Ref. Manual 6.5.14)
uint16_t uncalib_gyro_accuracy
 Uncalibrated gyro reading (See SH-2 Ref. Manual 6.5.14)
 
-uint16_t raw_magf_X
uint16_t raw_magf_X
 
-uint16_t raw_magf_Y
uint16_t raw_magf_Y
 
-uint16_t raw_magf_Z
uint16_t raw_magf_Z
 
-uint16_t magf_accuracy
 Calibrated magnetic field reading in uTesla (See SH-2 Ref. Manual 6.5.16)
uint16_t magf_accuracy
 Calibrated magnetic field reading in uTesla (See SH-2 Ref. Manual 6.5.16)
 
-uint8_t tap_detector
 Tap detector reading (See SH-2 Ref. Manual 6.5.27)
uint8_t tap_detector
 Tap detector reading (See SH-2 Ref. Manual 6.5.27)
 
-uint16_t step_count
 Step counter reading (See SH-2 Ref. Manual 6.5.29)
uint16_t step_count
 Step counter reading (See SH-2 Ref. Manual 6.5.29)
 
-uint8_t stability_classifier
 Stability status reading (See SH-2 Ref. Manual 6.5.31)
uint8_t stability_classifier
 Stability status reading (See SH-2 Ref. Manual 6.5.31)
 
-uint8_t activity_classifier
 Activity status reading (See SH-2 Ref. Manual 6.5.36)
uint8_t activity_classifier
 Activity status reading (See SH-2 Ref. Manual 6.5.36)
 
-uint8_t * activity_confidences
 Confidence of read activities (See SH-2 Ref. Manual 6.5.36)
uint8_t * activity_confidences
 Confidence of read activities (See SH-2 Ref. Manual 6.5.36)
 
-uint8_t calibration_status
 Calibration status of device (See SH-2 Ref. Manual 6.4.7.1 & 6.4.7.2)
-
uint8_t calibration_status
 Calibration status of device (See SH-2 Ref. Manual 6.4.7.1 & 6.4.7.2)
 
-uint16_t mems_raw_accel_X
uint16_t mems_raw_accel_X
 
-uint16_t mems_raw_accel_Y
uint16_t mems_raw_accel_Y
 
-uint16_t mems_raw_accel_Z
 Raw accelerometer readings from MEMS sensor (See SH2 Ref. Manual 6.5.8)
uint16_t mems_raw_accel_Z
 Raw accelerometer readings from MEMS sensor (See SH2 Ref. Manual 6.5.8)
 
-uint16_t mems_raw_gyro_X
uint16_t mems_raw_gyro_X
 
-uint16_t mems_raw_gyro_Y
uint16_t mems_raw_gyro_Y
 
-uint16_t mems_raw_gyro_Z
 Raw gyro readings from MEMS sensor (See SH-2 Ref. Manual 6.5.12)
uint16_t mems_raw_gyro_Z
 Raw gyro readings from MEMS sensor (See SH-2 Ref. Manual 6.5.12)
 
-uint16_t mems_raw_magf_X
uint16_t mems_raw_magf_X
 
-uint16_t mems_raw_magf_Y
uint16_t mems_raw_magf_Y
 
-uint16_t mems_raw_magf_Z
 Raw magnetometer (compass) readings from MEMS sensor (See SH-2 Ref. Manual 6.5.15)
uint16_t mems_raw_magf_Z
 Raw magnetometer (compass) readings from MEMS sensor (See SH-2 Ref. Manual 6.5.15)
 
-TaskHandle_t spi_task_hdl
 SPI task handle.
TaskHandle_t spi_task_hdl
 SPI task handle.
 
-volatile bool int_asserted
 Interrupt asserted flag, sets true after hint_handler ISR launches SPI task and it has run to completion.
 
- - + + - - + + - - - - - - - - - - - - - - - - - - - - - - - - - - - - - + + + + + - - + + - - + + - - + + - - + + - - + + - + - + - - + + - - + + - - + + - - + + - - + + - - + + - - + + - - + + - - + + - - + + - - + + - - + + - - + + - - + + - - + + - - + + - - + + - - + + - - + + - - + + - - + + - - + + - - + + - - + + - - + + - - + + - - + + - - + + - - + + - - + + - - + + - - + + - - + + - - + + - - + + - - + + - - + + - - - - - - - - - - - - - - - - - - - - - - - - - - + +

Static Private Attributes

-static bno08x_config_t default_imu_config
 default imu config settings
static bno08x_config_t default_imu_config
 default imu config settings
 
-static bool isr_service_installed = {false}
 true of the isr service has been installed, only has to be done once regardless of how many devices are used
static bool isr_service_installed = {false}
 true of the isr service has been installed, only has to be done once regardless of how many devices are used
 
-static const constexpr int16_t ROTATION_VECTOR_Q1 = 14
 Rotation vector Q point (See SH-2 Ref. Manual 6.5.18)
 
-static const constexpr int16_t ROTATION_VECTOR_ACCURACY_Q1 = 12
 Rotation vector accuracy estimate Q point (See SH-2 Ref. Manual 6.5.18)
 
-static const constexpr int16_t ACCELEROMETER_Q1 = 8
 Acceleration Q point (See SH-2 Ref. Manual 6.5.9)
 
-static const constexpr int16_t LINEAR_ACCELEROMETER_Q1 = 8
 Linear acceleration Q point (See SH-2 Ref. Manual 6.5.10)
 
-static const constexpr int16_t GYRO_Q1 = 9
 Gyro Q point (See SH-2 Ref. Manual 6.5.13)
 
-static const constexpr int16_t MAGNETOMETER_Q1 = 4
 Magnetometer Q point (See SH-2 Ref. Manual 6.5.16)
 
-static const constexpr int16_t ANGULAR_VELOCITY_Q1 = 10
 Angular velocity Q point (See SH-2 Ref. Manual 6.5.44)
 
-static const constexpr int16_t GRAVITY_Q1 = 8
 Gravity Q point (See SH-2 Ref. Manual 6.5.11)
 
-static const constexpr uint64_t HOST_INT_TIMEOUT_US = 150000ULL
 Max wait between HINT being asserted by BNO08x before transaction is considered failed.
 
-static const constexpr uint8_t CALIBRATE_ACCEL = 0
 Calibrate accelerometer command used by queue_calibrate_command.
static const constexpr uint64_t HOST_INT_TIMEOUT_MS
 Max wait between HINT being asserted by BNO08x before transaction is considered failed (in miliseconds)
 
static const constexpr uint8_t CALIBRATE_ACCEL = 0
 Calibrate accelerometer command used by queue_calibrate_command.
 
-static const constexpr uint8_t CALIBRATE_GYRO = 1
 Calibrate gyro command used by queue_calibrate_command.
static const constexpr uint8_t CALIBRATE_GYRO = 1
 Calibrate gyro command used by queue_calibrate_command.
 
-static const constexpr uint8_t CALIBRATE_MAG = 2
 Calibrate magnetometer command used by queue_calibrate_command.
static const constexpr uint8_t CALIBRATE_MAG = 2
 Calibrate magnetometer command used by queue_calibrate_command.
 
-static const constexpr uint8_t CALIBRATE_PLANAR_ACCEL = 3
 Calibrate planar acceleration command used by queue_calibrate_command.
static const constexpr uint8_t CALIBRATE_PLANAR_ACCEL = 3
 Calibrate planar acceleration command used by queue_calibrate_command.
 
-static const constexpr uint8_t CALIBRATE_ACCEL_GYRO_MAG = 4
 Calibrate accelerometer, gyro, & magnetometer command used by queue_calibrate_command.
static const constexpr uint8_t CALIBRATE_ACCEL_GYRO_MAG
 Calibrate accelerometer, gyro, & magnetometer command used by queue_calibrate_command.
 
-static const constexpr uint8_t CALIBRATE_STOP = 5
 Stop calibration command used by queue_calibrate_command.
static const constexpr uint8_t CALIBRATE_STOP = 5
 Stop calibration command used by queue_calibrate_command.
 
-static const constexpr uint8_t COMMAND_ERRORS = 1
static const constexpr uint8_t COMMAND_ERRORS = 1
 
-static const constexpr uint8_t COMMAND_COUNTER = 2
static const constexpr uint8_t COMMAND_COUNTER = 2
 
-static const constexpr uint8_t COMMAND_TARE = 3
 Command and response to tare command (See Sh2 Ref. Manual 6.4.4)
static const constexpr uint8_t COMMAND_TARE = 3
 Command and response to tare command (See Sh2 Ref. Manual 6.4.4)
 
-static const constexpr uint8_t COMMAND_INITIALIZE = 4
 Reinitialize sensor hub components See (SH2 Ref. Manual 6.4.5)
static const constexpr uint8_t COMMAND_INITIALIZE = 4
 Reinitialize sensor hub components See (SH2 Ref. Manual 6.4.5)
 
-static const constexpr uint8_t COMMAND_DCD = 6
 Save DCD command (See SH2 Ref. Manual 6.4.7)
static const constexpr uint8_t COMMAND_DCD = 6
 Save DCD command (See SH2 Ref. Manual 6.4.7)
 
-static const constexpr uint8_t COMMAND_ME_CALIBRATE = 7
 Command and response to configure ME calibration (See SH2 Ref. Manual 6.4.7)
static const constexpr uint8_t COMMAND_ME_CALIBRATE = 7
 Command and response to configure ME calibration (See SH2 Ref. Manual 6.4.7)
 
-static const constexpr uint8_t COMMAND_DCD_PERIOD_SAVE = 9
 Configure DCD periodic saving (See SH2 Ref. Manual 6.4)
static const constexpr uint8_t COMMAND_DCD_PERIOD_SAVE = 9
 Configure DCD periodic saving (See SH2 Ref. Manual 6.4)
 
-static const constexpr uint8_t COMMAND_OSCILLATOR = 10
 Retrieve oscillator type command (See SH2 Ref. Manual 6.4)
static const constexpr uint8_t COMMAND_OSCILLATOR = 10
 Retrieve oscillator type command (See SH2 Ref. Manual 6.4)
 
-static const constexpr uint8_t COMMAND_CLEAR_DCD = 11
 Clear DCD & Reset command (See SH2 Ref. Manual 6.4)
static const constexpr uint8_t COMMAND_CLEAR_DCD = 11
 Clear DCD & Reset command (See SH2 Ref. Manual 6.4)
 
-static const constexpr uint8_t SHTP_REPORT_COMMAND_RESPONSE = 0xF1
 See SH2 Ref. Manual 6.3.9.
static const constexpr uint8_t SHTP_REPORT_COMMAND_RESPONSE = 0xF1
 See SH2 Ref. Manual 6.3.9.
 
-static const constexpr uint8_t SHTP_REPORT_COMMAND_REQUEST = 0xF2
 See SH2 Ref. Manual 6.3.8.
static const constexpr uint8_t SHTP_REPORT_COMMAND_REQUEST = 0xF2
 See SH2 Ref. Manual 6.3.8.
 
-static const constexpr uint8_t SHTP_REPORT_FRS_READ_RESPONSE = 0xF3
 See SH2 Ref. Manual 6.3.7.
static const constexpr uint8_t SHTP_REPORT_FRS_READ_RESPONSE = 0xF3
 See SH2 Ref. Manual 6.3.7.
 
-static const constexpr uint8_t SHTP_REPORT_FRS_READ_REQUEST = 0xF4
 See SH2 Ref. Manual 6.3.6.
static const constexpr uint8_t SHTP_REPORT_FRS_READ_REQUEST = 0xF4
 See SH2 Ref. Manual 6.3.6.
 
-static const constexpr uint8_t SHTP_REPORT_PRODUCT_ID_RESPONSE = 0xF8
 See SH2 Ref. Manual 6.3.2.
static const constexpr uint8_t SHTP_REPORT_PRODUCT_ID_RESPONSE = 0xF8
 See SH2 Ref. Manual 6.3.2.
 
-static const constexpr uint8_t SHTP_REPORT_PRODUCT_ID_REQUEST = 0xF9
 See SH2 Ref. Manual 6.3.1.
static const constexpr uint8_t SHTP_REPORT_PRODUCT_ID_REQUEST = 0xF9
 See SH2 Ref. Manual 6.3.1.
 
-static const constexpr uint8_t SHTP_REPORT_BASE_TIMESTAMP = 0xFB
 See SH2 Ref. Manual 7.2.1.
static const constexpr uint8_t SHTP_REPORT_BASE_TIMESTAMP = 0xFB
 See SH2 Ref. Manual 7.2.1.
 
-static const constexpr uint8_t SHTP_REPORT_SET_FEATURE_COMMAND = 0xFD
 See SH2 Ref. Manual 6.5.4.
static const constexpr uint8_t SHTP_REPORT_SET_FEATURE_COMMAND = 0xFD
 See SH2 Ref. Manual 6.5.4.
 
-static const constexpr uint8_t SENSOR_REPORTID_ACCELEROMETER = 0x01
 See SH2 Ref. Manual 6.5.9.
static const constexpr uint8_t SENSOR_REPORTID_ACCELEROMETER = 0x01
 See SH2 Ref. Manual 6.5.9.
 
-static const constexpr uint8_t SENSOR_REPORTID_GYROSCOPE = 0x02
 See SH2 Ref. Manual 6.5.13.
static const constexpr uint8_t SENSOR_REPORTID_GYROSCOPE = 0x02
 See SH2 Ref. Manual 6.5.13.
 
-static const constexpr uint8_t SENSOR_REPORTID_MAGNETIC_FIELD = 0x03
 See SH2 Ref. Manual 6.5.16.
static const constexpr uint8_t SENSOR_REPORTID_MAGNETIC_FIELD = 0x03
 See SH2 Ref. Manual 6.5.16.
 
-static const constexpr uint8_t SENSOR_REPORTID_LINEAR_ACCELERATION = 0x04
 See SH2 Ref. Manual 6.5.10.
static const constexpr uint8_t SENSOR_REPORTID_LINEAR_ACCELERATION = 0x04
 See SH2 Ref. Manual 6.5.10.
 
-static const constexpr uint8_t SENSOR_REPORTID_ROTATION_VECTOR = 0x05
 See SH2 Ref. Manual 6.5.18.
static const constexpr uint8_t SENSOR_REPORTID_ROTATION_VECTOR = 0x05
 See SH2 Ref. Manual 6.5.18.
 
-static const constexpr uint8_t SENSOR_REPORTID_GRAVITY = 0x06
 See SH2 Ref. Manual 6.5.11.
static const constexpr uint8_t SENSOR_REPORTID_GRAVITY = 0x06
 See SH2 Ref. Manual 6.5.11.
 
-static const constexpr uint8_t SENSOR_REPORTID_UNCALIBRATED_GYRO = 0x07
 See SH2 Ref. Manual 6.5.14.
static const constexpr uint8_t SENSOR_REPORTID_UNCALIBRATED_GYRO = 0x07
 See SH2 Ref. Manual 6.5.14.
 
-static const constexpr uint8_t SENSOR_REPORTID_GAME_ROTATION_VECTOR = 0x08
 See SH2 Ref. Manual 6.5.19.
static const constexpr uint8_t SENSOR_REPORTID_GAME_ROTATION_VECTOR = 0x08
 See SH2 Ref. Manual 6.5.19.
 
-static const constexpr uint8_t SENSOR_REPORTID_GEOMAGNETIC_ROTATION_VECTOR = 0x09
 See SH2 Ref. Manual 6.5.20.
static const constexpr uint8_t SENSOR_REPORTID_GEOMAGNETIC_ROTATION_VECTOR = 0x09
 See SH2 Ref. Manual 6.5.20.
 
-static const constexpr uint8_t SENSOR_REPORTID_GYRO_INTEGRATED_ROTATION_VECTOR = 0x2A
 See SH2 Ref. Manual 6.5.44.
static const constexpr uint8_t SENSOR_REPORTID_GYRO_INTEGRATED_ROTATION_VECTOR = 0x2A
 See SH2 Ref. Manual 6.5.44.
 
-static const constexpr uint8_t SENSOR_REPORTID_TAP_DETECTOR = 0x10
 See SH2 Ref. Manual 6.5.27.
static const constexpr uint8_t SENSOR_REPORTID_TAP_DETECTOR = 0x10
 See SH2 Ref. Manual 6.5.27.
 
-static const constexpr uint8_t SENSOR_REPORTID_STEP_COUNTER = 0x11
 See SH2 Ref. Manual 6.5.29.
static const constexpr uint8_t SENSOR_REPORTID_STEP_COUNTER = 0x11
 See SH2 Ref. Manual 6.5.29.
 
-static const constexpr uint8_t SENSOR_REPORTID_STABILITY_CLASSIFIER = 0x13
 See SH2 Ref. Manual 6.5.31.
static const constexpr uint8_t SENSOR_REPORTID_STABILITY_CLASSIFIER = 0x13
 See SH2 Ref. Manual 6.5.31.
 
-static const constexpr uint8_t SENSOR_REPORTID_RAW_ACCELEROMETER = 0x14
 See SH2 Ref. Manual 6.5.8.
static const constexpr uint8_t SENSOR_REPORTID_RAW_ACCELEROMETER = 0x14
 See SH2 Ref. Manual 6.5.8.
 
-static const constexpr uint8_t SENSOR_REPORTID_RAW_GYROSCOPE = 0x15
 See SH2 Ref. Manual 6.5.12.
static const constexpr uint8_t SENSOR_REPORTID_RAW_GYROSCOPE = 0x15
 See SH2 Ref. Manual 6.5.12.
 
-static const constexpr uint8_t SENSOR_REPORTID_RAW_MAGNETOMETER = 0x16
 See SH2 Ref. Manual 6.5.15.
static const constexpr uint8_t SENSOR_REPORTID_RAW_MAGNETOMETER = 0x16
 See SH2 Ref. Manual 6.5.15.
 
-static const constexpr uint8_t SENSOR_REPORTID_PERSONAL_ACTIVITY_CLASSIFIER = 0x1E
 See SH2 Ref. Manual 6.5.36.
static const constexpr uint8_t SENSOR_REPORTID_PERSONAL_ACTIVITY_CLASSIFIER = 0x1E
 See SH2 Ref. Manual 6.5.36.
 
-static const constexpr uint8_t SENSOR_REPORTID_AR_VR_STABILIZED_ROTATION_VECTOR = 0x28
 See SH2 Ref. Manual 6.5.42.
static const constexpr uint8_t SENSOR_REPORTID_AR_VR_STABILIZED_ROTATION_VECTOR = 0x28
 See SH2 Ref. Manual 6.5.42.
 
-static const constexpr uint8_t SENSOR_REPORTID_AR_VR_STABILIZED_GAME_ROTATION_VECTOR = 0x29
 See SH2 Ref. Manual 6.5.43.
static const constexpr uint8_t SENSOR_REPORTID_AR_VR_STABILIZED_GAME_ROTATION_VECTOR = 0x29
 See SH2 Ref. Manual 6.5.43.
 
-static const constexpr uint8_t TARE_NOW = 0
 See SH2 Ref. Manual 6.4.4.1.
static const constexpr uint8_t TARE_NOW = 0
 See SH2 Ref. Manual 6.4.4.1.
 
-static const constexpr uint8_t TARE_PERSIST = 1
 See SH2 Ref. Manual 6.4.4.2.
static const constexpr uint8_t TARE_PERSIST = 1
 See SH2 Ref. Manual 6.4.4.2.
 
-static const constexpr uint8_t TARE_SET_REORIENTATION = 2
 See SH2 Ref. Manual 6.4.4.3.
static const constexpr uint8_t TARE_SET_REORIENTATION = 2
 See SH2 Ref. Manual 6.4.4.3.
 
-static const constexpr uint8_t TARE_AXIS_ALL = 0x07
 Tare all axes (used with tare now command)
 
-static const constexpr uint8_t TARE_AXIS_Z = 0x04
 Tar yaw axis only (used with tare now command)
 
-static const constexpr uint8_t TARE_ROTATION_VECTOR = 0
 Tare rotation vector.
 
-static const constexpr uint8_t TARE_GAME_ROTATION_VECTOR = 1
 Tare game rotation vector.
 
-static const constexpr uint8_t TARE_GEOMAGNETIC_ROTATION_VECTOR = 2
 tare geomagnetic rotation vector
 
-static const constexpr uint8_t TARE_GYRO_INTEGRATED_ROTATION_VECTOR = 3
 Tare gyro integrated rotation vector.
 
-static const constexpr uint8_t TARE_AR_VR_STABILIZED_ROTATION_VECTOR = 4
 Tare ARVR stabilized rotation vector.
 
-static const constexpr uint8_t TARE_AR_VR_STABILIZED_GAME_ROTATION_VECTOR = 5
 Tare ARVR stabilized game rotation vector.
 
-static const constexpr char * TAG = "BNO08x"
 Class tag used for serial print statements.
static const constexpr char * TAG = "BNO08x"
 Class tag used for serial print statements.
 

Constructor & Destructor Documentation

@@ -1018,8 +880,7 @@ static const constexpr char *  BNO08x::BNO08x ( - bno08x_config_t  - imu_config = default_imu_config) + bno08x_config_t imu_config = default_imu_config) @@ -1047,7 +908,7 @@ static const constexpr char *  void BNO08x::calibrate_accelerometer ( - ) + ) @@ -1067,7 +928,7 @@ static const constexpr char *  void BNO08x::calibrate_all ( - ) + ) @@ -1087,7 +948,7 @@ static const constexpr char *  void BNO08x::calibrate_gyro ( - ) + ) @@ -1107,7 +968,7 @@ static const constexpr char *  void BNO08x::calibrate_magnetometer ( - ) + ) @@ -1127,7 +988,7 @@ static const constexpr char *  void BNO08x::calibrate_planar_accelerometer ( - ) + ) @@ -1147,7 +1008,7 @@ static const constexpr char *  bool BNO08x::calibration_complete ( - ) + ) @@ -1167,7 +1028,7 @@ static const constexpr char *  void BNO08x::clear_tare ( - ) + ) @@ -1187,7 +1048,7 @@ static const constexpr char *  bool BNO08x::data_available ( - ) + ) @@ -1207,8 +1068,7 @@ static const constexpr char *  void BNO08x::enable_accelerometer ( - uint16_t  - time_between_reports) + uint16_t time_between_reports) @@ -1234,25 +1094,17 @@ static const constexpr char *  void BNO08x::enable_activity_classifier ( - uint16_t  - time_between_reports, + uint16_t time_between_reports, - uint32_t  - activities_to_enable, + uint32_t activities_to_enable, - uint8_t(&)  - activity_confidence_vals[9]  - - - - ) - + uint8_t(&) activity_confidence_vals[9] )
@@ -1279,8 +1131,7 @@ static const constexpr char *  void BNO08x::enable_ARVR_stabilized_game_rotation_vector ( - uint16_t  - time_between_reports) + uint16_t time_between_reports) @@ -1306,8 +1157,7 @@ static const constexpr char *  void BNO08x::enable_ARVR_stabilized_rotation_vector ( - uint16_t  - time_between_reports) + uint16_t time_between_reports) @@ -1333,8 +1183,7 @@ static const constexpr char *  void BNO08x::enable_game_rotation_vector ( - uint16_t  - time_between_reports) + uint16_t time_between_reports) @@ -1360,8 +1209,7 @@ static const constexpr char *  void BNO08x::enable_gravity ( - uint16_t  - time_between_reports) + uint16_t time_between_reports) @@ -1387,8 +1235,7 @@ static const constexpr char *  void BNO08x::enable_gyro ( - uint16_t  - time_between_reports) + uint16_t time_between_reports) @@ -1414,8 +1261,7 @@ static const constexpr char *  void BNO08x::enable_gyro_integrated_rotation_vector ( - uint16_t  - time_between_reports) + uint16_t time_between_reports) @@ -1441,8 +1287,7 @@ static const constexpr char *  void BNO08x::enable_linear_accelerometer ( - uint16_t  - time_between_reports) + uint16_t time_between_reports) @@ -1468,8 +1313,7 @@ static const constexpr char *  void BNO08x::enable_magnetometer ( - uint16_t  - time_between_reports) + uint16_t time_between_reports) @@ -1495,8 +1339,7 @@ static const constexpr char *  void BNO08x::enable_raw_accelerometer ( - uint16_t  - time_between_reports) + uint16_t time_between_reports) @@ -1522,8 +1365,7 @@ static const constexpr char *  void BNO08x::enable_raw_gyro ( - uint16_t  - time_between_reports) + uint16_t time_between_reports) @@ -1549,8 +1391,7 @@ static const constexpr char *  void BNO08x::enable_raw_magnetometer ( - uint16_t  - time_between_reports) + uint16_t time_between_reports) @@ -1576,8 +1417,7 @@ static const constexpr char *  void BNO08x::enable_rotation_vector ( - uint16_t  - time_between_reports) + uint16_t time_between_reports) @@ -1603,8 +1443,7 @@ static const constexpr char *  void BNO08x::enable_stability_classifier ( - uint16_t  - time_between_reports) + uint16_t time_between_reports) @@ -1630,8 +1469,7 @@ static const constexpr char *  void BNO08x::enable_step_counter ( - uint16_t  - time_between_reports) + uint16_t time_between_reports) @@ -1657,8 +1495,7 @@ static const constexpr char *  void BNO08x::enable_tap_detector ( - uint16_t  - time_between_reports) + uint16_t time_between_reports) @@ -1684,8 +1521,7 @@ static const constexpr char *  void BNO08x::enable_uncalibrated_gyro ( - uint16_t  - time_between_reports) + uint16_t time_between_reports) @@ -1711,7 +1547,7 @@ static const constexpr char *  void BNO08x::end_calibration ( - ) + ) @@ -1731,25 +1567,17 @@ static const constexpr char *  bool BNO08x::FRS_read_data ( - uint16_t  - record_ID, + uint16_t record_ID, - uint8_t  - start_location, + uint8_t start_location, - uint8_t  - words_to_read  - - - - ) - + uint8_t words_to_read )
@@ -1777,25 +1605,17 @@ static const constexpr char *  bool BNO08x::FRS_read_request ( - uint16_t  - record_ID, + uint16_t record_ID, - uint16_t  - read_offset, + uint16_t read_offset, - uint16_t  - block_size  - - - - ) - + uint16_t block_size )
@@ -1823,19 +1643,12 @@ static const constexpr char *  uint32_t BNO08x::FRS_read_word ( - uint16_t  - record_ID, + uint16_t record_ID, - uint8_t  - word_number  - - - - ) - + uint8_t word_number )
@@ -1862,31 +1675,22 @@ static const constexpr char *  void BNO08x::get_accel ( - float &  - x, + float & x, - float &  - y, + float & y, - float &  - z, + float & z, - uint8_t &  - accuracy  - - - - ) - + uint8_t & accuracy )
@@ -1914,7 +1718,7 @@ static const constexpr char *  uint8_t BNO08x::get_accel_accuracy ( - ) + ) @@ -1934,7 +1738,7 @@ static const constexpr char *  float BNO08x::get_accel_X ( - ) + ) @@ -1954,7 +1758,7 @@ static const constexpr char *  float BNO08x::get_accel_Y ( - ) + ) @@ -1974,7 +1778,7 @@ static const constexpr char *  float BNO08x::get_accel_Z ( - ) + ) @@ -1994,7 +1798,7 @@ static const constexpr char *  uint8_t BNO08x::get_activity_classifier ( - ) + ) @@ -2014,31 +1818,22 @@ static const constexpr char *  void BNO08x::get_gravity ( - float &  - x, + float & x, - float &  - y, + float & y, - float &  - z, + float & z, - uint8_t &  - accuracy  - - - - ) - + uint8_t & accuracy )
@@ -2066,15 +1861,14 @@ static const constexpr char *  uint8_t BNO08x::get_gravity_accuracy ( - ) + )

Get the reported gravity accuracy.

-
Returns
Accuracy of reported gravity.
-
+
Returns
Accuracy of reported gravity.
@@ -2087,7 +1881,7 @@ static const constexpr char *  float BNO08x::get_gravity_X ( - ) + ) @@ -2107,7 +1901,7 @@ static const constexpr char *  float BNO08x::get_gravity_Y ( - ) + ) @@ -2127,7 +1921,7 @@ static const constexpr char *  float BNO08x::get_gravity_Z ( - ) + ) @@ -2147,7 +1941,7 @@ static const constexpr char *  uint8_t BNO08x::get_gyro_accuracy ( - ) + ) @@ -2167,31 +1961,22 @@ static const constexpr char *  void BNO08x::get_gyro_calibrated_velocity ( - float &  - x, + float & x, - float &  - y, + float & y, - float &  - z, + float & z, - uint8_t &  - accuracy  - - - - ) - + uint8_t & accuracy )
@@ -2219,7 +2004,7 @@ static const constexpr char *  float BNO08x::get_gyro_calibrated_velocity_X ( - ) + ) @@ -2239,7 +2024,7 @@ static const constexpr char *  float BNO08x::get_gyro_calibrated_velocity_Y ( - ) + ) @@ -2259,7 +2044,7 @@ static const constexpr char *  float BNO08x::get_gyro_calibrated_velocity_Z ( - ) + ) @@ -2279,25 +2064,17 @@ static const constexpr char *  void BNO08x::get_gyro_velocity ( - float &  - x, + float & x, - float &  - y, + float & y, - float &  - z  - - - - ) - + float & z )
@@ -2324,7 +2101,7 @@ static const constexpr char *  float BNO08x::get_gyro_velocity_X ( - ) + ) @@ -2344,7 +2121,7 @@ static const constexpr char *  float BNO08x::get_gyro_velocity_Y ( - ) + ) @@ -2364,7 +2141,7 @@ static const constexpr char *  float BNO08x::get_gyro_velocity_Z ( - ) + ) @@ -2384,31 +2161,22 @@ static const constexpr char *  void BNO08x::get_linear_accel ( - float &  - x, + float & x, - float &  - y, + float & y, - float &  - z, + float & z, - uint8_t &  - accuracy  - - - - ) - + uint8_t & accuracy )
@@ -2436,7 +2204,7 @@ static const constexpr char *  uint8_t BNO08x::get_linear_accel_accuracy ( - ) + ) @@ -2456,7 +2224,7 @@ static const constexpr char *  float BNO08x::get_linear_accel_X ( - ) + ) @@ -2476,7 +2244,7 @@ static const constexpr char *  float BNO08x::get_linear_accel_Y ( - ) + ) @@ -2496,7 +2264,7 @@ static const constexpr char *  float BNO08x::get_linear_accel_Z ( - ) + ) @@ -2516,31 +2284,22 @@ static const constexpr char *  void BNO08x::get_magf ( - float &  - x, + float & x, - float &  - y, + float & y, - float &  - z, + float & z, - uint8_t &  - accuracy  - - - - ) - + uint8_t & accuracy )
@@ -2568,7 +2327,7 @@ static const constexpr char *  uint8_t BNO08x::get_magf_accuracy ( - ) + ) @@ -2588,7 +2347,7 @@ static const constexpr char *  float BNO08x::get_magf_X ( - ) + ) @@ -2608,7 +2367,7 @@ static const constexpr char *  float BNO08x::get_magf_Y ( - ) + ) @@ -2628,7 +2387,7 @@ static const constexpr char *  float BNO08x::get_magf_Z ( - ) + ) @@ -2648,7 +2407,7 @@ static const constexpr char *  float BNO08x::get_pitch ( - ) + ) @@ -2668,7 +2427,7 @@ static const constexpr char *  float BNO08x::get_pitch_deg ( - ) + ) @@ -2688,8 +2447,7 @@ static const constexpr char *  int16_t BNO08x::get_Q1 ( - uint16_t  - record_ID) + uint16_t record_ID) @@ -2716,8 +2474,7 @@ static const constexpr char *  int16_t BNO08x::get_Q2 ( - uint16_t  - record_ID) + uint16_t record_ID) @@ -2744,8 +2501,7 @@ static const constexpr char *  int16_t BNO08x::get_Q3 ( - uint16_t  - record_ID) + uint16_t record_ID) @@ -2772,43 +2528,32 @@ static const constexpr char *  void BNO08x::get_quat ( - float &  - i, + float & i, - float &  - j, + float & j, - float &  - k, + float & k, - float &  - real, + float & real, - float &  - rad_accuracy, + float & rad_accuracy, - uint8_t &  - accuracy  - - - - ) - + uint8_t & accuracy )
@@ -2838,7 +2583,7 @@ static const constexpr char *  uint8_t BNO08x::get_quat_accuracy ( - ) + ) @@ -2858,7 +2603,7 @@ static const constexpr char *  float BNO08x::get_quat_I ( - ) + ) @@ -2878,7 +2623,7 @@ static const constexpr char *  float BNO08x::get_quat_J ( - ) + ) @@ -2898,7 +2643,7 @@ static const constexpr char *  float BNO08x::get_quat_K ( - ) + ) @@ -2918,7 +2663,7 @@ static const constexpr char *  float BNO08x::get_quat_radian_accuracy ( - ) + ) @@ -2938,7 +2683,7 @@ static const constexpr char *  float BNO08x::get_quat_real ( - ) + ) @@ -2958,8 +2703,7 @@ static const constexpr char *  float BNO08x::get_range ( - uint16_t  - record_ID) + uint16_t record_ID) @@ -2985,7 +2729,7 @@ static const constexpr char *  int16_t BNO08x::get_raw_accel_X ( - ) + ) @@ -3005,7 +2749,7 @@ static const constexpr char *  int16_t BNO08x::get_raw_accel_Y ( - ) + ) @@ -3025,7 +2769,7 @@ static const constexpr char *  int16_t BNO08x::get_raw_accel_Z ( - ) + ) @@ -3045,7 +2789,7 @@ static const constexpr char *  int16_t BNO08x::get_raw_gyro_X ( - ) + ) @@ -3065,7 +2809,7 @@ static const constexpr char *  int16_t BNO08x::get_raw_gyro_Y ( - ) + ) @@ -3085,7 +2829,7 @@ static const constexpr char *  int16_t BNO08x::get_raw_gyro_Z ( - ) + ) @@ -3105,7 +2849,7 @@ static const constexpr char *  int16_t BNO08x::get_raw_magf_X ( - ) + ) @@ -3125,7 +2869,7 @@ static const constexpr char *  int16_t BNO08x::get_raw_magf_Y ( - ) + ) @@ -3145,7 +2889,7 @@ static const constexpr char *  int16_t BNO08x::get_raw_magf_Z ( - ) + ) @@ -3165,7 +2909,7 @@ static const constexpr char *  uint16_t BNO08x::get_readings ( - ) + ) @@ -3185,7 +2929,7 @@ static const constexpr char *  uint8_t BNO08x::get_reset_reason ( - ) + ) @@ -3205,8 +2949,7 @@ static const constexpr char *  float BNO08x::get_resolution ( - uint16_t  - record_ID) + uint16_t record_ID) @@ -3232,7 +2975,7 @@ static const constexpr char *  float BNO08x::get_roll ( - ) + ) @@ -3252,7 +2995,7 @@ static const constexpr char *  float BNO08x::get_roll_deg ( - ) + ) @@ -3272,7 +3015,7 @@ static const constexpr char *  int8_t BNO08x::get_stability_classifier ( - ) + ) @@ -3292,7 +3035,7 @@ static const constexpr char *  uint16_t BNO08x::get_step_count ( - ) + ) @@ -3312,7 +3055,7 @@ static const constexpr char *  uint8_t BNO08x::get_tap_detector ( - ) + ) @@ -3332,7 +3075,7 @@ static const constexpr char *  uint32_t BNO08x::get_time_stamp ( - ) + ) @@ -3352,49 +3095,37 @@ static const constexpr char *  void BNO08x::get_uncalibrated_gyro ( - float &  - x, + float & x, - float &  - y, + float & y, - float &  - z, + float & z, - float &  - b_x, + float & b_x, - float &  - b_y, + float & b_y, - float &  - b_z, + float & b_z, - uint8_t &  - accuracy  - - - - ) - + uint8_t & accuracy )
@@ -3425,7 +3156,7 @@ static const constexpr char *  uint8_t BNO08x::get_uncalibrated_gyro_accuracy ( - ) + ) @@ -3445,7 +3176,7 @@ static const constexpr char *  float BNO08x::get_uncalibrated_gyro_bias_X ( - ) + ) @@ -3465,7 +3196,7 @@ static const constexpr char *  float BNO08x::get_uncalibrated_gyro_bias_Y ( - ) + ) @@ -3485,7 +3216,7 @@ static const constexpr char *  float BNO08x::get_uncalibrated_gyro_bias_Z ( - ) + ) @@ -3505,7 +3236,7 @@ static const constexpr char *  float BNO08x::get_uncalibrated_gyro_X ( - ) + ) @@ -3525,7 +3256,7 @@ static const constexpr char *  float BNO08x::get_uncalibrated_gyro_Y ( - ) + ) @@ -3545,7 +3276,7 @@ static const constexpr char *  float BNO08x::get_uncalibrated_gyro_Z ( - ) + ) @@ -3565,7 +3296,7 @@ static const constexpr char *  float BNO08x::get_yaw ( - ) + ) @@ -3585,7 +3316,7 @@ static const constexpr char *  float BNO08x::get_yaw_deg ( - ) + ) @@ -3605,7 +3336,7 @@ static const constexpr char *  bool BNO08x::hard_reset ( - ) + ) @@ -3628,8 +3359,7 @@ static const constexpr char *  void IRAM_ATTR BNO08x::hint_handler ( - void *  - arg) + void * arg) @@ -3655,7 +3385,7 @@ static const constexpr char *  bool BNO08x::initialize ( - ) + ) @@ -3676,7 +3406,7 @@ static const constexpr char *  bool BNO08x::mode_on ( - ) + ) @@ -3696,7 +3426,7 @@ static const constexpr char *  bool BNO08x::mode_sleep ( - ) + ) @@ -3716,7 +3446,7 @@ static const constexpr char *  uint16_t BNO08x::parse_command_report ( - ) + ) @@ -3736,7 +3466,7 @@ static const constexpr char *  uint16_t BNO08x::parse_input_report ( - ) + ) @@ -3758,7 +3488,7 @@ static const constexpr char *  void BNO08x::print_header ( - ) + ) @@ -3767,6 +3497,23 @@ static const constexpr char * Prints the most recently received SHTP header to serial console with ESP_LOG statement.

Returns
void, nothing to return
+
+ + +

◆ print_packet()

+ +
+
+ + + + + + + +
void BNO08x::print_packet ()
+
+
@@ -3778,19 +3525,12 @@ static const constexpr char *  float BNO08x::q_to_float ( - int16_t  - fixed_point_value, + int16_t fixed_point_value, - uint8_t  - q_point  - - - - ) - + uint8_t q_point )
@@ -3819,8 +3559,7 @@ static const constexpr char *  void BNO08x::queue_calibrate_command ( - uint8_t  - sensor_to_calibrate) + uint8_t sensor_to_calibrate) @@ -3854,8 +3593,7 @@ static const constexpr char *  void BNO08x::queue_command ( - uint8_t  - command) + uint8_t command) @@ -3889,19 +3627,12 @@ static const constexpr char *  void BNO08x::queue_feature_command ( - uint8_t  - report_ID, + uint8_t report_ID, - uint16_t  - time_between_reports  - - - - ) - + uint16_t time_between_reports ) @@ -3935,25 +3666,17 @@ static const constexpr char *  void BNO08x::queue_feature_command ( - uint8_t  - report_ID, + uint8_t report_ID, - uint16_t  - time_between_reports, + uint16_t time_between_reports, - uint32_t  - specific_config  - - - - ) - + uint32_t specific_config ) @@ -3988,19 +3711,12 @@ static const constexpr char *  void BNO08x::queue_packet ( - uint8_t  - channel_number, + uint8_t channel_number, - uint8_t  - data_length  - - - - ) - + uint8_t data_length ) @@ -4027,7 +3743,7 @@ static const constexpr char *  void BNO08x::queue_request_product_id_command ( - ) + ) @@ -4055,25 +3771,17 @@ static const constexpr char *  void BNO08x::queue_tare_command ( - uint8_t  - command, + uint8_t command, - uint8_t  - axis = TARE_AXIS_ALL, + uint8_t axis = TARE_AXIS_ALL, - uint8_t  - rotation_vector_basis = TARE_ROTATION_VECTOR  - - - - ) - + uint8_t rotation_vector_basis = TARE_ROTATION_VECTOR ) @@ -4086,8 +3794,7 @@ static const constexpr char * Queues a packet containing a command related to zeroing sensor's axes. (See Ref. Manual 6.4.4.1)

Parameters
- +
commandTare command to be sent.
-
commandTare command to be sent.
axisSpecified axis (can be z or all at once)
rotation_vector_basisWhich rotation vector type to zero axes of, BNO08x saves seperate data for Rotation Vector, Gaming Rotation Vector, etc..)
@@ -4109,7 +3816,7 @@ static const constexpr char *  bool BNO08x::receive_packet ( - ) + ) @@ -4134,7 +3841,7 @@ static const constexpr char *  void BNO08x::request_calibration_status ( - ) + ) @@ -4154,7 +3861,7 @@ static const constexpr char *  bool BNO08x::run_full_calibration_routine ( - ) + ) @@ -4175,7 +3882,7 @@ static const constexpr char *  void BNO08x::save_calibration ( - ) + ) @@ -4195,7 +3902,7 @@ static const constexpr char *  void BNO08x::save_tare ( - ) + ) @@ -4218,7 +3925,7 @@ static const constexpr char *  void BNO08x::send_packet ( - ) + ) @@ -4243,7 +3950,7 @@ static const constexpr char *  bool BNO08x::soft_reset ( - ) + ) @@ -4266,7 +3973,7 @@ static const constexpr char *  void BNO08x::spi_task ( - ) + ) @@ -4294,8 +4001,7 @@ static const constexpr char *  void BNO08x::spi_task_trampoline ( - void *  - arg) + void * arg) @@ -4307,7 +4013,7 @@ static const constexpr char * 

Static function used to launch spi task.

-

Used such that spi_task() can be non-static class member.

+

Used such that spi_task() can be non-static class member.

Returns
void, nothing to return
@@ -4321,19 +4027,12 @@ static const constexpr char *  void BNO08x::tare_now ( - uint8_t  - axis_sel = TARE_AXIS_ALL, + uint8_t axis_sel = TARE_AXIS_ALL, - uint8_t  - rotation_vector_basis = TARE_ROTATION_VECTOR  - - - - ) - + uint8_t rotation_vector_basis = TARE_ROTATION_VECTOR )
@@ -4362,7 +4061,7 @@ static const constexpr char *  bool BNO08x::wait_for_device_int ( - ) + ) @@ -4376,16 +4075,3277 @@ static const constexpr char * Re-enables interrupts and waits for BNO08x to assert HINT pin.

Returns
void, nothing to return
+
+ +

Member Data Documentation

+ +

◆ accel_accuracy

+ +
+
+ + + + + +
+ + + + +
uint16_t BNO08x::accel_accuracy
+
+private
+
+ +

Raw acceleration readings (See SH-2 Ref. Manual 6.5.8)

+ +
+
+ +

◆ accel_lin_accuracy

+ +
+
+ + + + + +
+ + + + +
uint16_t BNO08x::accel_lin_accuracy
+
+private
+
+ +

Raw linear acceleration (See SH-2 Ref. Manual 6.5.10)

+ +
+
+ +

◆ ACCELEROMETER_Q1

+ +
+
+ + + + + +
+ + + + +
const constexpr int16_t BNO08x::ACCELEROMETER_Q1 = 8
+
+staticconstexpr
+
+ +

Acceleration Q point (See SH-2 Ref. Manual 6.5.9)

+ +
+
+ +

◆ activity_classifier

+ +
+
+ + + + + +
+ + + + +
uint8_t BNO08x::activity_classifier
+
+private
+
+ +

Activity status reading (See SH-2 Ref. Manual 6.5.36)

+ +
+
+ +

◆ activity_confidences

+ +
+
+ + + + + +
+ + + + +
uint8_t* BNO08x::activity_confidences
+
+private
+
+ +

Confidence of read activities (See SH-2 Ref. Manual 6.5.36)

+ +
+
+ +

◆ ANGULAR_VELOCITY_Q1

+ +
+
+ + + + + +
+ + + + +
const constexpr int16_t BNO08x::ANGULAR_VELOCITY_Q1 = 10
+
+staticconstexpr
+
+ +

Angular velocity Q point (See SH-2 Ref. Manual 6.5.44)

+ +
+
+ +

◆ bus_config

+ +
+
+ + + + + +
+ + + + +
spi_bus_config_t BNO08x::bus_config {}
+
+private
+
+ +

SPI bus GPIO configuration settings.

+ +
+
+ +

◆ CALIBRATE_ACCEL

+ +
+
+ + + + + +
+ + + + +
const constexpr uint8_t BNO08x::CALIBRATE_ACCEL = 0
+
+staticconstexprprivate
+
+ +

Calibrate accelerometer command used by queue_calibrate_command.

+ +
+
+ +

◆ CALIBRATE_ACCEL_GYRO_MAG

+ +
+
+ + + + + +
+ + + + +
const constexpr uint8_t BNO08x::CALIBRATE_ACCEL_GYRO_MAG
+
+staticconstexprprivate
+
+Initial value:
=
+
4
+
+

Calibrate accelerometer, gyro, & magnetometer command used by queue_calibrate_command.

+ +
+
+ +

◆ CALIBRATE_GYRO

+ +
+
+ + + + + +
+ + + + +
const constexpr uint8_t BNO08x::CALIBRATE_GYRO = 1
+
+staticconstexprprivate
+
+ +

Calibrate gyro command used by queue_calibrate_command.

+ +
+
+ +

◆ CALIBRATE_MAG

+ +
+
+ + + + + +
+ + + + +
const constexpr uint8_t BNO08x::CALIBRATE_MAG = 2
+
+staticconstexprprivate
+
+ +

Calibrate magnetometer command used by queue_calibrate_command.

+ +
+
+ +

◆ CALIBRATE_PLANAR_ACCEL

+ +
+
+ + + + + +
+ + + + +
const constexpr uint8_t BNO08x::CALIBRATE_PLANAR_ACCEL = 3
+
+staticconstexprprivate
+
+ +

Calibrate planar acceleration command used by queue_calibrate_command.

+ +
+
+ +

◆ CALIBRATE_STOP

+ +
+
+ + + + + +
+ + + + +
const constexpr uint8_t BNO08x::CALIBRATE_STOP = 5
+
+staticconstexprprivate
+
+ +

Stop calibration command used by queue_calibrate_command.

+ +
+
+ +

◆ calibration_status

+ +
+
+ + + + + +
+ + + + +
uint8_t BNO08x::calibration_status
+
+private
+
+ +

Calibration status of device (See SH-2 Ref. Manual 6.4.7.1 & 6.4.7.2)

+ +
+
+ +

◆ COMMAND_CLEAR_DCD

+ +
+
+ + + + + +
+ + + + +
const constexpr uint8_t BNO08x::COMMAND_CLEAR_DCD = 11
+
+staticconstexprprivate
+
+ +

Clear DCD & Reset command (See SH2 Ref. Manual 6.4)

+ +
+
+ +

◆ COMMAND_COUNTER

+ +
+
+ + + + + +
+ + + + +
const constexpr uint8_t BNO08x::COMMAND_COUNTER = 2
+
+staticconstexprprivate
+
+ +
+
+ +

◆ COMMAND_DCD

+ +
+
+ + + + + +
+ + + + +
const constexpr uint8_t BNO08x::COMMAND_DCD = 6
+
+staticconstexprprivate
+
+ +

Save DCD command (See SH2 Ref. Manual 6.4.7)

+ +
+
+ +

◆ COMMAND_DCD_PERIOD_SAVE

+ +
+
+ + + + + +
+ + + + +
const constexpr uint8_t BNO08x::COMMAND_DCD_PERIOD_SAVE = 9
+
+staticconstexprprivate
+
+ +

Configure DCD periodic saving (See SH2 Ref. Manual 6.4)

+ +
+
+ +

◆ COMMAND_ERRORS

+ +
+
+ + + + + +
+ + + + +
const constexpr uint8_t BNO08x::COMMAND_ERRORS = 1
+
+staticconstexprprivate
+
+ +
+
+ +

◆ COMMAND_INITIALIZE

+ +
+
+ + + + + +
+ + + + +
const constexpr uint8_t BNO08x::COMMAND_INITIALIZE = 4
+
+staticconstexprprivate
+
+ +

Reinitialize sensor hub components See (SH2 Ref. Manual 6.4.5)

+ +
+
+ +

◆ COMMAND_ME_CALIBRATE

+ +
+
+ + + + + +
+ + + + +
const constexpr uint8_t BNO08x::COMMAND_ME_CALIBRATE = 7
+
+staticconstexprprivate
+
+ +

Command and response to configure ME calibration (See SH2 Ref. Manual 6.4.7)

+ +
+
+ +

◆ COMMAND_OSCILLATOR

+ +
+
+ + + + + +
+ + + + +
const constexpr uint8_t BNO08x::COMMAND_OSCILLATOR = 10
+
+staticconstexprprivate
+
+ +

Retrieve oscillator type command (See SH2 Ref. Manual 6.4)

+ +
+
+ +

◆ command_sequence_number

+ +
+
+ + + + + +
+ + + + +
uint8_t BNO08x::command_sequence_number = 0
+
+private
+
+ +

Sequence num of command, sent within command packet.

+ +
+
+ +

◆ COMMAND_TARE

+ +
+
+ + + + + +
+ + + + +
const constexpr uint8_t BNO08x::COMMAND_TARE = 3
+
+staticconstexprprivate
+
+ +

Command and response to tare command (See Sh2 Ref. Manual 6.4.4)

+ +
+
+ +

◆ commands

+ +
+
+ + + + + +
+ + + + +
uint8_t BNO08x::commands[20]
+
+private
+
+ +

Command to be sent with send_packet()

+ +
+
+ +

◆ default_imu_config

+ +
+
+ + + + + +
+ + + + +
bno08x_config_t BNO08x::default_imu_config
+
+staticprivate
+
+ +

default imu config settings

+ +
+
+ +

◆ FRS_RECORDID_ACCELEROMETER

+ +
+
+ + + + + +
+ + + + +
const constexpr uint16_t BNO08x::FRS_RECORDID_ACCELEROMETER = 0xE302
+
+staticconstexpr
+
+ +
+
+ +

◆ FRS_RECORDID_GYROSCOPE_CALIBRATED

+ +
+
+ + + + + +
+ + + + +
const constexpr uint16_t BNO08x::FRS_RECORDID_GYROSCOPE_CALIBRATED = 0xE306
+
+staticconstexpr
+
+ +
+
+ +

◆ FRS_RECORDID_MAGNETIC_FIELD_CALIBRATED

+ +
+
+ + + + + +
+ + + + +
const constexpr uint16_t BNO08x::FRS_RECORDID_MAGNETIC_FIELD_CALIBRATED = 0xE309
+
+staticconstexpr
+
+ +
+
+ +

◆ FRS_RECORDID_ROTATION_VECTOR

+ +
+
+ + + + + +
+ + + + +
const constexpr uint16_t BNO08x::FRS_RECORDID_ROTATION_VECTOR = 0xE30B
+
+staticconstexpr
+
+ +
+
+ +

◆ gravity_accuracy

+ +
+
+ + + + + +
+ + + + +
uint16_t BNO08x::gravity_accuracy
+
+private
+
+ +

Gravity reading in m/s^2 (See SH-2 Ref. Manual 6.5.11)

+ +
+
+ +

◆ GRAVITY_Q1

+ +
+
+ + + + + +
+ + + + +
const constexpr int16_t BNO08x::GRAVITY_Q1 = 8
+
+staticconstexpr
+
+ +

Gravity Q point (See SH-2 Ref. Manual 6.5.11)

+ +
+
+ +

◆ gravity_X

+ +
+
+ + + + + +
+ + + + +
uint16_t BNO08x::gravity_X
+
+private
+
+ +
+
+ +

◆ gravity_Y

+ +
+
+ + + + + +
+ + + + +
uint16_t BNO08x::gravity_Y
+
+private
+
+ +
+
+ +

◆ gravity_Z

+ +
+
+ + + + + +
+ + + + +
uint16_t BNO08x::gravity_Z
+
+private
+
+ +
+
+ +

◆ gyro_accuracy

+ +
+
+ + + + + +
+ + + + +
uint16_t BNO08x::gyro_accuracy
+
+private
+
+ +

Raw gyro reading (See SH-2 Ref. Manual 6.5.13)

+ +
+
+ +

◆ GYRO_Q1

+ +
+
+ + + + + +
+ + + + +
const constexpr int16_t BNO08x::GYRO_Q1 = 9
+
+staticconstexpr
+
+ +

Gyro Q point (See SH-2 Ref. Manual 6.5.13)

+ +
+
+ +

◆ HOST_INT_TIMEOUT_MS

+ +
+
+ + + + + +
+ + + + +
const constexpr uint64_t BNO08x::HOST_INT_TIMEOUT_MS
+
+staticconstexprprivate
+
+Initial value:
=
+
150ULL
+
+

Max wait between HINT being asserted by BNO08x before transaction is considered failed (in miliseconds)

+ +
+
+ +

◆ imu_config

+ +
+
+ + + + + +
+ + + + +
bno08x_config_t BNO08x::imu_config {}
+
+private
+
+ +

IMU configuration settings.

+ +
+
+ +

◆ imu_spi_config

+ +
+
+ + + + + +
+ + + + +
spi_device_interface_config_t BNO08x::imu_spi_config {}
+
+private
+
+ +

SPI slave device settings.

+ +
+
+ +

◆ int_asserted_semaphore

+ +
+
+ + + + + +
+ + + + +
SemaphoreHandle_t BNO08x::int_asserted_semaphore
+
+private
+
+ +

Binary semaphore used to synchronize spi_task() calling wait_for_device_int(), given after hint_handler ISR launches SPI task and it has run to completion.

+ +
+
+ +

◆ isr_service_installed

+ +
+
+ + + + + +
+ + + + +
bool BNO08x::isr_service_installed = {false}
+
+staticprivate
+
+ +

true of the isr service has been installed, only has to be done once regardless of how many devices are used

+ +
+
+ +

◆ LINEAR_ACCELEROMETER_Q1

+ +
+
+ + + + + +
+ + + + +
const constexpr int16_t BNO08x::LINEAR_ACCELEROMETER_Q1 = 8
+
+staticconstexpr
+
+ +

Linear acceleration Q point (See SH-2 Ref. Manual 6.5.10)

+ +
+
+ +

◆ magf_accuracy

+ +
+
+ + + + + +
+ + + + +
uint16_t BNO08x::magf_accuracy
+
+private
+
+ +

Calibrated magnetic field reading in uTesla (See SH-2 Ref. Manual 6.5.16)

+ +
+
+ +

◆ MAGNETOMETER_Q1

+ +
+
+ + + + + +
+ + + + +
const constexpr int16_t BNO08x::MAGNETOMETER_Q1 = 4
+
+staticconstexpr
+
+ +

Magnetometer Q point (See SH-2 Ref. Manual 6.5.16)

+ +
+
+ +

◆ mems_raw_accel_X

+ +
+
+ + + + + +
+ + + + +
uint16_t BNO08x::mems_raw_accel_X
+
+private
+
+ +
+
+ +

◆ mems_raw_accel_Y

+ +
+
+ + + + + +
+ + + + +
uint16_t BNO08x::mems_raw_accel_Y
+
+private
+
+ +
+
+ +

◆ mems_raw_accel_Z

+ +
+
+ + + + + +
+ + + + +
uint16_t BNO08x::mems_raw_accel_Z
+
+private
+
+ +

Raw accelerometer readings from MEMS sensor (See SH2 Ref. Manual 6.5.8)

+ +
+
+ +

◆ mems_raw_gyro_X

+ +
+
+ + + + + +
+ + + + +
uint16_t BNO08x::mems_raw_gyro_X
+
+private
+
+ +
+
+ +

◆ mems_raw_gyro_Y

+ +
+
+ + + + + +
+ + + + +
uint16_t BNO08x::mems_raw_gyro_Y
+
+private
+
+ +
+
+ +

◆ mems_raw_gyro_Z

+ +
+
+ + + + + +
+ + + + +
uint16_t BNO08x::mems_raw_gyro_Z
+
+private
+
+ +

Raw gyro readings from MEMS sensor (See SH-2 Ref. Manual 6.5.12)

+ +
+
+ +

◆ mems_raw_magf_X

+ +
+
+ + + + + +
+ + + + +
uint16_t BNO08x::mems_raw_magf_X
+
+private
+
+ +
+
+ +

◆ mems_raw_magf_Y

+ +
+
+ + + + + +
+ + + + +
uint16_t BNO08x::mems_raw_magf_Y
+
+private
+
+ +
+
+ +

◆ mems_raw_magf_Z

+ +
+
+ + + + + +
+ + + + +
uint16_t BNO08x::mems_raw_magf_Z
+
+private
+
+ +

Raw magnetometer (compass) readings from MEMS sensor (See SH-2 Ref. Manual 6.5.15)

+ +
+
+ +

◆ meta_data

+ +
+
+ + + + + +
+ + + + +
uint32_t BNO08x::meta_data[9]
+
+private
+
+ +

First 9 bytes of meta data returned from FRS read operation (we don't really need the rest) (See Ref. Manual 5.1)

+ +
+
+ +

◆ packet_header_rx

+ +
+
+ + + + + +
+ + + + +
uint8_t BNO08x::packet_header_rx[4]
+
+private
+
+ +

SHTP header received with receive_packet()

+ +
+
+ +

◆ packet_length_rx

+ +
+
+ + + + + +
+ + + + +
uint16_t BNO08x::packet_length_rx = 0
+
+private
+
+ +

Packet length received (calculated from packet_header_rx)

+ +
+
+ +

◆ packet_length_tx

+ +
+
+ + + + + +
+ + + + +
uint16_t BNO08x::packet_length_tx = 0
+
+private
+
+ +

Packet length to be sent with send_packet()

+ +
+
+ +

◆ quat_accuracy

+ +
+
+ + + + + +
+ + + + +
uint16_t BNO08x::quat_accuracy
+
+private
+
+ +

Raw quaternion reading (See SH-2 Ref. Manual 6.5.44)

+ +
+
+ +

◆ raw_accel_X

+ +
+
+ + + + + +
+ + + + +
uint16_t BNO08x::raw_accel_X
+
+private
+
+ +
+
+ +

◆ raw_accel_Y

+ +
+
+ + + + + +
+ + + + +
uint16_t BNO08x::raw_accel_Y
+
+private
+
+ +
+
+ +

◆ raw_accel_Z

+ +
+
+ + + + + +
+ + + + +
uint16_t BNO08x::raw_accel_Z
+
+private
+
+ +
+
+ +

◆ raw_bias_X

+ +
+
+ + + + + +
+ + + + +
uint16_t BNO08x::raw_bias_X
+
+private
+
+ +
+
+ +

◆ raw_bias_Y

+ +
+
+ + + + + +
+ + + + +
uint16_t BNO08x::raw_bias_Y
+
+private
+
+ +
+
+ +

◆ raw_bias_Z

+ +
+
+ + + + + +
+ + + + +
uint16_t BNO08x::raw_bias_Z
+
+private
+
+ +
+
+ +

◆ raw_gyro_X

+ +
+
+ + + + + +
+ + + + +
uint16_t BNO08x::raw_gyro_X
+
+private
+
+ +
+
+ +

◆ raw_gyro_Y

+ +
+
+ + + + + +
+ + + + +
uint16_t BNO08x::raw_gyro_Y
+
+private
+
+ +
+
+ +

◆ raw_gyro_Z

+ +
+
+ + + + + +
+ + + + +
uint16_t BNO08x::raw_gyro_Z
+
+private
+
+ +
+
+ +

◆ raw_lin_accel_X

+ +
+
+ + + + + +
+ + + + +
uint16_t BNO08x::raw_lin_accel_X
+
+private
+
+ +
+
+ +

◆ raw_lin_accel_Y

+ +
+
+ + + + + +
+ + + + +
uint16_t BNO08x::raw_lin_accel_Y
+
+private
+
+ +
+
+ +

◆ raw_lin_accel_Z

+ +
+
+ + + + + +
+ + + + +
uint16_t BNO08x::raw_lin_accel_Z
+
+private
+
+ +
+
+ +

◆ raw_magf_X

+ +
+
+ + + + + +
+ + + + +
uint16_t BNO08x::raw_magf_X
+
+private
+
+ +
+
+ +

◆ raw_magf_Y

+ +
+
+ + + + + +
+ + + + +
uint16_t BNO08x::raw_magf_Y
+
+private
+
+ +
+
+ +

◆ raw_magf_Z

+ +
+
+ + + + + +
+ + + + +
uint16_t BNO08x::raw_magf_Z
+
+private
+
+ +
+
+ +

◆ raw_quat_I

+ +
+
+ + + + + +
+ + + + +
uint16_t BNO08x::raw_quat_I
+
+private
+
+ +
+
+ +

◆ raw_quat_J

+ +
+
+ + + + + +
+ + + + +
uint16_t BNO08x::raw_quat_J
+
+private
+
+ +
+
+ +

◆ raw_quat_K

+ +
+
+ + + + + +
+ + + + +
uint16_t BNO08x::raw_quat_K
+
+private
+
+ +
+
+ +

◆ raw_quat_radian_accuracy

+ +
+
+ + + + + +
+ + + + +
uint16_t BNO08x::raw_quat_radian_accuracy
+
+private
+
+ +
+
+ +

◆ raw_quat_real

+ +
+
+ + + + + +
+ + + + +
uint16_t BNO08x::raw_quat_real
+
+private
+
+ +
+
+ +

◆ raw_uncalib_gyro_X

+ +
+
+ + + + + +
+ + + + +
uint16_t BNO08x::raw_uncalib_gyro_X
+
+private
+
+ +
+
+ +

◆ raw_uncalib_gyro_Y

+ +
+
+ + + + + +
+ + + + +
uint16_t BNO08x::raw_uncalib_gyro_Y
+
+private
+
+ +
+
+ +

◆ raw_uncalib_gyro_Z

+ +
+
+ + + + + +
+ + + + +
uint16_t BNO08x::raw_uncalib_gyro_Z
+
+private
+
+ +
+
+ +

◆ raw_velocity_gyro_X

+ +
+
+ + + + + +
+ + + + +
uint16_t BNO08x::raw_velocity_gyro_X
+
+private
+
+ +
+
+ +

◆ raw_velocity_gyro_Y

+ +
+
+ + + + + +
+ + + + +
uint16_t BNO08x::raw_velocity_gyro_Y
+
+private
+
+ +
+
+ +

◆ raw_velocity_gyro_Z

+ +
+
+ + + + + +
+ + + + +
uint16_t BNO08x::raw_velocity_gyro_Z
+
+private
+
+ +

Raw gyro angular velocity reading (See SH-2 Ref. Manual 6.5.44)

+ +
+
+ +

◆ ROTATION_VECTOR_ACCURACY_Q1

+ +
+
+ + + + + +
+ + + + +
const constexpr int16_t BNO08x::ROTATION_VECTOR_ACCURACY_Q1 = 12
+
+staticconstexpr
+
+ +

Rotation vector accuracy estimate Q point (See SH-2 Ref. Manual 6.5.18)

+ +
+
+ +

◆ ROTATION_VECTOR_Q1

+ +
+
+ + + + + +
+ + + + +
const constexpr int16_t BNO08x::ROTATION_VECTOR_Q1 = 14
+
+staticconstexpr
+
+ +

Rotation vector Q point (See SH-2 Ref. Manual 6.5.18)

+ +
+
+ +

◆ rx_buffer

+ +
+
+ + + + + +
+ + + + +
uint8_t BNO08x::rx_buffer[300]
+
+private
+
+ +

buffer used to receive packet with receive_packet()

+ +
+
+ +

◆ SENSOR_REPORTID_ACCELEROMETER

+ +
+
+ + + + + +
+ + + + +
const constexpr uint8_t BNO08x::SENSOR_REPORTID_ACCELEROMETER = 0x01
+
+staticconstexprprivate
+
+ +

See SH2 Ref. Manual 6.5.9.

+ +
+
+ +

◆ SENSOR_REPORTID_AR_VR_STABILIZED_GAME_ROTATION_VECTOR

+ +
+
+ + + + + +
+ + + + +
const constexpr uint8_t BNO08x::SENSOR_REPORTID_AR_VR_STABILIZED_GAME_ROTATION_VECTOR = 0x29
+
+staticconstexprprivate
+
+ +

See SH2 Ref. Manual 6.5.43.

+ +
+
+ +

◆ SENSOR_REPORTID_AR_VR_STABILIZED_ROTATION_VECTOR

+ +
+
+ + + + + +
+ + + + +
const constexpr uint8_t BNO08x::SENSOR_REPORTID_AR_VR_STABILIZED_ROTATION_VECTOR = 0x28
+
+staticconstexprprivate
+
+ +

See SH2 Ref. Manual 6.5.42.

+ +
+
+ +

◆ SENSOR_REPORTID_GAME_ROTATION_VECTOR

+ +
+
+ + + + + +
+ + + + +
const constexpr uint8_t BNO08x::SENSOR_REPORTID_GAME_ROTATION_VECTOR = 0x08
+
+staticconstexprprivate
+
+ +

See SH2 Ref. Manual 6.5.19.

+ +
+
+ +

◆ SENSOR_REPORTID_GEOMAGNETIC_ROTATION_VECTOR

+ +
+
+ + + + + +
+ + + + +
const constexpr uint8_t BNO08x::SENSOR_REPORTID_GEOMAGNETIC_ROTATION_VECTOR = 0x09
+
+staticconstexprprivate
+
+ +

See SH2 Ref. Manual 6.5.20.

+ +
+
+ +

◆ SENSOR_REPORTID_GRAVITY

+ +
+
+ + + + + +
+ + + + +
const constexpr uint8_t BNO08x::SENSOR_REPORTID_GRAVITY = 0x06
+
+staticconstexprprivate
+
+ +

See SH2 Ref. Manual 6.5.11.

+ +
+
+ +

◆ SENSOR_REPORTID_GYRO_INTEGRATED_ROTATION_VECTOR

+ +
+
+ + + + + +
+ + + + +
const constexpr uint8_t BNO08x::SENSOR_REPORTID_GYRO_INTEGRATED_ROTATION_VECTOR = 0x2A
+
+staticconstexprprivate
+
+ +

See SH2 Ref. Manual 6.5.44.

+ +
+
+ +

◆ SENSOR_REPORTID_GYROSCOPE

+ +
+
+ + + + + +
+ + + + +
const constexpr uint8_t BNO08x::SENSOR_REPORTID_GYROSCOPE = 0x02
+
+staticconstexprprivate
+
+ +

See SH2 Ref. Manual 6.5.13.

+ +
+
+ +

◆ SENSOR_REPORTID_LINEAR_ACCELERATION

+ +
+
+ + + + + +
+ + + + +
const constexpr uint8_t BNO08x::SENSOR_REPORTID_LINEAR_ACCELERATION = 0x04
+
+staticconstexprprivate
+
+ +

See SH2 Ref. Manual 6.5.10.

+ +
+
+ +

◆ SENSOR_REPORTID_MAGNETIC_FIELD

+ +
+
+ + + + + +
+ + + + +
const constexpr uint8_t BNO08x::SENSOR_REPORTID_MAGNETIC_FIELD = 0x03
+
+staticconstexprprivate
+
+ +

See SH2 Ref. Manual 6.5.16.

+ +
+
+ +

◆ SENSOR_REPORTID_PERSONAL_ACTIVITY_CLASSIFIER

+ +
+
+ + + + + +
+ + + + +
const constexpr uint8_t BNO08x::SENSOR_REPORTID_PERSONAL_ACTIVITY_CLASSIFIER = 0x1E
+
+staticconstexprprivate
+
+ +

See SH2 Ref. Manual 6.5.36.

+ +
+
+ +

◆ SENSOR_REPORTID_RAW_ACCELEROMETER

+ +
+
+ + + + + +
+ + + + +
const constexpr uint8_t BNO08x::SENSOR_REPORTID_RAW_ACCELEROMETER = 0x14
+
+staticconstexprprivate
+
+ +

See SH2 Ref. Manual 6.5.8.

+ +
+
+ +

◆ SENSOR_REPORTID_RAW_GYROSCOPE

+ +
+
+ + + + + +
+ + + + +
const constexpr uint8_t BNO08x::SENSOR_REPORTID_RAW_GYROSCOPE = 0x15
+
+staticconstexprprivate
+
+ +

See SH2 Ref. Manual 6.5.12.

+ +
+
+ +

◆ SENSOR_REPORTID_RAW_MAGNETOMETER

+ +
+
+ + + + + +
+ + + + +
const constexpr uint8_t BNO08x::SENSOR_REPORTID_RAW_MAGNETOMETER = 0x16
+
+staticconstexprprivate
+
+ +

See SH2 Ref. Manual 6.5.15.

+ +
+
+ +

◆ SENSOR_REPORTID_ROTATION_VECTOR

+ +
+
+ + + + + +
+ + + + +
const constexpr uint8_t BNO08x::SENSOR_REPORTID_ROTATION_VECTOR = 0x05
+
+staticconstexprprivate
+
+ +

See SH2 Ref. Manual 6.5.18.

+ +
+
+ +

◆ SENSOR_REPORTID_STABILITY_CLASSIFIER

+ +
+
+ + + + + +
+ + + + +
const constexpr uint8_t BNO08x::SENSOR_REPORTID_STABILITY_CLASSIFIER = 0x13
+
+staticconstexprprivate
+
+ +

See SH2 Ref. Manual 6.5.31.

+ +
+
+ +

◆ SENSOR_REPORTID_STEP_COUNTER

+ +
+
+ + + + + +
+ + + + +
const constexpr uint8_t BNO08x::SENSOR_REPORTID_STEP_COUNTER = 0x11
+
+staticconstexprprivate
+
+ +

See SH2 Ref. Manual 6.5.29.

+ +
+
+ +

◆ SENSOR_REPORTID_TAP_DETECTOR

+ +
+
+ + + + + +
+ + + + +
const constexpr uint8_t BNO08x::SENSOR_REPORTID_TAP_DETECTOR = 0x10
+
+staticconstexprprivate
+
+ +

See SH2 Ref. Manual 6.5.27.

+ +
+
+ +

◆ SENSOR_REPORTID_UNCALIBRATED_GYRO

+ +
+
+ + + + + +
+ + + + +
const constexpr uint8_t BNO08x::SENSOR_REPORTID_UNCALIBRATED_GYRO = 0x07
+
+staticconstexprprivate
+
+ +

See SH2 Ref. Manual 6.5.14.

+ +
+
+ +

◆ sequence_number

+ +
+
+ + + + + +
+ + + + +
uint8_t BNO08x::sequence_number[6]
+
+private
+
+ +

Sequence num of each com channel, 6 in total.

+ +
+
+ +

◆ SHTP_REPORT_BASE_TIMESTAMP

+ +
+
+ + + + + +
+ + + + +
const constexpr uint8_t BNO08x::SHTP_REPORT_BASE_TIMESTAMP = 0xFB
+
+staticconstexprprivate
+
+ +

See SH2 Ref. Manual 7.2.1.

+ +
+
+ +

◆ SHTP_REPORT_COMMAND_REQUEST

+ +
+
+ + + + + +
+ + + + +
const constexpr uint8_t BNO08x::SHTP_REPORT_COMMAND_REQUEST = 0xF2
+
+staticconstexprprivate
+
+ +

See SH2 Ref. Manual 6.3.8.

+ +
+
+ +

◆ SHTP_REPORT_COMMAND_RESPONSE

+ +
+
+ + + + + +
+ + + + +
const constexpr uint8_t BNO08x::SHTP_REPORT_COMMAND_RESPONSE = 0xF1
+
+staticconstexprprivate
+
+ +

See SH2 Ref. Manual 6.3.9.

+ +
+
+ +

◆ SHTP_REPORT_FRS_READ_REQUEST

+ +
+
+ + + + + +
+ + + + +
const constexpr uint8_t BNO08x::SHTP_REPORT_FRS_READ_REQUEST = 0xF4
+
+staticconstexprprivate
+
+ +

See SH2 Ref. Manual 6.3.6.

+ +
+
+ +

◆ SHTP_REPORT_FRS_READ_RESPONSE

+ +
+
+ + + + + +
+ + + + +
const constexpr uint8_t BNO08x::SHTP_REPORT_FRS_READ_RESPONSE = 0xF3
+
+staticconstexprprivate
+
+ +

See SH2 Ref. Manual 6.3.7.

+ +
+
+ +

◆ SHTP_REPORT_PRODUCT_ID_REQUEST

+ +
+
+ + + + + +
+ + + + +
const constexpr uint8_t BNO08x::SHTP_REPORT_PRODUCT_ID_REQUEST = 0xF9
+
+staticconstexprprivate
+
+ +

See SH2 Ref. Manual 6.3.1.

+ +
+
+ +

◆ SHTP_REPORT_PRODUCT_ID_RESPONSE

+ +
+
+ + + + + +
+ + + + +
const constexpr uint8_t BNO08x::SHTP_REPORT_PRODUCT_ID_RESPONSE = 0xF8
+
+staticconstexprprivate
+
+ +

See SH2 Ref. Manual 6.3.2.

+ +
+
+ +

◆ SHTP_REPORT_SET_FEATURE_COMMAND

+ +
+
+ + + + + +
+ + + + +
const constexpr uint8_t BNO08x::SHTP_REPORT_SET_FEATURE_COMMAND = 0xFD
+
+staticconstexprprivate
+
+ +

See SH2 Ref. Manual 6.5.4.

+ +
+
+ +

◆ spi_hdl

+ +
+
+ + + + + +
+ + + + +
spi_device_handle_t BNO08x::spi_hdl {}
+
+private
+
+ +

SPI device handle.

+ +
+
+ +

◆ spi_task_hdl

+ +
+
+ + + + + +
+ + + + +
TaskHandle_t BNO08x::spi_task_hdl
+
+private
+
+ +

SPI task handle.

+ +
+
+ +

◆ spi_transaction

+ +
+
+ + + + + +
+ + + + +
spi_transaction_t BNO08x::spi_transaction {}
+
+private
+
+ +

SPI transaction handle.

+ +
+
+ +

◆ stability_classifier

+ +
+
+ + + + + +
+ + + + +
uint8_t BNO08x::stability_classifier
+
+private
+
+ +

Stability status reading (See SH-2 Ref. Manual 6.5.31)

+ +
+
+ +

◆ step_count

+ +
+
+ + + + + +
+ + + + +
uint16_t BNO08x::step_count
+
+private
+
+ +

Step counter reading (See SH-2 Ref. Manual 6.5.29)

+ +
+
+ +

◆ TAG

+ +
+
+ + + + + +
+ + + + +
const constexpr char* BNO08x::TAG = "BNO08x"
+
+staticconstexprprivate
+
+ +

Class tag used for serial print statements.

+ +
+
+ +

◆ tap_detector

+ +
+
+ + + + + +
+ + + + +
uint8_t BNO08x::tap_detector
+
+private
+
+ +

Tap detector reading (See SH-2 Ref. Manual 6.5.27)

+ +
+
+ +

◆ TARE_AR_VR_STABILIZED_GAME_ROTATION_VECTOR

+ +
+
+ + + + + +
+ + + + +
const constexpr uint8_t BNO08x::TARE_AR_VR_STABILIZED_GAME_ROTATION_VECTOR = 5
+
+staticconstexpr
+
+ +

Tare ARVR stabilized game rotation vector.

+ +
+
+ +

◆ TARE_AR_VR_STABILIZED_ROTATION_VECTOR

+ +
+
+ + + + + +
+ + + + +
const constexpr uint8_t BNO08x::TARE_AR_VR_STABILIZED_ROTATION_VECTOR = 4
+
+staticconstexpr
+
+ +

Tare ARVR stabilized rotation vector.

+ +
+
+ +

◆ TARE_AXIS_ALL

+ +
+
+ + + + + +
+ + + + +
const constexpr uint8_t BNO08x::TARE_AXIS_ALL = 0x07
+
+staticconstexpr
+
+ +

Tare all axes (used with tare now command)

+ +
+
+ +

◆ TARE_AXIS_Z

+ +
+
+ + + + + +
+ + + + +
const constexpr uint8_t BNO08x::TARE_AXIS_Z = 0x04
+
+staticconstexpr
+
+ +

Tar yaw axis only (used with tare now command)

+ +
+
+ +

◆ TARE_GAME_ROTATION_VECTOR

+ +
+
+ + + + + +
+ + + + +
const constexpr uint8_t BNO08x::TARE_GAME_ROTATION_VECTOR = 1
+
+staticconstexpr
+
+ +

Tare game rotation vector.

+ +
+
+ +

◆ TARE_GEOMAGNETIC_ROTATION_VECTOR

+ +
+
+ + + + + +
+ + + + +
const constexpr uint8_t BNO08x::TARE_GEOMAGNETIC_ROTATION_VECTOR = 2
+
+staticconstexpr
+
+ +

tare geomagnetic rotation vector

+ +
+
+ +

◆ TARE_GYRO_INTEGRATED_ROTATION_VECTOR

+ +
+
+ + + + + +
+ + + + +
const constexpr uint8_t BNO08x::TARE_GYRO_INTEGRATED_ROTATION_VECTOR = 3
+
+staticconstexpr
+
+ +

Tare gyro integrated rotation vector.

+ +
+
+ +

◆ TARE_NOW

+ +
+
+ + + + + +
+ + + + +
const constexpr uint8_t BNO08x::TARE_NOW = 0
+
+staticconstexprprivate
+
+ +

See SH2 Ref. Manual 6.4.4.1.

+ +
+
+ +

◆ TARE_PERSIST

+ +
+
+ + + + + +
+ + + + +
const constexpr uint8_t BNO08x::TARE_PERSIST = 1
+
+staticconstexprprivate
+
+ +

See SH2 Ref. Manual 6.4.4.2.

+ +
+
+ +

◆ TARE_ROTATION_VECTOR

+ +
+
+ + + + + +
+ + + + +
const constexpr uint8_t BNO08x::TARE_ROTATION_VECTOR = 0
+
+staticconstexpr
+
+ +

Tare rotation vector.

+ +
+
+ +

◆ TARE_SET_REORIENTATION

+ +
+
+ + + + + +
+ + + + +
const constexpr uint8_t BNO08x::TARE_SET_REORIENTATION = 2
+
+staticconstexprprivate
+
+ +

See SH2 Ref. Manual 6.4.4.3.

+ +
+
+ +

◆ time_stamp

+ +
+
+ + + + + +
+ + + + +
uint32_t BNO08x::time_stamp
+
+private
+
+ +

Report timestamp (see datasheet 1.3.5.3)

+ +
+
+ +

◆ tx_buffer

+ +
+
+ + + + + +
+ + + + +
uint8_t BNO08x::tx_buffer[50]
+
+private
+
+ +

buffer used for sending packet with send_packet()

+ +
+
+ +

◆ tx_packet_queued

+ +
+
+ + + + + +
+ + + + +
volatile uint8_t BNO08x::tx_packet_queued
+
+private
+
+ +

Whether or not a packet is currently waiting to be sent, a queued packet is sent on assertion of BNO08x HINT pin)

+ +
+
+ +

◆ tx_semaphore

+ +
+
+ + + + + +
+ + + + +
SemaphoreHandle_t BNO08x::tx_semaphore
+
+private
+
+ +

Mutex semaphore used to prevent sending or receiving of packets if packet is currently being queued.

+ +
+
+ +

◆ uncalib_gyro_accuracy

+ +
+
+ + + + + +
+ + + + +
uint16_t BNO08x::uncalib_gyro_accuracy
+
+private
+
+ +

Uncalibrated gyro reading (See SH-2 Ref. Manual 6.5.14)

+

The documentation for this class was generated from the following files: diff --git a/documentation/html/classes.html b/documentation/html/classes.html index 092d17d..164078c 100644 --- a/documentation/html/classes.html +++ b/documentation/html/classes.html @@ -3,12 +3,14 @@ - + esp32_BNO08x: Class Index + + @@ -21,7 +23,7 @@ -
esp32_BNO08x 1.00 +
esp32_BNO08x 1.01
C++ BNO08x IMU driver component for esp-idf.
@@ -30,7 +32,7 @@
- + @@ -82,7 +84,7 @@ $(function() { diff --git a/documentation/html/clipboard.js b/documentation/html/clipboard.js new file mode 100644 index 0000000..42c1fb0 --- /dev/null +++ b/documentation/html/clipboard.js @@ -0,0 +1,61 @@ +/** + +The code below is based on the Doxygen Awesome project, see +https://github.com/jothepro/doxygen-awesome-css + +MIT License + +Copyright (c) 2021 - 2022 jothepro + +Permission is hereby granted, free of charge, to any person obtaining a copy +of this software and associated documentation files (the "Software"), to deal +in the Software without restriction, including without limitation the rights +to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +copies of the Software, and to permit persons to whom the Software is +furnished to do so, subject to the following conditions: + +The above copyright notice and this permission notice shall be included in all +copies or substantial portions of the Software. + +THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE +SOFTWARE. + +*/ + +let clipboard_title = "Copy to clipboard" +let clipboard_icon = `` +let clipboard_successIcon = `` +let clipboard_successDuration = 1000 + +$(function() { + if(navigator.clipboard) { + const fragments = document.getElementsByClassName("fragment") + for(const fragment of fragments) { + const clipboard_div = document.createElement("div") + clipboard_div.classList.add("clipboard") + clipboard_div.innerHTML = clipboard_icon + clipboard_div.title = clipboard_title + $(clipboard_div).click(function() { + const content = this.parentNode.cloneNode(true) + // filter out line number and folded fragments from file listings + content.querySelectorAll(".lineno, .ttc, .foldclosed").forEach((node) => { node.remove() }) + let text = content.textContent + // remove trailing newlines and trailing spaces from empty lines + text = text.replace(/^\s*\n/gm,'\n').replace(/\n*$/,'') + navigator.clipboard.writeText(text); + this.classList.add("success") + this.innerHTML = clipboard_successIcon + window.setTimeout(() => { // switch back to normal icon after timeout + this.classList.remove("success") + this.innerHTML = clipboard_icon + }, clipboard_successDuration); + }) + fragment.insertBefore(clipboard_div, fragment.firstChild) + } + } +}) diff --git a/documentation/html/cookie.js b/documentation/html/cookie.js new file mode 100644 index 0000000..53ad21d --- /dev/null +++ b/documentation/html/cookie.js @@ -0,0 +1,58 @@ +/*! + Cookie helper functions + Copyright (c) 2023 Dimitri van Heesch + Released under MIT license. +*/ +let Cookie = { + cookie_namespace: 'doxygen_', + + readSetting(cookie,defVal) { + if (window.chrome) { + const val = localStorage.getItem(this.cookie_namespace+cookie) || + sessionStorage.getItem(this.cookie_namespace+cookie); + if (val) return val; + } else { + let myCookie = this.cookie_namespace+cookie+"="; + if (document.cookie) { + const index = document.cookie.indexOf(myCookie); + if (index != -1) { + const valStart = index + myCookie.length; + let valEnd = document.cookie.indexOf(";", valStart); + if (valEnd == -1) { + valEnd = document.cookie.length; + } + return document.cookie.substring(valStart, valEnd); + } + } + } + return defVal; + }, + + writeSetting(cookie,val,days=10*365) { // default days='forever', 0=session cookie, -1=delete + if (window.chrome) { + if (days==0) { + sessionStorage.setItem(this.cookie_namespace+cookie,val); + } else { + localStorage.setItem(this.cookie_namespace+cookie,val); + } + } else { + let date = new Date(); + date.setTime(date.getTime()+(days*24*60*60*1000)); + const expiration = days!=0 ? "expires="+date.toGMTString()+";" : ""; + document.cookie = this.cookie_namespace + cookie + "=" + + val + "; SameSite=Lax;" + expiration + "path=/"; + } + }, + + eraseSetting(cookie) { + if (window.chrome) { + if (localStorage.getItem(this.cookie_namespace+cookie)) { + localStorage.removeItem(this.cookie_namespace+cookie); + } else if (sessionStorage.getItem(this.cookie_namespace+cookie)) { + sessionStorage.removeItem(this.cookie_namespace+cookie); + } + } else { + this.writeSetting(cookie,'',-1); + } + }, +} diff --git a/documentation/html/dir_575a586a6cee2959cc416e08c83a9494.html b/documentation/html/dir_f8bf4cf9c99e2cbdf74bcfc417d31962.html similarity index 80% rename from documentation/html/dir_575a586a6cee2959cc416e08c83a9494.html rename to documentation/html/dir_f8bf4cf9c99e2cbdf74bcfc417d31962.html index b7ce909..409624d 100644 --- a/documentation/html/dir_575a586a6cee2959cc416e08c83a9494.html +++ b/documentation/html/dir_f8bf4cf9c99e2cbdf74bcfc417d31962.html @@ -3,12 +3,14 @@ - + -esp32_BNO08x: D:/development/git/esp32_BNO08x Directory Reference +esp32_BNO08x: esp32_BNO08x Directory Reference + + @@ -21,7 +23,7 @@ -
esp32_BNO08x 1.00 +
esp32_BNO08x 1.01
C++ BNO08x IMU driver component for esp-idf.
@@ -30,7 +32,7 @@
- + @@ -70,7 +72,7 @@ $(function() {
@@ -80,13 +82,15 @@ $(function() { - + + +

Files

 BNO08x.hpp
 BNO08x.cpp
 
 BNO08x.hpp
 
diff --git a/documentation/html/doxygen.css b/documentation/html/doxygen.css index 0caa19b..7b7d851 100644 --- a/documentation/html/doxygen.css +++ b/documentation/html/doxygen.css @@ -1,4 +1,4 @@ -/* The standard CSS for doxygen 1.9.7*/ +/* The standard CSS for doxygen 1.10.0*/ html { /* page base colors */ @@ -145,6 +145,7 @@ html { --fragment-lineno-link-bg-color: #D8D8D8; --fragment-lineno-link-hover-fg-color: #4665A2; --fragment-lineno-link-hover-bg-color: #C8C8C8; +--fragment-copy-ok-color: #2EC82E; --tooltip-foreground-color: black; --tooltip-background-color: white; --tooltip-border-color: gray; @@ -152,6 +153,11 @@ html { --tooltip-declaration-color: #006318; --tooltip-link-color: #4665A2; --tooltip-shadow: 1px 1px 7px gray; +--fold-line-color: #808080; +--fold-minus-image: url('minus.svg'); +--fold-plus-image: url('plus.svg'); +--fold-minus-image-relpath: url('../../minus.svg'); +--fold-plus-image-relpath: url('../../plus.svg'); /** font-family */ --font-family-normal: Roboto,sans-serif; @@ -163,6 +169,28 @@ html { --font-family-icon: Arial,Helvetica; --font-family-tooltip: Roboto,sans-serif; +/** special sections */ +--warning-color-bg: #f8d1cc; +--warning-color-hl: #b61825; +--warning-color-text: #75070f; +--note-color-bg: #faf3d8; +--note-color-hl: #f3a600; +--note-color-text: #5f4204; +--todo-color-bg: #e4f3ff; +--todo-color-hl: #1879C4; +--todo-color-text: #274a5c; +--test-color-bg: #e8e8ff; +--test-color-hl: #3939C4; +--test-color-text: #1a1a5c; +--deprecated-color-bg: #ecf0f3; +--deprecated-color-hl: #5b6269; +--deprecated-color-text: #43454a; +--bug-color-bg: #e4dafd; +--bug-color-hl: #5b2bdd; +--bug-color-text: #2a0d72; +--invariant-color-bg: #d8f1e3; +--invariant-color-hl: #44b86f; +--invariant-color-text: #265532; } @media (prefers-color-scheme: dark) { @@ -298,13 +326,13 @@ html { --code-char-literal-color: #00E0F0; --code-xml-cdata-color: #C9D1D9; --code-vhdl-digit-color: #FF00FF; ---code-vhdl-char-color: #000000; ---code-vhdl-keyword-color: #700070; +--code-vhdl-char-color: #C0C0C0; +--code-vhdl-keyword-color: #CF53C9; --code-vhdl-logic-color: #FF0000; --code-link-color: #79C0FF; --code-external-link-color: #79C0FF; --fragment-foreground-color: #C9D1D9; ---fragment-background-color: black; +--fragment-background-color: #090D16; --fragment-border-color: #30363D; --fragment-lineno-border-color: #30363D; --fragment-lineno-background-color: black; @@ -313,6 +341,7 @@ html { --fragment-lineno-link-bg-color: #303030; --fragment-lineno-link-hover-fg-color: #8E96A1; --fragment-lineno-link-hover-bg-color: #505050; +--fragment-copy-ok-color: #0EA80E; --tooltip-foreground-color: #C9D1D9; --tooltip-background-color: #202020; --tooltip-border-color: #C9D1D9; @@ -320,6 +349,11 @@ html { --tooltip-declaration-color: #20C348; --tooltip-link-color: #79C0FF; --tooltip-shadow: none; +--fold-line-color: #808080; +--fold-minus-image: url('minusd.svg'); +--fold-plus-image: url('plusd.svg'); +--fold-minus-image-relpath: url('../../minusd.svg'); +--fold-plus-image-relpath: url('../../plusd.svg'); /** font-family */ --font-family-normal: Roboto,sans-serif; @@ -331,6 +365,28 @@ html { --font-family-icon: Arial,Helvetica; --font-family-tooltip: Roboto,sans-serif; +/** special sections */ +--warning-color-bg: #2e1917; +--warning-color-hl: #ad2617; +--warning-color-text: #f5b1aa; +--note-color-bg: #3b2e04; +--note-color-hl: #f1b602; +--note-color-text: #ceb670; +--todo-color-bg: #163750; +--todo-color-hl: #1982D2; +--todo-color-text: #dcf0fa; +--test-color-bg: #121258; +--test-color-hl: #4242cf; +--test-color-text: #c0c0da; +--deprecated-color-bg: #2e323b; +--deprecated-color-hl: #738396; +--deprecated-color-text: #abb0bd; +--bug-color-bg: #2a2536; +--bug-color-hl: #7661b3; +--bug-color-text: #ae9ed6; +--invariant-color-bg: #303a35; +--invariant-color-hl: #76ce96; +--invariant-color-text: #cceed5; }} body { background-color: var(--page-background-color); @@ -347,8 +403,6 @@ body, table, div, p, dl { /* @group Heading Levels */ .title { - font-weight: 400; - font-size: 14px; font-family: var(--font-family-normal); line-height: 28px; font-size: 150%; @@ -481,6 +535,12 @@ div.qindex{ color: var(--index-separator-color); } +#main-menu a:focus { + outline: auto; + z-index: 10; + position: relative; +} + dt.alphachar{ font-size: 180%; font-weight: bold; @@ -540,7 +600,13 @@ a { } a:hover { - text-decoration: underline; + text-decoration: none; + background: linear-gradient(to bottom, transparent 0,transparent calc(100% - 1px), currentColor 100%); +} + +a:hover > span.arrow { + text-decoration: none; + background : var(--nav-background-color); } a.el { @@ -616,30 +682,63 @@ ul.multicol { .fragment { text-align: left; direction: ltr; - overflow-x: auto; /*Fixed: fragment lines overlap floating elements*/ + overflow-x: auto; overflow-y: hidden; + position: relative; + min-height: 12px; + margin: 10px 0px; + padding: 10px 10px; + border: 1px solid var(--fragment-border-color); + border-radius: 4px; + background-color: var(--fragment-background-color); + color: var(--fragment-foreground-color); } pre.fragment { - border: 1px solid var(--fragment-border-color); - background-color: var(--fragment-background-color); - color: var(--fragment-foreground-color); - padding: 4px 6px; - margin: 4px 8px 4px 2px; - overflow: auto; - word-wrap: break-word; - font-size: 9pt; - line-height: 125%; - font-family: var(--font-family-monospace); - font-size: 105%; + word-wrap: break-word; + font-size: 10pt; + line-height: 125%; + font-family: var(--font-family-monospace); } -div.fragment { - padding: 0 0 1px 0; /*Fixed: last line underline overlap border*/ - margin: 4px 8px 4px 2px; - color: var(--fragment-foreground-color); - background-color: var(--fragment-background-color); - border: 1px solid var(--fragment-border-color); +.clipboard { + width: 24px; + height: 24px; + right: 5px; + top: 5px; + opacity: 0; + position: absolute; + display: inline; + overflow: auto; + fill: var(--fragment-foreground-color); + justify-content: center; + align-items: center; + cursor: pointer; +} + +.clipboard.success { + border: 1px solid var(--fragment-foreground-color); + border-radius: 4px; +} + +.fragment:hover .clipboard, .clipboard.success { + opacity: .28; +} + +.clipboard:hover, .clipboard.success { + opacity: 1 !important; +} + +.clipboard:active:not([class~=success]) svg { + transform: scale(.91); +} + +.clipboard.success svg { + fill: var(--fragment-copy-ok-color); +} + +.clipboard.success { + border-color: var(--fragment-copy-ok-color); } div.line { @@ -679,6 +778,18 @@ div.line.glow { box-shadow: 0 0 10px var(--glow-color); } +span.fold { + margin-left: 5px; + margin-right: 1px; + margin-top: 0px; + margin-bottom: 0px; + padding: 0px; + display: inline-block; + width: 12px; + height: 12px; + background-repeat:no-repeat; + background-position:center; +} span.lineno { padding-right: 4px; @@ -750,10 +861,6 @@ img.light-mode-visible { display: none; } -img.formulaDsp { - -} - img.formulaInl, img.inline { vertical-align: middle; } @@ -1053,17 +1160,25 @@ dl.reflist dd { .paramtype { white-space: nowrap; + padding: 0px; + padding-bottom: 1px; } .paramname { - color: var(--memdef-param-name-color); white-space: nowrap; + padding: 0px; + padding-bottom: 1px; + margin-left: 2px; } + .paramname em { + color: var(--memdef-param-name-color); font-style: normal; + margin-right: 1px; } -.paramname code { - line-height: 14px; + +.paramname .paramdefval { + font-family: var(--font-family-monospace); } .params, .retval, .exception, .tparams { @@ -1397,7 +1512,6 @@ table.fieldtable { { height:32px; display:block; - text-decoration: none; outline: none; color: var(--nav-text-normal-color); font-family: var(--font-family-nav); @@ -1486,7 +1600,8 @@ dl { padding: 0 0 0 0; } -/* dl.note, dl.warning, dl.attention, dl.pre, dl.post, dl.invariant, dl.deprecated, dl.todo, dl.test, dl.bug, dl.examples */ +/* + dl.section { margin-left: 0px; padding-left: 0px; @@ -1541,8 +1656,101 @@ dl.bug { border-color: #C08050; } +*/ + +dl.bug dt a, dl.deprecated dt a, dl.todo dt a, dl.test a { + font-weight: bold !important; +} + +dl.warning, dl.attention, dl.note, dl.deprecated, dl.bug, +dl.invariant, dl.pre, dl.post, dl.todo, dl.test, dl.remark { + padding: 10px; + margin: 10px 0px; + overflow: hidden; + margin-left: 0; + border-radius: 4px; +} + dl.section dd { - margin-bottom: 6px; + margin-bottom: 2px; +} + +dl.warning, dl.attention { + background: var(--warning-color-bg); + border-left: 8px solid var(--warning-color-hl); + color: var(--warning-color-text); +} + +dl.warning dt, dl.attention dt { + color: var(--warning-color-hl); +} + +dl.note, dl.remark { + background: var(--note-color-bg); + border-left: 8px solid var(--note-color-hl); + color: var(--note-color-text); +} + +dl.note dt, dl.remark dt { + color: var(--note-color-hl); +} + +dl.todo { + background: var(--todo-color-bg); + border-left: 8px solid var(--todo-color-hl); + color: var(--todo-color-text); +} + +dl.todo dt { + color: var(--todo-color-hl); +} + +dl.test { + background: var(--test-color-bg); + border-left: 8px solid var(--test-color-hl); + color: var(--test-color-text); +} + +dl.test dt { + color: var(--test-color-hl); +} + +dl.bug dt a { + color: var(--bug-color-hl) !important; +} + +dl.bug { + background: var(--bug-color-bg); + border-left: 8px solid var(--bug-color-hl); + color: var(--bug-color-text); +} + +dl.bug dt a { + color: var(--bug-color-hl) !important; +} + +dl.deprecated { + background: var(--deprecated-color-bg); + border-left: 8px solid var(--deprecated-color-hl); + color: var(--deprecated-color-text); +} + +dl.deprecated dt a { + color: var(--deprecated-color-hl) !important; +} + +dl.section dd, dl.bug dd, dl.deprecated dd, dl.todo dd, dl.test dd { + margin-inline-start: 0px; +} + +dl.invariant, dl.pre, dl.post { + background: var(--invariant-color-bg); + border-left: 8px solid var(--invariant-color-hl); + color: var(--invariant-color-text); +} + +dl.invariant dt, dl.pre dt, dl.post dt { + color: var(--invariant-color-hl); } @@ -1557,12 +1765,12 @@ dl.section dd { vertical-align: bottom; border-collapse: separate; } - + #projectlogo img -{ +{ border: 0px none; } - + #projectalign { vertical-align: middle; diff --git a/documentation/html/doxygen_crawl.html b/documentation/html/doxygen_crawl.html new file mode 100644 index 0000000..f80678b --- /dev/null +++ b/documentation/html/doxygen_crawl.html @@ -0,0 +1,84 @@ + + + +Validator / crawler helper + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/documentation/html/dynsections.js b/documentation/html/dynsections.js index f579fbf..8f49326 100644 --- a/documentation/html/dynsections.js +++ b/documentation/html/dynsections.js @@ -22,102 +22,173 @@ @licend The above is the entire license notice for the JavaScript code in this file */ -function toggleVisibility(linkObj) -{ - var base = $(linkObj).attr('id'); - var summary = $('#'+base+'-summary'); - var content = $('#'+base+'-content'); - var trigger = $('#'+base+'-trigger'); - var src=$(trigger).attr('src'); - if (content.is(':visible')===true) { - content.hide(); - summary.show(); - $(linkObj).addClass('closed').removeClass('opened'); - $(trigger).attr('src',src.substring(0,src.length-8)+'closed.png'); - } else { - content.show(); - summary.hide(); - $(linkObj).removeClass('closed').addClass('opened'); - $(trigger).attr('src',src.substring(0,src.length-10)+'open.png'); - } - return false; -} -function updateStripes() -{ - $('table.directory tr'). - removeClass('even').filter(':visible:even').addClass('even'); - $('table.directory tr'). - removeClass('odd').filter(':visible:odd').addClass('odd'); -} +let dynsection = { -function toggleLevel(level) -{ - $('table.directory tr').each(function() { - var l = this.id.split('_').length-1; - var i = $('#img'+this.id.substring(3)); - var a = $('#arr'+this.id.substring(3)); - if (l'); + // add vertical lines to other rows + $('span[class=lineno]').not(':eq(0)').append(''); + // add toggle controls to lines with fold divs + $('div[class=foldopen]').each(function() { + // extract specific id to use + const id = $(this).attr('id').replace('foldopen',''); + // extract start and end foldable fragment attributes + const start = $(this).attr('data-start'); + const end = $(this).attr('data-end'); + // replace normal fold span with controls for the first line of a foldable fragment + $(this).find('span[class=fold]:first').replaceWith(''); + // append div for folded (closed) representation + $(this).after(''); + // extract the first line from the "open" section to represent closed content + const line = $(this).children().first().clone(); + // remove any glow that might still be active on the original line + $(line).removeClass('glow'); + if (start) { + // if line already ends with a start marker (e.g. trailing {), remove it + $(line).html($(line).html().replace(new RegExp('\\s*'+start+'\\s*$','g'),'')); + } + // replace minus with plus symbol + $(line).find('span[class=fold]').css('background-image',codefold.plusImg[relPath]); + // append ellipsis + $(line).append(' '+start+''+end); + // insert constructed line into closed div + $('#foldclosed'+id).html(line); + }); + }, +}; /* @license-end */ diff --git a/documentation/html/files.html b/documentation/html/files.html index d3de100..e5c8588 100644 --- a/documentation/html/files.html +++ b/documentation/html/files.html @@ -3,12 +3,14 @@ - + esp32_BNO08x: File List + + @@ -21,7 +23,7 @@ -
esp32_BNO08x 1.00 +
esp32_BNO08x 1.01
C++ BNO08x IMU driver component for esp-idf.
@@ -30,7 +32,7 @@
- + @@ -73,19 +75,17 @@ $(function() {
File List
-
Here is a list of all documented files with brief descriptions:
-
[detail level 12345]
- - - - - +
Here is a list of all files with brief descriptions:
+
[detail level 12]
  D:
  development
  git
  esp32_BNO08x
 BNO08x.hpp
+ + +
  esp32_BNO08x
 BNO08x.cpp
 BNO08x.hpp
diff --git a/documentation/html/functions.html b/documentation/html/functions.html index 6bd5221..6d5e698 100644 --- a/documentation/html/functions.html +++ b/documentation/html/functions.html @@ -3,12 +3,14 @@ - + esp32_BNO08x: Class Members + + @@ -21,7 +23,7 @@ -
esp32_BNO08x 1.00 +
esp32_BNO08x 1.01
C++ BNO08x IMU driver component for esp-idf.
@@ -30,7 +32,7 @@
- + @@ -70,7 +72,7 @@ $(function() {
-
Here is a list of all documented class members with links to the class documentation for each member:
+
Here is a list of all class members with links to the classes they belong to:

- a -

diff --git a/documentation/html/functions_b.html b/documentation/html/functions_b.html index 5471984..0ae485f 100644 --- a/documentation/html/functions_b.html +++ b/documentation/html/functions_b.html @@ -3,12 +3,14 @@ - + esp32_BNO08x: Class Members + + @@ -21,7 +23,7 @@ -
esp32_BNO08x 1.00 +
esp32_BNO08x 1.01
C++ BNO08x IMU driver component for esp-idf.
@@ -30,7 +32,7 @@
- + @@ -70,7 +72,7 @@ $(function() {
-
Here is a list of all documented class members with links to the class documentation for each member:
+
Here is a list of all class members with links to the classes they belong to:

- b -

diff --git a/documentation/html/functions_c.html b/documentation/html/functions_c.html index de7b91c..3f9c771 100644 --- a/documentation/html/functions_c.html +++ b/documentation/html/functions_c.html @@ -3,12 +3,14 @@ - + esp32_BNO08x: Class Members + + @@ -21,7 +23,7 @@ -
esp32_BNO08x 1.00 +
esp32_BNO08x 1.01
C++ BNO08x IMU driver component for esp-idf.
@@ -30,7 +32,7 @@
- + @@ -70,7 +72,7 @@ $(function() {
-
Here is a list of all documented class members with links to the class documentation for each member:
+
Here is a list of all class members with links to the classes they belong to:

- c -

diff --git a/documentation/html/functions_d.html b/documentation/html/functions_d.html index cd75416..0b2a751 100644 --- a/documentation/html/functions_d.html +++ b/documentation/html/functions_d.html @@ -3,12 +3,14 @@ - + esp32_BNO08x: Class Members + + @@ -21,7 +23,7 @@ -
esp32_BNO08x 1.00 +
esp32_BNO08x 1.01
C++ BNO08x IMU driver component for esp-idf.
@@ -30,7 +32,7 @@
- + @@ -70,7 +72,7 @@ $(function() {
-
Here is a list of all documented class members with links to the class documentation for each member:
+
Here is a list of all class members with links to the classes they belong to:

- d -

diff --git a/documentation/html/functions_e.html b/documentation/html/functions_e.html index c01b98b..e7b863f 100644 --- a/documentation/html/functions_e.html +++ b/documentation/html/functions_e.html @@ -3,12 +3,14 @@ - + esp32_BNO08x: Class Members + + @@ -21,7 +23,7 @@ -
esp32_BNO08x 1.00 +
esp32_BNO08x 1.01
C++ BNO08x IMU driver component for esp-idf.
@@ -30,7 +32,7 @@
- + @@ -70,7 +72,7 @@ $(function() {
-
Here is a list of all documented class members with links to the class documentation for each member:
+
Here is a list of all class members with links to the classes they belong to:

- e -

diff --git a/documentation/html/functions_f.html b/documentation/html/functions_f.html index d713d2a..aa0f911 100644 --- a/documentation/html/functions_f.html +++ b/documentation/html/functions_f.html @@ -3,12 +3,14 @@ - + esp32_BNO08x: Class Members + + @@ -21,7 +23,7 @@ -
esp32_BNO08x 1.00 +
esp32_BNO08x 1.01
C++ BNO08x IMU driver component for esp-idf.
@@ -30,7 +32,7 @@
- + @@ -70,17 +72,21 @@ $(function() {
-
Here is a list of all documented class members with links to the class documentation for each member:
+
Here is a list of all class members with links to the classes they belong to:

- f -

diff --git a/documentation/html/functions_func.html b/documentation/html/functions_func.html index b3541fa..45344ec 100644 --- a/documentation/html/functions_func.html +++ b/documentation/html/functions_func.html @@ -3,12 +3,14 @@ - + esp32_BNO08x: Class Members - Functions + + @@ -21,7 +23,7 @@ -
esp32_BNO08x 1.00 +
esp32_BNO08x 1.01
C++ BNO08x IMU driver component for esp-idf.
@@ -30,7 +32,7 @@
- + @@ -70,7 +72,7 @@ $(function() {
-
Here is a list of all documented functions with links to the class documentation for each member:
+
Here is a list of all functions with links to the classes they belong to:

- b -

@@ -262,7 +265,7 @@ $(function() {
diff --git a/documentation/html/functions_g.html b/documentation/html/functions_g.html index 4489658..3d42a07 100644 --- a/documentation/html/functions_g.html +++ b/documentation/html/functions_g.html @@ -3,12 +3,14 @@ - + esp32_BNO08x: Class Members + + @@ -21,7 +23,7 @@ -
esp32_BNO08x 1.00 +
esp32_BNO08x 1.01
C++ BNO08x IMU driver component for esp-idf.
@@ -30,7 +32,7 @@
- + @@ -70,7 +72,7 @@ $(function() {
-
Here is a list of all documented class members with links to the class documentation for each member:
+
Here is a list of all class members with links to the classes they belong to:

- g -

diff --git a/documentation/html/functions_h.html b/documentation/html/functions_h.html index d1fc493..63772d0 100644 --- a/documentation/html/functions_h.html +++ b/documentation/html/functions_h.html @@ -3,12 +3,14 @@ - + esp32_BNO08x: Class Members + + @@ -21,7 +23,7 @@ -
esp32_BNO08x 1.00 +
esp32_BNO08x 1.01
C++ BNO08x IMU driver component for esp-idf.
@@ -30,7 +32,7 @@
- + @@ -70,17 +72,17 @@ $(function() {
-
Here is a list of all documented class members with links to the class documentation for each member:
+
Here is a list of all class members with links to the classes they belong to:

- h -

diff --git a/documentation/html/functions_i.html b/documentation/html/functions_i.html index 841c195..0981540 100644 --- a/documentation/html/functions_i.html +++ b/documentation/html/functions_i.html @@ -3,12 +3,14 @@ - + esp32_BNO08x: Class Members + + @@ -21,7 +23,7 @@ -
esp32_BNO08x 1.00 +
esp32_BNO08x 1.01
C++ BNO08x IMU driver component for esp-idf.
@@ -30,7 +32,7 @@
- + @@ -70,13 +72,14 @@ $(function() {
-
Here is a list of all documented class members with links to the class documentation for each member:
+
Here is a list of all class members with links to the classes they belong to:

- i -

diff --git a/documentation/html/functions_l.html b/documentation/html/functions_l.html index e641671..449a5a4 100644 --- a/documentation/html/functions_l.html +++ b/documentation/html/functions_l.html @@ -3,12 +3,14 @@ - + esp32_BNO08x: Class Members + + @@ -21,7 +23,7 @@ -
esp32_BNO08x 1.00 +
esp32_BNO08x 1.01
C++ BNO08x IMU driver component for esp-idf.
@@ -30,7 +32,7 @@
- + @@ -70,7 +72,7 @@ $(function() {
-
Here is a list of all documented class members with links to the class documentation for each member:
+
Here is a list of all class members with links to the classes they belong to:

- l -

diff --git a/documentation/html/functions_m.html b/documentation/html/functions_m.html index ed15977..95ea7e1 100644 --- a/documentation/html/functions_m.html +++ b/documentation/html/functions_m.html @@ -3,12 +3,14 @@ - + esp32_BNO08x: Class Members + + @@ -21,7 +23,7 @@ -
esp32_BNO08x 1.00 +
esp32_BNO08x 1.01
C++ BNO08x IMU driver component for esp-idf.
@@ -30,7 +32,7 @@
- + @@ -70,13 +72,19 @@ $(function() {
-
Here is a list of all documented class members with links to the class documentation for each member:
+
Here is a list of all class members with links to the classes they belong to:

- m -

diff --git a/documentation/html/functions_p.html b/documentation/html/functions_p.html index ac33675..4c92155 100644 --- a/documentation/html/functions_p.html +++ b/documentation/html/functions_p.html @@ -3,12 +3,14 @@ - + esp32_BNO08x: Class Members + + @@ -21,7 +23,7 @@ -
esp32_BNO08x 1.00 +
esp32_BNO08x 1.01
C++ BNO08x IMU driver component for esp-idf.
@@ -30,7 +32,7 @@
- + @@ -70,7 +72,7 @@ $(function() {
-
Here is a list of all documented class members with links to the class documentation for each member:
+
Here is a list of all class members with links to the classes they belong to:

- p -

diff --git a/documentation/html/functions_q.html b/documentation/html/functions_q.html index 0845e0e..18668d7 100644 --- a/documentation/html/functions_q.html +++ b/documentation/html/functions_q.html @@ -3,12 +3,14 @@ - + esp32_BNO08x: Class Members + + @@ -21,7 +23,7 @@ -
esp32_BNO08x 1.00 +
esp32_BNO08x 1.01
C++ BNO08x IMU driver component for esp-idf.
@@ -30,7 +32,7 @@
- + @@ -70,7 +72,7 @@ $(function() {
-
Here is a list of all documented class members with links to the class documentation for each member:
+
Here is a list of all class members with links to the classes they belong to:

- q -

diff --git a/documentation/html/functions_r.html b/documentation/html/functions_r.html index 14640d4..5ecc08c 100644 --- a/documentation/html/functions_r.html +++ b/documentation/html/functions_r.html @@ -3,12 +3,14 @@ - + esp32_BNO08x: Class Members + + @@ -21,7 +23,7 @@ -
esp32_BNO08x 1.00 +
esp32_BNO08x 1.01
C++ BNO08x IMU driver component for esp-idf.
@@ -30,7 +32,7 @@
- + @@ -70,9 +72,34 @@ $(function() {
-
Here is a list of all documented class members with links to the class documentation for each member:
+
Here is a list of all class members with links to the classes they belong to:

- r -

diff --git a/documentation/html/functions_s.html b/documentation/html/functions_s.html index 55e5c0e..319b3fe 100644 --- a/documentation/html/functions_s.html +++ b/documentation/html/functions_s.html @@ -3,12 +3,14 @@ - + esp32_BNO08x: Class Members + + @@ -21,7 +23,7 @@ -
esp32_BNO08x 1.00 +
esp32_BNO08x 1.01
C++ BNO08x IMU driver component for esp-idf.
@@ -30,7 +32,7 @@
- + @@ -70,7 +72,7 @@ $(function() {
-
Here is a list of all documented class members with links to the class documentation for each member:
+
Here is a list of all class members with links to the classes they belong to:

- s -

diff --git a/documentation/html/functions_t.html b/documentation/html/functions_t.html index 71e113e..2c8a84a 100644 --- a/documentation/html/functions_t.html +++ b/documentation/html/functions_t.html @@ -3,12 +3,14 @@ - + esp32_BNO08x: Class Members + + @@ -21,7 +23,7 @@ -
esp32_BNO08x 1.00 +
esp32_BNO08x 1.01
C++ BNO08x IMU driver component for esp-idf.
@@ -30,7 +32,7 @@
- + @@ -70,7 +72,7 @@ $(function() {
-
Here is a list of all documented class members with links to the class documentation for each member:
+
Here is a list of all class members with links to the classes they belong to:

- t -

diff --git a/documentation/html/functions_u.html b/documentation/html/functions_u.html index 1658bcc..3316f6e 100644 --- a/documentation/html/functions_u.html +++ b/documentation/html/functions_u.html @@ -3,12 +3,14 @@ - + esp32_BNO08x: Class Members + + @@ -21,7 +23,7 @@ -
esp32_BNO08x 1.00 +
esp32_BNO08x 1.01
C++ BNO08x IMU driver component for esp-idf.
@@ -30,7 +32,7 @@
- + @@ -70,7 +72,7 @@ $(function() {
-
Here is a list of all documented class members with links to the class documentation for each member:
+
Here is a list of all class members with links to the classes they belong to:

- u -

diff --git a/documentation/html/functions_vars.html b/documentation/html/functions_vars.html index 76d201e..691ac74 100644 --- a/documentation/html/functions_vars.html +++ b/documentation/html/functions_vars.html @@ -3,12 +3,14 @@ - + esp32_BNO08x: Class Members - Variables + + @@ -21,7 +23,7 @@ -
esp32_BNO08x 1.00 +
esp32_BNO08x 1.01
C++ BNO08x IMU driver component for esp-idf.
@@ -30,7 +32,7 @@
- + @@ -70,7 +72,7 @@ $(function() {
-
Here is a list of all documented variables with links to the class documentation for each member:
+
Here is a list of all variables with links to the classes they belong to:

- a -

+

- f -

+ +

- g -

- h -

- i -

diff --git a/documentation/html/functions_w.html b/documentation/html/functions_w.html index da6dffa..d452a18 100644 --- a/documentation/html/functions_w.html +++ b/documentation/html/functions_w.html @@ -3,12 +3,14 @@ - + esp32_BNO08x: Class Members + + @@ -21,7 +23,7 @@ -
esp32_BNO08x 1.00 +
esp32_BNO08x 1.01
C++ BNO08x IMU driver component for esp-idf.
@@ -30,7 +32,7 @@
- + @@ -70,7 +72,7 @@ $(function() {
-
Here is a list of all documented class members with links to the class documentation for each member:
+
Here is a list of all class members with links to the classes they belong to:

- w -

diff --git a/documentation/html/globals.html b/documentation/html/globals.html new file mode 100644 index 0000000..2e1ee7b --- /dev/null +++ b/documentation/html/globals.html @@ -0,0 +1,92 @@ + + + + + + + +esp32_BNO08x: File Members + + + + + + + + + + + +
+
+ + + + + + +
+
esp32_BNO08x 1.01 +
+
C++ BNO08x IMU driver component for esp-idf.
+
+
+ + + + + + + +
+ +
+
+ + +
+
+
+
+
+
Loading...
+
Searching...
+
No Matches
+
+
+
+
+ +
+
Here is a list of all file members with links to the files they belong to:
+
+ + + + diff --git a/documentation/html/globals_enum.html b/documentation/html/globals_enum.html new file mode 100644 index 0000000..e20477e --- /dev/null +++ b/documentation/html/globals_enum.html @@ -0,0 +1,85 @@ + + + + + + + +esp32_BNO08x: File Members + + + + + + + + + + + +
+
+ + + + + + +
+
esp32_BNO08x 1.01 +
+
C++ BNO08x IMU driver component for esp-idf.
+
+
+ + + + + + + +
+ +
+
+ + +
+
+
+
+
+
Loading...
+
Searching...
+
No Matches
+
+
+
+
+ +
+
Here is a list of all enums with links to the files they belong to:
+
+ + + + diff --git a/documentation/html/globals_eval.html b/documentation/html/globals_eval.html new file mode 100644 index 0000000..d15ac0e --- /dev/null +++ b/documentation/html/globals_eval.html @@ -0,0 +1,89 @@ + + + + + + + +esp32_BNO08x: File Members + + + + + + + + + + + +
+
+ + + + + + +
+
esp32_BNO08x 1.01 +
+
C++ BNO08x IMU driver component for esp-idf.
+
+
+ + + + + + + +
+ +
+
+ + +
+
+
+
+
+
Loading...
+
Searching...
+
No Matches
+
+
+
+
+ +
+
Here is a list of all enum values with links to the files they belong to:
+
+ + + + diff --git a/documentation/html/dir_ebea21e7cbc239e4b984a419d2ec33b9.html b/documentation/html/globals_type.html similarity index 81% rename from documentation/html/dir_ebea21e7cbc239e4b984a419d2ec33b9.html rename to documentation/html/globals_type.html index 3cfc9cc..8317567 100644 --- a/documentation/html/dir_ebea21e7cbc239e4b984a419d2ec33b9.html +++ b/documentation/html/globals_type.html @@ -3,12 +3,14 @@ - + -esp32_BNO08x: D:/development Directory Reference +esp32_BNO08x: File Members + + @@ -21,7 +23,7 @@ -
esp32_BNO08x 1.00 +
esp32_BNO08x 1.01
C++ BNO08x IMU driver component for esp-idf.
@@ -30,7 +32,7 @@
- + +
- - -
-
development Directory Reference
-
+
Here is a list of all typedefs with links to the files they belong to:
diff --git a/documentation/html/index.html b/documentation/html/index.html index 02a91e2..27ff715 100644 --- a/documentation/html/index.html +++ b/documentation/html/index.html @@ -3,12 +3,14 @@ - + esp32_BNO08x: Main Page + + @@ -21,7 +23,7 @@ -
esp32_BNO08x 1.00 +
esp32_BNO08x 1.01
C++ BNO08x IMU driver component for esp-idf.
@@ -30,7 +32,7 @@
- + @@ -73,10 +75,11 @@ $(function() {
esp32_BNO08x Documentation
+
diff --git a/documentation/html/md__d_1_2development_2git_2esp32___b_n_o08x_2_r_e_a_d_m_e.html b/documentation/html/md_esp32___b_n_o08x_2_r_e_a_d_m_e.html similarity index 79% rename from documentation/html/md__d_1_2development_2git_2esp32___b_n_o08x_2_r_e_a_d_m_e.html rename to documentation/html/md_esp32___b_n_o08x_2_r_e_a_d_m_e.html index 7d8223f..382ac56 100644 --- a/documentation/html/md__d_1_2development_2git_2esp32___b_n_o08x_2_r_e_a_d_m_e.html +++ b/documentation/html/md_esp32___b_n_o08x_2_r_e_a_d_m_e.html @@ -3,12 +3,14 @@ - + esp32_BNO08x: README + + @@ -21,7 +23,7 @@ -
esp32_BNO08x 1.00 +
esp32_BNO08x 1.01
C++ BNO08x IMU driver component for esp-idf.
@@ -30,7 +32,7 @@
- + @@ -74,7 +76,7 @@ $(function() {

Table of Contents.

-

image

+

image

  1. About
  2. @@ -91,6 +93,14 @@ $(function() {
  3. Documentation
  4. +Program Flowcharts +
  5. +
  6. Acknowledgements
  7. License
  8. @@ -99,7 +109,7 @@ $(function() {

About

-

esp32_BNO08x is a C++ component written for esp-idf version 5.1 to serve as a driver for the BNO085 or BNO080 IMU.
+

esp32_BNO08x is a C++ esp-idf v5.x component, intended to serve as a driver for both the BNO080 and BNO085 IMUs.
This library is heavy influenced by the SparkFun BNO080 Arduino Library, it is more or less a port. It supports access to all the same data that the BNO08x provides.
Currently, only SPI is supported, there is no plans to support I2C (esp32 has I2C driver silicone bug, leading to unpredictable behavior).
I may implement UART at some point in the future.

@@ -121,28 +131,31 @@ Adding to Project
  • Cd into the components directory and clone the esp32_BNO08x repo.

    cd components
    git clone https://github.com/myles-parfeniuk/esp32_BNO08x.git
    -

    (back to top)

    -
  • +
    +
  • Ensure you clean your esp-idf project before rebuilding.
    + Within esp-idf enabled terminal:
    idf.py fullclean
    +
  • +

    (back to top)

    Example

    #include <stdio.h>
    -
    #include "BNO08x.hpp"
    +
    #include "BNO08x.hpp"
    extern "C" void app_main(void)
    {
    BNO08x imu; //create IMU object with default wiring scheme
    +
    //if a custom wiring scheme is desired instead of default:
    +
    /*
    -
    //if a custom wiring scheme is desired:
    -
    //create config struct
    -
    bno08x_config_t imu_config;
    -
    imu_config.io_mos = GPIO_NUM_X;
    -
    imu_config.io_miso = GPIO_NUM_X;
    +
    bno08x_config_t imu_config; //create config struct
    +
    imu_config.io_mosi = GPIO_NUM_X; //assign pin
    +
    imu_config.io_miso = GPIO_NUM_X; //assign pin
    //etc...
    -
    -
    BNO08x imu(imu_config);
    +
    BNO08x imu(imu_config); //pass config to BNO08x constructor
    */
    +
    imu.initialize(); //initialize IMU
    @@ -156,22 +169,23 @@ Example
    if(imu.data_available())
    {
    ESP_LOGW("Main", "Velocity: x: %.3f y: %.3f z: %.3f", imu.get_gyro_calibrated_velocity_X(), imu.get_gyro_calibrated_velocity_Y(), imu.get_gyro_calibrated_velocity_Z());
    -
    ESP_LOGI("Main", "Euler Angle: pitch: %.3f roll: %.3f yaw: %.3f", imu.get_pitch_deg(), imu.get_roll_deg(), imu.get_yaw_deg());
    +
    ESP_LOGI("Main", "Euler Angle: x (roll): %.3f y (pitch): %.3f z (yaw): %.3f", imu.get_roll_deg(), imu.get_pitch_deg(), imu.get_yaw_deg());
    }
    }
    }
    -
    Definition BNO08x.hpp:74
    -
    float get_gyro_calibrated_velocity_Z()
    Get calibrated gyro z axis angular velocity measurement.
    Definition BNO08x.cpp:1862
    + +
    Definition BNO08x.hpp:104
    +
    float get_gyro_calibrated_velocity_Z()
    Get calibrated gyro z axis angular velocity measurement.
    Definition BNO08x.cpp:1866
    bool data_available()
    Checks if BNO08x has asserted interrupt and sent data.
    Definition BNO08x.cpp:725
    -
    void enable_game_rotation_vector(uint16_t time_between_reports)
    Sends command to enable game rotation vector reports (See Ref. Manual 6.5.19)
    Definition BNO08x.cpp:996
    -
    float get_roll_deg()
    Get the reported rotation about x axis.
    Definition BNO08x.cpp:1500
    -
    void enable_gyro(uint16_t time_between_reports)
    Sends command to enable gyro reports (See Ref. Manual 6.5.13)
    Definition BNO08x.cpp:1100
    -
    float get_gyro_calibrated_velocity_X()
    Get calibrated gyro x axis angular velocity measurement.
    Definition BNO08x.cpp:1842
    -
    float get_gyro_calibrated_velocity_Y()
    Get calibrated gyro y axis angular velocity measurement.
    Definition BNO08x.cpp:1852
    -
    bool initialize()
    Initializes BNO08x sensor.
    Definition BNO08x.cpp:114
    -
    float get_pitch_deg()
    Get the reported rotation about y axis.
    Definition BNO08x.cpp:1510
    -
    float get_yaw_deg()
    Get the reported rotation about z axis.
    Definition BNO08x.cpp:1520
    +
    void enable_game_rotation_vector(uint16_t time_between_reports)
    Sends command to enable game rotation vector reports (See Ref. Manual 6.5.19)
    Definition BNO08x.cpp:1002
    +
    float get_roll_deg()
    Get the reported rotation about x axis.
    Definition BNO08x.cpp:1505
    +
    void enable_gyro(uint16_t time_between_reports)
    Sends command to enable gyro reports (See Ref. Manual 6.5.13)
    Definition BNO08x.cpp:1106
    +
    float get_gyro_calibrated_velocity_X()
    Get calibrated gyro x axis angular velocity measurement.
    Definition BNO08x.cpp:1846
    +
    float get_gyro_calibrated_velocity_Y()
    Get calibrated gyro y axis angular velocity measurement.
    Definition BNO08x.cpp:1856
    +
    bool initialize()
    Initializes BNO08x sensor.
    Definition BNO08x.cpp:119
    +
    float get_pitch_deg()
    Get the reported rotation about y axis.
    Definition BNO08x.cpp:1515
    +
    float get_yaw_deg()
    Get the reported rotation about z axis.
    Definition BNO08x.cpp:1525

    (back to top)

    Documentation

    @@ -179,6 +193,19 @@ Documentation

    (back to top)

    +Program Flowcharts

    +

    The following charts illustrate the program flow this library implements for sending and receiving data from BNO08x.
    + These are here to aid development for anyone looking to modify, fork, or contribute.

    +

    (back to top)

    +

    +Receiving Case

    +

    This assumes the user as initialized the imu and has sent a command to enable a report (for ex. enable_game_rotation_vector). image

    +

    (back to top)

    +

    +Sending Case

    +

    image

    +

    (back to top)

    +

    Acknowledgements

    Special thanks to the original creators of the sparkfun BNO080 library. Developing this without a reference would have been much more time consuming.
    https://github.com/sparkfun/SparkFun_BNO080_Arduino_Library
    @@ -187,11 +214,11 @@ Acknowledgements https://github.com/hwBirdy007

    (back to top)

    -

    +

    License

    Distributed under the MIT License. See LICENSE.md for more information.

    (back to top)

    -

    +

    Contact

    Myles Parfeniuk - myles.nosp@m..par.nosp@m.fenyu.nosp@m.k@gm.nosp@m.ail.c.nosp@m.om

    Project Link: https://github.com/myles-parfeniuk/esp32_BNO08x.git

    @@ -200,7 +227,7 @@ Contact
    diff --git a/documentation/html/menu.js b/documentation/html/menu.js index b0b2693..717761d 100644 --- a/documentation/html/menu.js +++ b/documentation/html/menu.js @@ -24,13 +24,12 @@ */ function initMenu(relPath,searchEnabled,serverSide,searchPage,search) { function makeTree(data,relPath) { - var result=''; + let result=''; if ('children' in data) { result+='