Maintained fork of eupn/bno055 for the PID autonomous motor
control system. no_std compatible, embedded-hal 1.0.
The upstream crate had:
- Two
unsafeblocks in calibration serialization (raw pointer casts) — removed - A bug where
AxisRemap::y()returned the X axis — fixed - A 900-line monolithic
lib.rs— split into 9 modules - No tests — 206 tests added
- Unit error type on
AxisRemapBuilder::build()— replaced withInvalidAxisRemap - Redundant I2C writes on every sensor read — page tracking added
- No bulk read option —
all_sensor_data()added (36% faster full-sensor poll) - Three unnecessary dependencies (
byteorder,num-derive,num-traits) — removed
| Component | Value |
|---|---|
| Sensor | Bosch BNO055 (9-axis IMU, on-chip sensor fusion) |
| Host | Raspberry Pi 5 |
| Bus | I2C-1 (/dev/i2c-1) |
| Address | 0x28 (alternate, COM3 pulled LOW) |
| Datasheet | BST-BNO055-DS000 |
src/
sensors.rs 318 lines Sensor reads, bulk read, AllSensorData struct
lib.rs 204 lines Struct, Error, init, reset, I2C helpers, re-exports
axis.rs 191 lines AxisRemap builder, AxisConfig, AxisSign
mode.rs 179 lines OperationMode, PowerMode, RegisterPage
calibration.rs 176 lines Calibration struct, status, profile read/write
acc_config.rs 174 lines AccConfig types, get/set methods
status.rs 141 lines SystemStatus, Revision, SelfTest
regs.rs 122 lines Register addresses
std.rs 18 lines Display impls (std feature only)
Measured on Raspberry Pi 5, I2C-1 at 100kHz (standard mode), BNO055 in NDOF fusion mode.
Sensor stationary on flat surface. Run with cargo bench --bench sensor_reads.
| Read type | I2C bytes | Time | Max throughput |
|---|---|---|---|
| temperature | 1 | 1.02 ms | ~980 Hz |
| calibration_status | 1 | 1.04 ms | ~960 Hz |
| accel_data | 6 | 1.69 ms | ~590 Hz |
| gyro_data | 6 | 1.67 ms | ~600 Hz |
| mag_data | 6 | 1.71 ms | ~585 Hz |
| euler_angles | 6 | 1.70 ms | ~588 Hz |
| linear_acceleration | 6 | 1.70 ms | ~588 Hz |
| gravity | 6 | 1.68 ms | ~595 Hz |
| quaternion | 8 | 1.97 ms | ~508 Hz |
| all 6 sensors (individual) | ~33 | 9.83 ms | ~102 Hz |
| calibration_profile | 22 + mode switch | 43.9 ms | — |
| init | reset + configure | 653.6 ms | — |
Every sensor read wasted an I2C write to set the register page even when already on the correct page. A full sensor loop barely fit in a 10 ms window (100 Hz).
| Read type | I2C bytes | Time | Improvement |
|---|---|---|---|
| temperature | 1 | 0.60 ms | -41% |
| calibration_status | 1 | 0.60 ms | -42% |
| accel_data | 6 | 1.26 ms | -25% |
| gyro_data | 6 | 1.24 ms | -26% |
| mag_data | 6 | 1.26 ms | -26% |
| euler_angles | 6 | 1.24 ms | -27% |
| linear_acceleration | 6 | 1.26 ms | -26% |
| gravity | 6 | 1.26 ms | -25% |
| quaternion | 8 | 1.53 ms | -22% |
| all 6 sensors (individual) | ~33 | 7.16 ms | -27% |
| all_sensor_data (bulk) | 45 | 6.28 ms | -36% |
| calibration_profile | 22 + mode switch | 42.6 ms | -3% |
| init | reset + configure | 652.0 ms | no change |
Full sensor loop: 9.83 ms -> 6.28 ms (~102 Hz -> ~159 Hz).
| # | Optimization | Impact | Details |
|---|---|---|---|
| 1 | Page tracking | -27% on all reads | Added page field to Bno055. set_page() skips the I2C write when already on the correct page. Eliminated ~0.5 ms per read. |
| 2 | Bulk sensor read | -36% vs baseline | New all_sensor_data() reads registers 0x08-0x34 (45 bytes) in one I2C transaction instead of 6+ separate reads. |
| 3 | Removed byteorder |
code quality | Replaced LittleEndian::read_i16() with i16::from_le_bytes() from core. One fewer dependency. |
| 4 | Removed num-derive/num-traits |
code quality | Replaced FromPrimitive derives with manual match arms. Two fewer proc-macro dependencies. |
| 5 | Calibration buffer cleanup | code clarity | Replaced iterator chain with copy_from_slice. |
AxisRemap::y()returned wrong axis — the getter returnedself.xinstead ofself.y, hidden by#[allow(clippy::misnamed_getters)]. Fixed and lint allow removed.
- Removed both
unsafeblocks inBNO055Calibration.from_buf()now constructs field-by-field.as_bytes()now returns an owned[u8; 22]instead of an unsafe&[u8]tied to a raw pointer cast.
- Page tracking —
set_page()tracks the current page and skips the I2C write when the requested page is already active. Aftersoft_reset(), the tracker resets to page 0. - Bulk sensor read — new
all_sensor_data()method reads all sensor registers in one I2C transaction. ReturnsAllSensorDatawithOptionfields based on mode availability.
BNO055Calibration::as_bytes()returns[u8; 22]instead of&[u8].AxisRemapBuilder::build()returnsResult<AxisRemap, InvalidAxisRemap>instead ofResult<AxisRemap, ()>.- New
all_sensor_data()method andAllSensorDatastruct.
byteorder— replaced withi16::from_le_bytes()/u16::from_le_bytes()from core.num-derive— replacedFromPrimitivederive with manual match arms.num-traits— no longer needed withoutFromPrimitive.
lib.rs(996 lines) split into 9 focused modules. No breaking public API change.- Internal fields and helpers changed from private to
pub(crate)to support the split.
206 integration tests covering:
- Every public API method — happy path and I2C error path
- All 13 operation modes — sensor availability matrix
- Calibration
repr(C)struct — byte-by-byte field mapping for all 22 bytes - AxisRemapBuilder — all swap functions, all invalid states, register encoding
- Sensor scaling — exact conversion factors verified for all sensor types
- Bulk read — value consistency with individual reads, mode-dependent availability
- i16 boundary values, alternative I2C address, page switching, mode transitions
- Debug formatting, consecutive reads, double init
Run with cargo test.
use bno055::{Bno055, BNO055OperationMode};
use linux_embedded_hal::{Delay, I2cdev};
let i2c = I2cdev::new("/dev/i2c-1").unwrap();
let mut delay = Delay {};
let mut imu = Bno055::new(i2c).with_alternative_address();
imu.init(&mut delay)?;
imu.set_mode(BNO055OperationMode::NDOF, &mut delay)?;
let quat = imu.quaternion()?;
let euler = imu.euler_angles()?;
let accel = imu.accel_data()?;
let gyro = imu.gyro_data()?;
let mag = imu.mag_data()?;
let temp = imu.temperature()?;// Single I2C transaction — reads all sensors at once.
let data = imu.all_sensor_data()?;
// Fields are Option — None if the current mode doesn't enable that sensor.
if let Some(quat) = data.quaternion {
// Use quaternion orientation
}
if let Some(accel) = data.accel {
// Use accelerometer data (m/s^2)
}
let temp = data.temperature; // Always available| Flag | Effect |
|---|---|
std |
Adds std::error::Error impl for Error type |
serde |
Adds Serialize/Deserialize for BNO055Calibration |
defmt-03 |
Adds defmt::Format derives for no_std logging |
The BNO055 has known I2C clock-stretching issues. If reads fail intermittently:
- Lower I2C bus speed (try 100 kHz standard mode).
- Increase I2C timeout on your host.
- See Adafruit's notes.
The sensor has a 400-650 ms startup delay (datasheet chapter 1.2). If your MCU boots
faster than the sensor, delay before calling init() or retry on failure.
MIT