Communicating with BMI088 using I2C and SPI

In my continued work with inertial sensors, specifically IMU’s for use in autonomous navigation systems, the latest sensor I’ve been using is the BMI088 from Bosch. It’s well regarded for it’s ability to handle vibrations and is supposed to be well suited for robotics and drones. Onboard is a 3-axis accelerometer and 3-axis gyro. While they are on the same chip, they exist as two separate sensors, so communication with each must be handled individually with some uniqueness between the two. The IMU can handle both I2C and SPI protocols. This page aims mostly to keep track of notes for myself, but hopefully helpful to others as well (computer science + electrical engineering from the perspective of a mechanical engineer, oh joy!).

I2C

The first BMI088 breakout board I tried was the Grove board from Seeed Studios. It is configured for I2C only (no SPI connections).

There are some good libraries for this, including ones from Seeed and Bolder Flight Systems. These provide a good option to get up and running. However, wanting to develop a better understanding of this IMU and the communication protocols, I began to write my down drivers, starting development in Arduino, then porting to STM32 (which I’m also learning).

Physical connections are straight forward: Power, GND, SDA and SCL.

BMI088 spec sheet, diagram for I2C:

 

Communication works by the master (microcontroller) sending a message to the slave (BMI088) device and awaiting a reply. Each device connected to the I2C bus has it’s own address, which we must utilize in each communication. I think of the I2C bus (and similarly for SPI), as a neighborhood. The I2C bus (literal wires connecting to the SDA and SCL pins) is like the main street through the neighborhood. Each ‘house’ has an address. In this case, the ‘houses’ are the gyro and accelerometer sensors. Within each ‘house’ are a bunch of ‘rooms’, or in terms of the sensor, registers, each having their own address. These addresses are generally represented in hexadecimal form (0x00, 0x69, etc.).

 

The registers are where all the sensor data and settings reside. As an example, if we wish to read the device ID from the gyro, we must send a message to the gyro that contains both the sensor address and the register address we’re interested in. These addresses are all outlined in the BMI088 data sheet. This is the register information for the gyro ID:

We can see the register is at 0x00. The reset value, or the default value at power-on is 0x0F. Each register will have it’s own default setting. Some are read-only (such as the ID value above), others can be configured, such as the gyro range shown here at register 0x0F:

The reset value for the gyro range is 0x00, which corresponds to a default setting of +/-2000 degrees/second.

Let’s look at a couple example code snippets for working with both of the registers presented above, starting with reading the chip ID for the gyro. To refresh:

Gyro address on I2C bus: 0x69

GYRO_CHIP_ID register: 0x00

Arduino Code: (using Wire.h library)
Wire.beginTransmission(0x69); // Start communication with device at address 0x69
Wire.write(0x00); // Send the register address we're interested in (0x00)
Wire.endTransmission(false); // use 'false' to retain control of bus

Wire.requestFrom(0x69, 1); // requesting 1 byte from device at address 0x69
uint8_t gyroID = Wire.read(); // read the byte (device ID)

 

Now, lets see how to write a value to the gyro. Specifically, let’s change the GYRO_RANGE from 2000 deg/s to 500 deg/s by changing the default register value from 0x00 to 0x02.

Arduino Code: (using Wire.h library)

Wire.beginTransmission(0x69); // Start communication with device at address 0x69
Wire.write(0x0F); // Send the register address we're interested in (0x00)
Wire.write(0x02); // Write the value 0x02 to the above specified register
Wire.endTransmission();

 

Taking this over to the STM32 environment (using STM32CubeIDE), to read the gyro rates for all 3 axis:

#define GYRO_ADDR 0x69
#define GYRO_RATE_X_LSB_ADDR 0x02

uint8_t sensorBuffer[6];

// Tell gyro we want gyro rate

uint8_t buf[1] = { GYRO_RATE_X_LSB_ADDR };
HAL_I2C_Master_Transmit(&hi2c1, GYRO_ADDR<<1, buf, 1, 200);

// Request 6 bytes - the BMI088 will autoincrement the register address after each byte read
// We must shift the sensor address over 1 bit (Arduino does this automatically)

HAL_I2C_Master_Receive(&hi2c1, GYRO_ADDR<<1, sensorBuffer, 6, 500); // 500=timeout(ms)

// Process gyro data
for(int i=0; i<3; i++){
uint8_t byteLSB, byteMSB;
int16_t twoByte;

byteLSB = sensorBuffer[i*2]; // Pull bytes into their own variables so we can manipulate them
byteMSB = sensorBuffer[(i*2)+1];

twoByte = byteMSB << 8 | byteLSB; // Combine both bytes

float rate = twoByte / 16.384; // (32768 / 2000deg/s = 16.384) --- 32768 is largest signed number in 16-bit variable

gyro[i] = rate;
}

With regards to bit shifting the address on the STM32, this is because addresses are 7 bits long. You send the address plus the read/write bit – for a total of 8 bits. The Arduino Wire library does this automatically, but we have to do this manually on the STM32.

This diagram may be helpful to visualizing the address frame (7-bit address + 1-bit read/write bit), from Texas instruments (page 8). Note that the MSB is sent first.

 

 

Important Notes:

  • For I2C, the SDA and SCL connections require pull-up resistors. The Grove board has 4.7k resistors tied to VCC. This works fine for 100 kHz speeds, but I ran into issues when trying to run at the maximum 400 kHz. The fix was to add a couple 2.2k resistors to up the voltage. The only downside of this is technically a little bit more power is used.
  • ACC_PWR_CTRL for accelerometer (address 0x7D) starts in “suspend” mode. It must be changed to “normal” mode by writing 0x04 to the register. There must be a delay of at least 5ms after this change before further communication with the sensor (else you’ll just get 0 values back).
  • Start reading gyro rate data at address 0x02 (RATE_X_LSB). The LSB and MSB come in pairs (16-bit 2’s complement). Once the LSB byte is read, the MSB byte is locked until read to keep both bytes in sync.
  • When reading accel or gyro data, a burst-access mechanism will auto-increment the register address being read. So for the gyro, which contains rate information for each axis at addresses 0x02 to 0x07, you can send a “read” byte to register 0x02, then just keep reading bytes until all 6 have been read. Works for both I2C and SPI protocols.

 

 

SPI

Since the Grove board doesn’t support SPI, I sought out a BMI088 breakout board that did. Apparently there really aren’t many options. The only available board I could find was the BMI088 Shuttle board from Bosch, which was designed to work with their development system. However, looking at the schematic, the board looks pretty bare-bones, so as long as I can work with the form factor, I’ll be golden.

The pin spacing on the Shuttle is only 0.05″ instead of the typical 0.1″ found on breakout boards. I found  some adaptor boards on Amazon that will fix the pitch spacing.

The finished board:

BMI088 Shuttle Pins:

Pin connections from board, top view (orientation coincides with my above photo):

 

BMI088 pin-out and hardware connections on Shuttle:


 

From BMI088 datasheet:

 

SPI communication:

The general process of working with the BMI088 using SPI is very similar to I2C, though there are some notable differences, especially with the accelerometer.

  • Gotcha #1: During read operations with the accelerometer (this doesn’t apply to gyro), after the register address is sent to the chip, it will first send a “dummy” byte back, which must be discarded. For example, if we wish to read the accelerometer’s CHIP_ID, once we send the register address 0x00, we will expect to get back two bytes. The first byte is the dummy, which we will ignore, the 2nd byte is the ID value we want. For reading the ACC data for all 3 axis, we’ll actually need to read 7 bytes rather than just the 6 we did with I2C, with the very first byte being discarded.
  • Gotcha #2: The accelerometer, by default, begins in suspend power mode. you MUST change the mode to normal to activate this sensor by writing 0x04 to register ACC_PWR_CTRL.
  • Gotcha #3: The accelerometer, by default, begins in I2C mode. To change it to SPI, the CSB1 pin looks for a rising edge (setting that pin HIGH). Once switched to SPI mode, it will stay there until power-on-reset.
  • Ensure the microcontroller can handle the speed that is set in code. Fastest SPI speed is 1/2 of microcontroller clock speed. For the Arduino UNO, which has a 16 MHz clock, the fastest SPI speed is 8 MHz (8000000 Hz) or less.
  • In general, most SPI devices send MSB first, so bit #7 gets sent first, then #6, etc.
  • With SPI, if you send a byte you have to receive a byte, and if you want to receive a byte, you have to send a byte. That means one of the devices will be sending a “dummy” byte.
Let’s jump into an Arduino code sample. Of note, ensure that the CS lines for both gyro and accelerometer are declared as “OUTPUT”, even if you should be working with only one of those two sensors (I found out the hard way and left one ‘floating’… eventually I discovered why things weren’t working right!).
 
Code to get things setup:
#include <SPI.h>

#define CS_ACCEL 8  // Chip select for accelerometer
#define CS_GYRO 9   // Chip select for gyroscope

float gyro[3], acc[3];

void setup() {

    Serial.begin(115200);

    delay(1); // ensure sensor has had at least 1ms boot-up time

    SPI.begin();

    pinMode(CS_ACCEL, OUTPUT);
  pinMode(CS_GYRO, OUTPUT);

// For both CSB1 (ACCEL CS) and CSB2 (GYRO CS), setting pins HIGH deselects them
// For CSB1 (accelerometer), setting CSB1 high changes ACCELEROMETER protocol from I2C to SPI
  digitalWrite(CS_ACCEL, HIGH);
  digitalWrite(CS_GYRO, HIGH);
}

 

To read a register, I have this simple function, which I’ll break-down:

uint8_t gyroReadRegister(uint8_t csPin, uint8_t reg) {
  digitalWrite(csPin, LOW); // Set gyro CS pin to LOW to select device
  SPI.transfer(reg | 0x80);  // Set read bit to 1 (0x80 = 0b10000000)
  uint8_t value = SPI.transfer(0x00);  // Read
  digitalWrite(csPin, HIGH);
  return value;
}

Using SPI, we have to first select the device we wish to communicate with on the bus. We do this by setting the CS (chip select) pin to LOW. Then, we send the register address. Note, at least for the gyro, this is a 16-bit protocol. We send either the register address + data byte, or register address + dummy byte. Because the address is only 7 bits, we need to add 1 more bit that tells the device if this is a READ or WRITE operation. A read operation sets this bit to 1, while a write operation uses 0. Since the MSB bit is sent first, we set the furthest left bit (bit #7) to 1. The diagram below gives a visual illustration of this. Note this is opposite of how I2C addresses are formatted (which place the R/W bit on the far right at the LSB).

Just like with I2C, we can then read the return byte. To do so, we end up sending a dummy byte for each read we want to do (0x00 is used here). Sending this dummy byte also completes the 16-bit protocol requirement (see datasheet for details). Once we’ve read our byte, we deselect the device by returning the CS pin to HIGH.

If were were writing a value to a register instead, the code would look like this:

// Write single value to sensor register (works for both gyro and accelerometer)

void writeRegister(uint8_t csPin, uint8_t reg, uint8_t value) {
  digitalWrite(csPin, LOW); // Select sensor
  SPI.transfer(reg);  // Send register address (write bit, MSB, should be 0 already)
  SPI.transfer(value); // Send single value
  digitalWrite(csPin, HIGH); // De-select sensor
}

 

Moving back over to the STM32. I’m specifically using the STM32H723 Nucleo board for my current work. Configuring the SPI is fairly easy, though there are a lot of places to go wrong. I’ve setup SPI1. My settings to work with the BMI088 are shown below:

Things to note:

  • The IDE will setup the SCK, MISO and MOSI pins. However, the CS pins must be manually configured by choosing a couple available pins to making them GPIO_Output. We’ll then manually control these in code to select the desired sensor.

Here’s a learning experience I had. I ran into an issue with one of my chosen CS pins, PB2, which I’m using for the accelerometer. Confident I had my wiring correct, and having already gotten SPI working on the STM32 with the gyro, I spent far too long trying to get SPI working with the accelerometer. Eventually I discovered there are two PB2 pins on the board and they are not connected:

I had my CS pin connected to PB2(D72), which wasn’t working. The other PB2 pin is D27. Once I swapped my wire over to the other PB2 pin, things suddenly worked as expected. But why? Diving back into the datasheet for the Nucleo board I found answers.

Per the datasheet, PB2 is connected to QSPI_CLK by default, which corresponds to the PB2(D27) pin, and not the PB2(D72) pin. Mystery solved!

Here’s a couple code samples to read and write from the gyro:

// SPI - Gyro Read
void gyroRead(uint8_t sensorRegister, uint16_t numBytes, uint8_t* readBuffer)
{
sensorRegister |= 0x80; // read operation, MSB must be set to 1

HAL_GPIO_WritePin(GPIOB, CS_GYRO_Pin, GPIO_PIN_RESET); // set CS line LOW to select
HAL_SPI_Transmit(&hspi1, &sensorRegister, 1, 100); // send register address we wish to read from
HAL_SPI_Receive(&hspi1, readBuffer, numBytes, 100);
HAL_GPIO_WritePin(GPIOB, CS_GYRO_Pin, GPIO_PIN_SET); // set CS line HIGH to deselect
}

 

// SPI - Gyro Write
void gyroWrite(uint8_t sensorRegister, uint8_t sensorMsg)
{
uint8_t TX_Buffer [] = { sensorRegister, sensorMsg } ; // DATA to send

HAL_GPIO_WritePin(GPIOB, CS_GYRO_Pin, GPIO_PIN_RESET); // set CS line LOW to select
HAL_SPI_Transmit(&hspi1, TX_Buffer, 2, 100); // tell how many bytes, wait time
HAL_GPIO_WritePin(GPIOB, CS_GYRO_Pin, GPIO_PIN_SET); // set CS line HIGH to deselect
}

 

Lets wrap this up with one more example reading from the accelerometer since it’s slightly different with needing to discard the first byte:

// SPI - Accelerometer Read
void accelRead(uint8_t sensorRegister, uint16_t numBytes, uint8_t* readBuffer)
{
sensorRegister |= 0x80; // read operation, MSB must be set to 1
uint8_t discardByte;

HAL_GPIO_WritePin(GPIOB, CS_ACCEL_Pin, GPIO_PIN_RESET); // set CS line LOW to select

HAL_SPI_Transmit(&hspi1, &sensorRegister, 1, 100);
// send register address we wish to read from
HAL_SPI_Receive(&hspi1, &discardByte, 1, 100); // first byte received is to be discarded (per datasheet)
HAL_SPI_Receive(&hspi1, readBuffer, numBytes, 100);

HAL_GPIO_WritePin(GPIOB, CS_ACCEL_Pin,
GPIO_PIN_SET); // set CS line HIGH to deselect
}

 

Bit Masking

Reading from some registers on the BMI088 (and many other devices for that matter) require some bitwise operations due to the formatting of the register data. As an example, the BMI088 accelerometer has a register, 0x02, that returns error codes. There are two different errors grouped into one returned byte:

Bits 4:2 contain any “persistent errors”, and bit 0 is a flag indicating a “fatal error”. To pull these out of the returned byte, bit masking can be used. Using the above example, in order to retrieve the “error_code” for the accelerometer, we need to pull out bits 4:2 using the following bit mask:

Using the bitwise ‘&’ (AND) operator, we can extract just the 3 bits we care about. This result then needs to be shifted two(2) bits to the right. This might look like:

uint8_t error_code = (readByte & 0x1C) >> 2;

 

Comments

Leave a Reply

Your email address will not be published. Required fields are marked *