12 releases
0.4.0 | Feb 27, 2024 |
---|---|
0.3.4 |
|
0.3.3 | Aug 26, 2021 |
0.3.2 | Dec 11, 2020 |
0.1.5 | Feb 10, 2019 |
#96 in Hardware support
115 downloads per month
275KB
900 lines
Bosch Sensortec BNO055 embedded-hal driver
What is this?
This is a embedded-hal driver for Bosch's Absolute Orientation Sensor BNO055.
It is device-agnostic and uses embedded-hal's Write
/WriteRead
(for I2C)
and Delay
traits for its operation.
Uses and re-exports mint's Quaternion for quaternion reading and EulerAngles for Euler angles and Vector3 for sensor readings.
Feature flags
std
By default, this crate is no_std
compatible. However, you can enable std
features by enabling the std
feature flag.
At the moment this only adds std::error::Error
trait implementation for the Error
type.
serde
The serde
flag adds implementation of Serialize
/ Deserialize
to BNO055Calibration
.
Note: serde
itself is no_std
compatible, however not all serializers are (e.g. serde-json
is not but serde-json-core
is),
so be careful that you're not enabling serde
's std
feature by accident (see here for a complete explanation).
Usage
-
Add a dependency to
Cargo.toml
:cargo add bno055
-
Instantiate and init the device:
// ... declare and configure your I2c and Delay implementations ... // let i2c = ...; // let delay = ...; // Init BNO055 IMU let imu = bno055::Bno055::new(i2c); imu.init(&mut delay)?; // Enable 9-degrees-of-freedom sensor fusion mode with fast magnetometer calibration imu.set_mode(bno055::BNO055OperationMode::NDOF)?; Ok(imu)
-
Read orientation data, quaternion or euler angles (roll, pitch, yaw/heading):
let quat: mint::Quaternion<f32> = imu.quaternion()?; // or: let euler: mint::EulerAngles<f32, ()> = imu.euler_angles()?;
Due to the BNO055 firmware bugs, the Euler angles reading shouldn't be relied on. I recommend to stick with quaternion readings and convert them to the Euler angles later if needed.
Details and examples
Device calibration
To calibrate the device's sensors for first time:
use bno055::{BNO055Calibration, BNO055OperationMode, BNO055_CALIB_SIZE};
let bno055 = ...;
// Enter NDOF (absolute orientation) sensor fusion mode which is also performing
// a regular sensors calibration
bno055.set_mode(BNO055OperationMode::NDOF)?;
// Wait for device to auto-calibrate.
// Please perform steps necessary for auto-calibration to kick in.
// Required steps are described in Datasheet section 3.11
while !bno055.is_fully_calibrated() {}
let calib = bno055.calibration_profile()?;
// Save calibration profile in NVRAM
mcu.nvram_write(BNO055_CALIB_ADDR, calib.as_bytes(), BNO055_CALIB_SIZE)?;
To load a previously saved calibration profile:
use bno055::{BNO055Calibration, BNO055OperationMode, BNO055_CALIB_SIZE};
let bno055 = ...;
// Read saved calibration profile from MCUs NVRAM
let mut buf = [0u8; BNO055_CALIB_SIZE];
mcu.nvram_read(BNO055_CALIB_ADDR, &mut buf, BNO055_CALIB_SIZE)?;
// Apply calibration profile
let calib = BNO055Calibration::from_buf(buf);
bno055.set_calibration_profile(calib)?;
Remapping of axes to correspond your mounting
BNO055 allows to change default axes to meet the chip orientation with an actual physical device orientation, thus providing possibility to place BNO055 chip on PCB as suitable for the designer and to match the chip's axes to physical axes in software later.
use bno055::{AxisRemap, BNO055AxisConfig};
// ...
// Build remap configuration example with X and Y axes swapped:
let remap = AxisRemap::builder()
.swap_x_with(BNO055AxisConfig::AXIS_AS_Y)
.build()
.expect("Failed to build axis remap config");
bno055.set_axis_remap(remap)?;
Please note that AxisRemap
builder (and the chip itself) doesn't allow an invalid state to be constructed,
that is, when one axis is swapped with multiple of others.
For example, swapping axis X
with both Y
and Z
at the same time is not allowed:
AxisRemap::builder()
.swap_x_with(BNO055AxisConfig::AXIS_AS_Y)
.swap_x_with(BNO055AxisConfig::AXIS_AS_Z)
.build()
.unwrap(); // <- panics, .build() returned Err
Changing axes sign
It is also possible to flip the sign of either axis of the chip.
Example of flipping X and Y axes:
bno055
.set_axis_sign(BNO055AxisSign::X_NEGATIVE | bno055::BNO055AxisSign::Y_NEGATIVE)
.expect("Unable to communicate");
Using external 32k crystal
For better performance, it is recommended to connect and use external 32k quartz crystal.
You enable or disable its use by calling set_external_crystal
:
bno055
.set_external_crystal(true)
.expect("Failed to set to external crystal");
Using alternative I2C address
BNO055 allows to change its I2C address from default 0x29
to alternative 0x28
by setting
COM3
pin LOW
.
To connect to device with an alternative address, enable its use by calling with_alternative_address()
:
// use default 0x29 address
let mut bno = bno055::Bno055::new(i2c, delay);
// or:
// use 0x28 address
let mut bno = bno055::Bno055::new(i2c, delay).with_alternative_address();
Change BNO055 power mode
use bno055::{Bno055, BNO055PowerMode};
// Normal mode
bno055.set_power_mode(BNO055PowerMode::NORMAL)?;
// Low-power mode (only accelerometer being awake)
bno055.set_power_mode(BNO055PowerMode::LOW_POWER)?;
// Suspend mode (all sensors and controller are sleeping)
bno055.set_power_mode(BNO055PowerMode::SUSPEND)?;
Read chip temperature
Temperature is specified in degrees Celsius by default.
let temp: i8 = bno055.temperature()?;
Status
What is done and tested and what is not yet:
- Sensor initialization
- Device mode setup
- Device status readout
- Calibration status readout
- External crystal selection
- Axis remap
- Axis sign setup
- Calibration data readout
- Calibration data setup
- Alternative I2C address
- Take register pages into account
- Orientation data readout
- Quaternions
- Euler angles
- Raw sensor data readout
- Raw accelerometer data readout
- Raw gyroscope data readout
- Raw magnetometer data readout
- Linear acceleration data readout
- Gravity vector data readout
- Temperature readout
- Per-sensor configuration (when not in fusion mode)
- Unit selection
- Interrupts
License: MIT.
Contributions welcomed!
Dependencies
~1–1.7MB
~35K SLoC