The Bosch BNO055 combines tri-axis accelerometers, gyroscopes, and magnetometers to provide orientation to users.

About the Sensor

The BNO055 uses three triple-axis sensors to simultaneously measure tangential acceleration (via an accelerometer), rotational acceleration (via a gyroscope), and the strength of the local magnetic field (via a magnetometer). Data can then be either sent to an external microprocessor or analyzed inside the sensor with an M0+ microprocessor running a proprietary fusion algorithm. Users then have the option of requesting data from the sensor in a variety of formats.

The chip also has an interrupt that can notify the host microcontroller when certain motion has occurred (change in orientation, sudden acceleration, etc.).

 

Re-created block diagram from datasheet

 

The sensor must be calibrated prior to use and a read register holds the current calibration status. Once calibrated, the calibration offsets can be written to the sensor and then the sensor is immediately ready to use the next time it is powered on.

See the video below to learn how to calibrate your sensor.

 


  UART Interface     Handling Soldering Specifications     Datasheet  


A host microcontroller can request any or all of the data from the sensors (accelerometer, gyroscope, and/or magnetometer) in non-fusion mode and can request absolute and relative orientation (angles or quaternions) in fusion mode.

The sensor can return acceleration in m/s² or mg ($$1 mg=9.81\frac{m}{s^2}\times 10^{-3}$$); magnetic field strength in mT; gyroscope data in degrees or radians per second (DPS and RPS, respectively), Euler angles in degrees or radians, or quaternions; and temperature in °C or °F.  All options are set in the unit_selection register (table 3-11 in the datasheet, PDF page 30).

 

Euler Angles vs. Quaternions

If you are designing a sensor solution for a system that has a limited range of motion, you can use Euler angles. But if you are designing a sensor that can be oriented anywhere in space, you should use quaternions.

 

Euler Angles

Euler angles allow for simple visualization of objects rotated three times around perpendicular axes (x-y-x, x-z-x, y-x-y, y-z-y, z-x-z, z-y-z, x-y-z, x-z-y, y-x-z, y-z-x, z-x-y, z-y-x).

 

x-y-z rotations from Wolfram.com

 

As long as the axes stay at least partially perpendicular, they are sufficient. However, as the axes rotate, an angle exists where two axes can describe the same rotation—creating a condition known as gimbal lock. When gimbal lock occurs, it is impossible to reorient without an external reference. See my article, Don't Get Lost in Deep Space: Understanding Quaternions, to learn more about gimbal lock.

 

This animation has three gimbals (shown as red, green, and blue solid cylinder segments) along with the available rotations (shown as red, green, and blue transparent spherical lunes). When the plane of the internal green gimbal aligns with the plane of the red gimbal, the axes of rotation of the red and blue gimbals overlap and gimbal lock occurs (indicated by a light-yellow background).

 

The problem of gimbal lock does not exist when using quaternions.

 

Quaternions

Quaternions were invented by William Hamilton in 1843 as a way to multiply and divide three numbers. They slowly fell out of favor over the course of many decades and saw a revitalization in the nuclear era and again with modern computer graphics programming. A quaternion consists of four numbers: a scalar and a three-component vector.

 

 .

 

where w, x, y, and z are all real numbers and i, j, and k are quaternion units.

Typically, w, x, y, and z are kept in the range between -1 and 1, and $$\sqrt{w^2+x^2+y^2+z^2}=1$$.  

These four numbers succinctly reorient vectors in a single rotation with or without changes in length.

 

The blue and red vectors are of unit length. The orange is the rotation required to rotate the blue vector into the red.

 

Normal transformation matrices consist of nine numbers and involve the application of trigonometric functions. Quaternions consist of four numbers, all less than or equal to one. It is possible to convert a quaternion to an orthogonal transformation matrix but, due to the mathematical properties associated with gimbal lock (again, see my quaternion article for more information), it is slightly more difficult to convert from rotation matrix to a quaternion.

 

Method of converting a quaternion to a 3x3 orthogonal rotation matrix.

 

The code snippets below demonstrate how to create a 3×3 transformation matrix and roll, pitch, and yaw angles from a quaternion.

 

                    /* Create Rotation Matrix rm from Quaternion */
double rm[3][3];

rm[1][1] = quat.w()*quat.w() + quat.x()*quat.x() - quat.y()*quat.y() - quat.z()*quat.z();   
rm[1][2] = 2*quat.x()*quat.y() - 2*quat.w()*quat.z();            
rm[1][3] = 2*quat.x()*quat.z() + 2*quat.w()*quat.y();
rm[2][1] = 2*quat.x()*quat.y() + 2*quat.w()*quat.z();       
rm[2][2] = quat.w()*quat.w() - quat.x()*quat.x() + quat.y()*quat.y() - quat.z()*quat.z();          
rm[2][3] = 2*quat.y()*quat.z() - 2*quat.w()*quat.x();     
rm[3][1] = 2*quat.x()*quat.z() - 2*quat.w()*quat.y();       
rm[3][2] = 2*quat.y()*quat.z() + 2*quat.w()*quat.x();            
rm[3][3] = quat.w()*quat.w() - quat.x()*quat.x() - quat.y()*quat.y() + quat.z()*quat.z();

/* Display Rotation Matrix */
Serial.print(rm[1][1],5);Serial.print("  \t");
Serial.print(rm[1][2],5);Serial.print("  \t");
Serial.println(rm[1][3],5);
Serial.print(rm[2][1],5);Serial.print("  \t");
Serial.print(rm[2][2],5);Serial.print("  \t");
Serial.println(rm[2][3],5);
Serial.print(rm[3][1],5);Serial.print("  \t");
Serial.print(rm[3][2],5);Serial.print("  \t");
Serial.println(rm[3][3],5);

/* Create Roll Pitch Yaw Angles from Quaternions */
double yy = quat.y() * quat.y(); // 2 Uses below

double roll = atan2(2 * (quat.w() * quat.x() + quat.y() * quat.z()), 1 - 2*(quat.x() * quat.x() + yy));
double pitch = asin(2 * quat.w() * quat.y() - quat.x() * quat.z());
double yaw = atan2(2 * (quat.w() * quat.z() + quat.x() * quat.y()), 1 - 2*(yy+quat.z() * quat.z()));

/*  Convert Radians to Degrees */
float rollDeg  = 57.2958 * roll;
float pitchDeg = 57.2958 * pitch;
float yawDeg   = 57.2958 * yaw;

/*  Display Roll, Pitch, and Yaw in Radians and Degrees*/
Serial.print("Roll:");  Serial.print(roll,5);  Serial.print(" Radians \t"); Serial.print(rollDeg,2);  Serial.println(" Degrees");
Serial.print("Pitch:"); Serial.print(pitch,5); Serial.print(" Radians \t"); Serial.print(pitchDeg,2); Serial.println(" Degrees");
Serial.print("Yaw:");   Serial.print(yaw,5);   Serial.print(" Radians \t"); Serial.print(yawDeg,2);   Serial.println(" Degrees");

                  

Interfacing the Sensor with Arduino

I purchased the BNO055 sensor affixed to a development board with support components from Adafruit. It is possible to save a bit of money by purchasing the BNO055 from Digi-Key or Mouser and soldering it to a 7.5×4.4mm 28-pin LGA to DIP converter for prototyping on a solderless breadboard. But for the marginal cost savings after shipping, I wouldn't recommend it.

To get started interfacing your BNO055 with an Arduino, follow these steps:

  1. Connect power, ground, SDA, and SCL
  2. Open the Arduino IDE and click on Sketch→Include Library→Manage Libraries
  3. Search for and install "Adafruit BNO055" and "Adafruit Sensor"
  4. Open and edit File→Examples→Adafruit BNO055→Raw Data to comment out the Euler angle section and uncomment the Quaternion section, or copy and paste the abridged code below.

 

                    #include <Wire.h>
#include <Adafruit_Sensor.h>
#include <Adafruit_BNO055.h>
#include <utility/imumaths.h>

/*
This program is an abridged version of Adafruit BNO055 rawdata.ino available after installing the Adafruit BNO055 library
File→Examples→Adafruit BNO055→Raw Data
  Connections on Arduino Uno
  =========================================================================
  SCL to analog 5 | SDA to analog 4 | VDD to 3.3V DC | GND to common ground
*/

#define BNO055_SAMPLERATE_DELAY_MS (100)          // Delay between data requests

Adafruit_BNO055 bno = Adafruit_BNO055();          // Create sensor object bno based on Adafruit_BNO055 library

void setup(void)
{
  Serial.begin(115200);                           // Begin serial port communication
  if(!bno.begin())                                // Initialize sensor communication
  {  
    Serial.print("Ooops, no BNO055 detected ... Check your wiring or I2C ADDR!");  
  }
  delay(1000);
  bno.setExtCrystalUse(true);                     // Use the crystal on the development board
}

void loop(void)
{
  imu::Quaternion quat = bno.getQuat();           // Request quaternion data from BNO055

  Serial.print(quat.w(), 4);  Serial.print("\t"); // Print quaternion w
  Serial.print(quat.x(), 4);  Serial.print("\t"); // Print quaternion x
  Serial.print(quat.y(), 4);  Serial.print("\t"); // Print quaternion y
  Serial.print(quat.z(), 4);  Serial.println();   // Print quaternion z

  delay(BNO055_SAMPLERATE_DELAY_MS);              // Pause before capturing new data
}
                  

The program simply communicates with the BNO055 over I²C and streams the data back to the computer over a UART port. Quaternion data is sent back as tab-separated data with newlines after each quaternion.

Keep in mind that until your sensor is calibrated, your data is not valid.

 

Sample Quaternion Data

For the following example, I requested quaternion data from the BNO055 as I placed it in a random orientation near my desk. You can interpret the data manually at WolframAlpha.com by entering it as comma separated values enclosed in parenthesis after the word quaternion (e.g., "Quaternion(0.403, 0.414, 0.085, 0.812)")

 

W X Y Z
0.40344238 0.41363525 0.08508301 0.81176757
The numbers above are a quaternion that describes the current orientation of the sensor with respect to the reference orientation.
 

Image from WolframAlpha.com shows default and actual orientation of object

 

Image from WolframAlpha.com shows rotation axis and amount of rotation needed to reach the current position from the default position.

 

 

While it's certainly not necessary to look to the Internet to process your quaternion data, it is nice to have the option to double-check your work.

 

Capturing Data with Mathematica

Mathematica is a versatile computer program that can process almost any data you can imagine. For those interested, I put together a few lines of code that demonstrate how to receive data from a device and how to use Mathematica to evaluate the data with a few quaternion-based functions. The code below was written for Windows, so Linux and Mac users might have to change the input device line (the line that begins bConnect).

 

Screenshot of the Mathematica Notebook available via the download button below

 

Mathematica allows data to be collected and processed in real-time and after the fact. For this demonstration, I opted for a program that collects the data from the serial buffer, converts it to a rotation matrix, and uses the rotation matrix to reorient an arrow in a reference sphere.

Begin by clicking "Connect Arduino" and then "Data from Buffer." I didn't incorporate any data validation or error checking, so if the data area is blank or misformatted, the only option is to recollect the data.

Mathematica is capable of reading and working with data as it arrives over the serial port, but for this demonstration, the 30 or so measurements stored in the buffer should be sufficient to see how the program works.

 

Data sent from the BNO055 is analyzed in Mathematica and used to reorient an arrow in a reference sphere

 

  Quaternion with Mathematica  


Controlling a Two-Axis Gimbal

The BNO055 is well-suited for robotics use. As an example application, I'll use the BNO055 to control a laser mounted on a servo-based two-axis gimbal. The code should allow the seamless introduction of a third axis-of-rotation for any reader fortunate enough to have one.

Connect the BNO055 as before and add servos, connected to digital pins 9-11. If you're using the gimbals to hold a camera, consider upgrading to the Alorium XLR8 board. Servos rely on precise timing, and if the Arduino is processing competing tasks, it can lead to jitter. The XLR8 is a drop-in replacement of the Arduino made from an FPGA. It has a library that can control the servos from a separate "XLR8tor" (accelerator) block for steady and fluid servo movement.

 

Wiring overview of the circuit

 

Arduino Uno R3 replacements:  XLR8 vs Sparkfun "Redboard" Arduino Uno R3

 

                    //---- Included Libraries ----//
#include <Wire.h>                           // I²C library
#include <math.h>                           // trig functions
#include <Adafruit_Sensor.h>                // Base library for sensors
#include <Adafruit_BNO055.h>                // BNO055 specific library
#include <utility/imumaths.h>               // Vector, Matrix, and IMUMath library
//#include <servo.h>                        // Standard Servo library
#include <XLR8Servo.h>                      // XLR8 servo library
#include <XLR8Float.h>                      // XLR8 accelerated floating point math

#define BNO055_SAMPLERATE_DELAY_MS (50)     // Set pause between samples

//---- Variable Declaration ----//

boolean debug = true;                       // true/false = extra/no information over serial

int rollPin  = 9;                           // Digital pin for roll
int yawPin   = 10;                          // Digital pin for yaw
int pitchPin = 11;                          // Digital pin for pitch

float roll, pitch, yaw;                     // Variable to hold roll, pitch, yaw information

Adafruit_BNO055 bno = Adafruit_BNO055();    // Use object bno to hold information

Servo rollServo;                            // Create servo rollServo
Servo pitchServo;                           // Create servo pitchServo
Servo yawServo;                             // Create servo yawServo

void setup(void) {

  rollServo.attach(rollPin);                // The rollServo is connected at rollPin
  pitchServo.attach(pitchPin);              // The pitchServo is connected at pitchPin
  yawServo.attach(yawPin);                  // The yawServo is connected at yawPin

  Serial.begin(115200);                     // Create serial connection at 115,000 Baud

  if (!bno.begin())                         // Attempt communication with sensor
  {
    Serial.print("Ooops, no BNO055 detected ... Check your wiring or I2C ADDR!");
  }

  delay(100);                               // Wait 0.1 seconds to allow it to initialize
  bno.setExtCrystalUse(true);               // Tell sensor to use external crystal
}

//---- Main Program Loop ----//
void loop() {

  //---- Request Euler Angles from Sensor ----//
  imu::Vector<3> euler = bno.getVector(Adafruit_BNO055::VECTOR_EULER);

  if (debug) {                             // If debug is true, send information over serial
    Serial.print("Measured Euler Roll-Pitch-Yaw");
    Serial.print("\t   yaw: "); Serial.print(euler.x()); Serial.print("\t");
    Serial.print("\t pitch: "); Serial.print(euler.z()); Serial.print("\t");
    Serial.print("\t  roll: "); Serial.print(euler.y()); Serial.println();
  }
  /* Remap information from the sensor over the 0° - 180° range of the servo
     The Yaw values are between 0° to +360°
     The Roll values are between -90° and +90°
     The Pitch values are between -180° and +180°
  */
  int servoYaw   = map(euler.x(),   0, 360, 0, 180);
  int servoRoll =  map(euler.y(),  -90, 90, 0, 180);
  int servoPitch = map(euler.z(), -180, 180, 0, 180);

  if (debug) {                             // If debug is true, send information over serial
    Serial.print("Measured Euler Roll-Pitch-Yaw");
    Serial.print("\t   Yaw Servo: "); Serial.print(servoYaw);   Serial.print("\t");
    Serial.print("\t Pitch Servo: "); Serial.print(servoPitch); Serial.print("\t");
    Serial.print("\t  Roll Servo: "); Serial.print(servoRoll);  Serial.println();
  }
  // If debug is true, send information over serial
  if (debug) {
    Serial.println("Calculated Servo Roll-Pitch-Yaw");
    Serial.print("\t roll:");  Serial.print(servoRoll, DEC);  Serial.print("\t");
    Serial.print("\t pitch:"); Serial.print(servoPitch, DEC); Serial.print("\t");
    Serial.print("\t yaw:");   Serial.print(servoYaw, DEC);   Serial.println();
  }

  rollServo.write(servoRoll);              // Send mapped value to rollServo
  pitchServo.write(servoPitch);            // Send mapped value to rollServo
  yawServo.write(servoYaw);                // Send mapped value to rollServo

  delay(BNO055_SAMPLERATE_DELAY_MS);       // Wait before rerunning loop
}
                  

  Arduino Sketches for BNO055  


Check out my project in action below:

 


Conclusion

The BNO055 is an easy-to-use inertial measurement unit that could be incorporated into a wide variety of applications, from robot stabilization (quadcopter, inverted pendulum, etc.) to camera stabilization and navigation (including dead reckoning).

Unlike other 9-DOF systems that output raw measurement data, the BNO055 filters and synthesizes data for a host microcontroller, thereby freeing up processor bandwidth and taking the guesswork out of programming.

Readers—if you would like to see a project or article that uses quaternions in greater depth, please let us know in the comment section below.

 

Featured image courtesy of Adafruit.

 

Comments

12 Comments


  • Funny how this article show how good is this device but doesn’t show the complaint of people having drift over time and unstable calibration.

    • Mark Hughes 2017-03-23

      @Christian Bianchini 1,
          Thanks for joining the site today, it’s always nice to get new members.  From the tone of your comment, I assume you have the sensor and have difficulty in your application.  What problem are you experiencing and in what application?  (I assume that you wrote the calibration values to the registers rather than leaving it in a state of continuous calibration?).
      Mark

  • Neil Benson 2017-03-25

    Yes, please, I would like to see more examples of quaternion usage.

  • tanming 2017-04-17

    Please tell me about the theory (math) of calculate the angle? I am doing a project using BNo055 to detect the angle, but confused about how to do it.

    • Mark Hughes 2017-04-18

      Hi @tanming,
          First, take steps to calibrate the sensor according to the datasheet or the video in the article and write the calibration values to tot he sensor—working with an uncalibrated sensor will produce unreliable and sometimes contradictory results.  Second—are you using quaternions or Euler Angles?  Euler angles have some drawbacks, and quaternions can be difficult to understand—I did write an article about the two that provides an introduction to the subject:  http://www.allaboutcircuits.com/technical-articles/dont-get-lost-in-deep-space-understanding-quaternions/

      Are you using pitch (-180,180), roll (-90,90), and yaw (0,360) to keep track of things, quaternions, or quaternions converted to pitch, roll, yaw?  If you can explain a little more of what’s troubling you, I’ll do my best to help—although we might need to move this conversation to the forums where there is more room to type.
      Thanks,
      Mark

  • Mingming Zhang 2017-06-02

    Hi

    I have been using this sensor a lot lately. There are several problems that I want to get an idea from you.

    1). When the sensor is fully calibrated, at its original position there is a reading (Yaw Pitch Roll), associated with the original position. After a long time of movement, I placed the sensor back to its original position, the Yaw could be off by some constant degree, 20 - 50 degree depending on the environment. Why this is happening? The sensor is always auto calibrate itself, but still I am expecting the reading at original position was more or less the same. Can you explain this and how to solve this.

    2. Calibrate could be very painful and not stable, i.e. gyro, acc, and mag status are all 3, but sys indicates 0. Why is that?

    Thanks

    • Mark Hughes 2017-06-02

      Hi @Mingming Zhang,
          Glad you like the sensor—sorry you are having troubles.
        The BNO055 doesn’t have an internal EEPROM to store calibration data—so every time that the sensor loses power, the calibration data disappears with it.  Ideally, you would enter calibration mode just once (default at power-on), carefully go through the steps to calibrate the sensor (Datasheet page 47), and read the calibration data to store externally to non-volatile memory (EEPROM.)  Then the next time the BNO055 is powered on, read the calibration profile from the EEPROM memory and send it to the BNO055.  From the datasheet:  “Once the sensor enters the internal calibration routine, the calibration profile is overwritten with the newly obtained sensor offsets and sensor radius.”

      I suspect that your sensor is in a continuous state of calibration.  How did that happen?  Well provided that you are using the sample code I have posted above, the code that controls the mode of the device is hidden in the header files of the BNO055 library (Adafruit_BNO055.h, Adafruit_BNO055.cpp, Adafruit_Sensors.h, etc…)
      Look for lines like this:
      OPERATION_MODE_CONFIG = 0x00, ..., OPERATION_MODE_IMUPLUS - 0x08, etc…
      and like this:
      void Adafruit_BNO055::setMode(adafruit_bno055_opmode_t mode)
      {
      _mode = mode;
      write8(BNO055_OPR_MODE_ADDR, _mode);
      delay(30);
      }

      Also, there might be some stray magnetic fields near your work surface that are messing with things (ferrous-metal bolts, screws, worksurface, etc…)

      So—to summarize—you should only have to calibrate once—once calibrated—get out of the config mode—otherwise the calibration data that you worked so hard to get will be continuously overwritten—resulting in a sensor that gives wildly inaccurate readings.

      Does that make sense?  Do you need additional assistance?  If so, please create a post in the forum and ping me and I’ll try to assist you more.

      Thanks,
      Mark

      • Oscar Salgado 2017-06-15

        Hey Mark, I just started playing with the Adafruit BNO055 and your article is clearing up a lot on how to get started.

        In your code you haven’t used the setMode method that you mention in this comment. Why is that? If I am understanding correctly, I should calibrate my sensor, save the offsets to the EEPROM, and then each time the sensor boots up, the sensor is in config mode by default. While it is here, I should read the offset values from EEPROM, set them to the sensor and then change the mode using the setMode method. Is that right?

        • Mark Hughes 2017-06-15

          Hi @Oscar Salgado,
              Hi Oscar—you don’t see any setMode in my functions because I am not switching into and out of a calibration state.  When I wrote this article, I only used the BNO055 once and only carefully calibrated the sensor once, and since I kept the sensor powered on while I made the other sketches, I didn’t worry about it again or frankly even think about it again.  In retrospect, I wish I had written the article to include more about the calibration offsets and radius and included a software routine and schematics that included an integrated external EEPROM, as this article has attracted quite a few confused makers—so sorry about that.
             
              You have to calibrate the device—the sketches in the adafruit example library provide a calibration status (0 is not calibrated, 3 is calibrated, 1 and 2 are somewhere in between).  Once you get to level 3, the device is calibrated.  You can read the data from the registers while the operation mode is CONFIG_MODE.
              Perhaps include a switch/button on your board that you press (or do it automatically with code at startup) that does the following steps listed on page 48 of the datasheet (once calibrated).
            1)  Change operation mode to CONFIG_MODE
            2)  Write the sensor offsets and radius data
            3)  Change to fusion mode.
              If you go to https://github.com/adafruit/Adafruit_BNO055/blob/master/examples/restore_offsets/restore_offsets.ino you’ll see a sketch that does this.
              I hope this helps—if you need further assistance, please create a post in the forums and ping me and I will try to assist you.  This is the maximum comment depth and you will not be able to reply to my post, however, you should still be able to reply to the original article.

        • Freddy4711 2017-11-02

          Hi all,
          I am also playing with the BNO055 since a few days. And despite of all data sheet reading and reading of the comments above I am still confused about the auto calibration of the device. In the last comment Mark recommends the steps listed on page 48 in the datasheet. After loading the previousely stored cal data we change from CONFIG to FUSION mode. But what happens? The autocal in the background starts to run…. and the problems come up. There is footnote (5) on page 48 saying that the permanent background calibration can not be disabled.
          So what is my problem?
          I run the BNO55 in car to measure the horizontal acceleration, preferably without the influence of the gravity vector. I switch on IMU mode, do the cal steps as recommended, wait for the cal status bits to report 03 for the gyroscope and 03 for the acc sensor. The sensor is now mounted in a perpendicular manner on the dashboard and I compare the raw accel data in driving direction and the linear accel that the fusion algorithm reports. I expect the linear accel to be free of influence of road inclination and vehicle pitching. But what happens when I moderately accelerate and brake the vehicle? The raw accel is what I expect from the speed increase/decrease. The fusion accel follows the expected output for 1 or 2 seconds but approaches zero after a few seconds although the vehicle is still accelerating or braking constantly. The vehicle acceleration/deceleration is nearly constant. I can easily derive this from a straight speed trace going up up or down. I guess that the permanent recalibration cancels my moderate acceleration to zero. For one or two seconds the linear accel looks realistic, thereafter it is definitely wrong, while the raw accel data is realistic.
          Isn’t there a chance to disable the internal recal for a while?
          I havn’t found any details about the autocal procedure that Bosch implemented. There is a nice video showing how simple one can calibrate the sensor. The video is like a hocus-pocus… but no in-depth information. The user is left alone in the end.
          Mark, can you tell me what I need to know?

  • Mark Hughes 2017-11-03

    @Freddy4711,
        When I wrote this article, my interest with the BNO055 lied primarily with the quaternion information, so I did not do a full implementation with custom code.  I used a library that was already available.  Had I known at the time how vexing this little device was for so many users, I would have gone in a completely different direction and focused on the sensor implementation rather than dealing with the data.
        Here’s are my recommendations:
    1)  If all you’re doing is looking at acceleration data, don’t recalibrate at all.  See this quick-start guide.  https://ae-bst.resource.bosch.com/media/_tech/media/application_notes/BST-BNO055-AN007-00_Quick_Start_Guide.pdf
    The accelerometer should be factory calibrated.  Calibration is necessary for the magnetometer and the gyroscope (the gyro will drift relentlessly and requires the magnetometer data to be useful)
    2)  Get an I2C EEPROM and use it to store your calibration data.  Park your car and turn off the engine, go through all of the calibration “hocus-pocus” with the BNO055 where it will be mounted in your car.  Then read the BNO055 calibration registers and write them to the I2C EEPROM.  Anytime you power-on the BNO055 from that point forward, you should be able to simply read the data from the EEPROM and write it to the BNO055.
    3)  Don’t use Fusion mode if all you’re trying to do is get acceleration data.  If I remember correctly, the fusion modes force the continuous calibration.  You just need acceleration—so get a non-fusion mode running that provides acceleration.
    4)  You cannot ignore vehicle and road pitch.  The acceleration due to your car and the acceleration due to gravity are identical to an accelerometer.  While I wouldn’t expect this to be too significant, it will affect your results.  You should be able to deal with this in programming though (For example, if the sensor is perfectly level and the acceleration of the car is only in the x direction, any readings in the z directions would indicate a pitching sensor, and a reading in the y direction would indicate a yaw)

    If you could, please create a forum post for further questions and ping me so I can help out there.  It’s very difficult to deal with questions inside the limitations of a comment box.
    Best,
    Mark