Loading [MathJax]/extensions/tex2jax.js
ProtoTracer  1.0
Real-time 3D rendering and animation engine
All Classes Namespaces Files Functions Variables Enumerations Enumerator Friends Macros Pages
BNO055.h
Go to the documentation of this file.
1/**
2 * @file BNO055.h
3 * @brief A class for interfacing with the Adafruit BNO055 sensor.
4 *
5 * This file defines the BNO055 class, which provides methods for retrieving and processing sensor data
6 * such as acceleration, angular velocity, magnetic field, gravity vector, and absolute orientation.
7 *
8 * @date 22/12/2024
9 * @author Coela Can't
10 */
11
12#pragma once
13
14#include <Wire.h> // Include for I2C communication.
15#include <Adafruit_Sensor.h> // Include for Adafruit sensor base class.
16#include <Adafruit_BNO055.h> // Include for Adafruit BNO055 sensor library.
17#include <utility/imumaths.h> // Include for mathematical utilities for IMU sensors.
18#include "../../Utils/Filter/QuaternionKalmanFilter.h" // Include for quaternion filtering.
19#include "../../Utils/Filter/VectorRunningAverageFilter.h" // Include for vector filtering.
20#include "../../Utils/Math/Rotation.h" // Include for rotation mathematics.
21
22/**
23 * @class BNO055
24 * @brief A class for managing the Adafruit BNO055 sensor.
25 *
26 * The BNO055 class provides methods for retrieving processed sensor data, including acceleration,
27 * angular velocity, magnetic field, gravity vector, and absolute orientation. It uses filters
28 * to smooth the data for improved reliability.
29 */
30class BNO055 {
31private:
32 sensors_event_t angVelocityData, magnetometerData, accelerometerData, gravityData; ///< Sensor event data.
33 Adafruit_BNO055 bno = Adafruit_BNO055(55, 0x28); ///< BNO055 sensor instance.
34 Vector3D localForce; ///< Computed local force.
35 Vector3D localAcceleration; ///< Raw local acceleration data.
36 Vector3D localMagneticField; ///< Raw local magnetic field data.
37 Vector3D localAngularVelocity; ///< Raw local angular velocity data.
38 Vector3D localGravityVector; ///< Raw local gravity vector data.
39 Vector3D previousLocalAngularVelocity; ///< Previous angular velocity for filtering.
40 Quaternion absoluteOrientation; ///< Computed absolute orientation.
41 long previousMicros; ///< Timestamp of the previous sensor update.
42
46
47 /**
48 * @brief Reads the magnetic field vector from the sensor.
49 *
50 * @return A Vector3D representing the magnetic field.
51 */
53
54 /**
55 * @brief Reads the local acceleration vector from the sensor.
56 *
57 * @return A Vector3D representing the local acceleration.
58 */
60
61 /**
62 * @brief Reads the local angular velocity vector from the sensor.
63 *
64 * @return A Vector3D representing the local angular velocity.
65 */
67
68 /**
69 * @brief Reads the local gravity vector from the sensor.
70 *
71 * @return A Vector3D representing the local gravity vector.
72 */
74
75public:
76 /**
77 * @brief Constructs a BNO055 instance.
78 */
79 BNO055();
80
81 /**
82 * @brief Updates the sensor data and applies filtering.
83 */
84 void Update();
85
86 /**
87 * @brief Retrieves the local magnetic field vector.
88 *
89 * @return A Vector3D representing the magnetic field.
90 */
92
93 /**
94 * @brief Retrieves the computed local force vector.
95 *
96 * @return A Vector3D representing the local force.
97 */
99
100 /**
101 * @brief Retrieves the filtered local acceleration vector.
102 *
103 * @return A Vector3D representing the filtered local acceleration.
104 */
106
107 /**
108 * @brief Retrieves the filtered local angular velocity vector.
109 *
110 * @return A Vector3D representing the filtered local angular velocity.
111 */
113
114 /**
115 * @brief Retrieves the raw local acceleration vector.
116 *
117 * @return A Vector3D representing the raw local acceleration.
118 */
120
121 /**
122 * @brief Retrieves the raw local angular velocity vector.
123 *
124 * @return A Vector3D representing the raw local angular velocity.
125 */
127
128 /**
129 * @brief Retrieves the absolute orientation as a quaternion.
130 *
131 * @return A Quaternion representing the absolute orientation.
132 */
134};
A class for managing the Adafruit BNO055 sensor.
Definition BNO055.h:30
Quaternion GetAbsoluteOrientation()
Retrieves the absolute orientation as a quaternion.
Definition BNO055.cpp:84
Vector3D previousLocalAngularVelocity
Previous angular velocity for filtering.
Definition BNO055.h:39
Vector3D GetLocalAcceleration()
Retrieves the raw local acceleration vector.
Definition BNO055.cpp:76
Quaternion absoluteOrientation
Computed absolute orientation.
Definition BNO055.h:40
Vector3D GetLocalForce()
Retrieves the computed local force vector.
Definition BNO055.cpp:64
Adafruit_BNO055 bno
BNO055 sensor instance.
Definition BNO055.h:33
VectorRunningAverageFilter< 10 > localAngulKF
Filter for angular velocity.
Definition BNO055.h:43
Vector3D ReadMagneticField()
Reads the magnetic field vector from the sensor.
Definition BNO055.cpp:21
Vector3D GetLocalAngularVelocityFiltered()
Retrieves the filtered local angular velocity vector.
Definition BNO055.cpp:72
VectorRunningAverageFilter< 10 > localGraviKF
Filter for gravity vector.
Definition BNO055.h:45
Vector3D localAngularVelocity
Raw local angular velocity data.
Definition BNO055.h:37
BNO055()
Constructs a BNO055 instance.
Definition BNO055.cpp:3
sensors_event_t magnetometerData
Definition BNO055.h:32
Vector3D GetLocalAccelerationFiltered()
Retrieves the filtered local acceleration vector.
Definition BNO055.cpp:68
sensors_event_t angVelocityData
Definition BNO055.h:32
Vector3D localForce
Computed local force.
Definition BNO055.h:34
Vector3D ReadLocalAcceleration()
Reads the local acceleration vector from the sensor.
Definition BNO055.cpp:26
sensors_event_t accelerometerData
Definition BNO055.h:32
Vector3D ReadLocalAngularVelocity()
Reads the local angular velocity vector from the sensor.
Definition BNO055.cpp:31
VectorRunningAverageFilter< 10 > localAccelKF
Filter for acceleration.
Definition BNO055.h:44
Vector3D GetLocalAngularVelocity()
Retrieves the raw local angular velocity vector.
Definition BNO055.cpp:80
Vector3D localMagneticField
Raw local magnetic field data.
Definition BNO055.h:36
sensors_event_t gravityData
Sensor event data.
Definition BNO055.h:32
long previousMicros
Timestamp of the previous sensor update.
Definition BNO055.h:41
Vector3D localAcceleration
Raw local acceleration data.
Definition BNO055.h:35
Vector3D ReadLocalGravityVector()
Reads the local gravity vector from the sensor.
Definition BNO055.cpp:36
void Update()
Updates the sensor data and applies filtering.
Definition BNO055.cpp:41
Vector3D localGravityVector
Raw local gravity vector data.
Definition BNO055.h:38
Vector3D GetLocalMagneticField()
Retrieves the local magnetic field vector.
Definition BNO055.cpp:60
A mathematical construct representing a rotation in 3D space.
Definition Quaternion.h:30
Represents a 3D vector (X, Y, Z) and provides methods for vector arithmetic.
Definition Vector3D.h:26
Applies running average filtering independently to each component of a 3D vector.