One day, looking for cheap sensors on ebay, I found this interesting board which contained everything I was looking for. It basically consists of a 3-axis accelerometer (ADXL345), a 3-axis magnetometer (HMC5883L), a 3
-axis gyroscope (L3G4200D) and a barometric pressure sensor (BMP085). My plan is to build an Inertial Measurement Unit (IMU) (or maybe I should call it Attitude and heading reference system (AHRS)) and in the process learn how to interact and interpret the information all of this sensors provide. The fact is I have some experience using IMUs since I used one on my master thesis and another one on the Avora AUV, but the fact is they come preprogrammed and there is not much point in working with the raw sensor data unless you want to improve the measurement or give it another use.
For this project I am also using an Arduino Duemilanove, for that reason I wanted to call it ArduIMU, but there is already another project with the same name, so I will have to find another name (suggestions would be appreciate
d). Connecting the sensor board to the Arduino is pretty straightforward, every sensor has an I²C interface so you can access each of them using the Arduino Wire Library. The drawing was done using fritzing, on which I created the corresponding custom part for this board, although I did something wrong and it does not conform to the fritzing graphic standards.
This will be the first of a series of posts I plan to write about this project, since there are several steps I need to take in order to fully understand each sensor and several more to combine them in order to improve accuracy. In this post I want to talk about the accelerometer and how to obtain the roll and pitch angles from it, which is a process that can also be called tilt sensing.
Accelerometers are devices that are capable of measuring the acceleration they experience relative to free-fall, the same acceleration living beings feel. As a consequence, accelerometers are incapable of measuring the acceleration of gravity, but can be used to measure the upwards acceleration that counters gravity when at rest. This acceleration is measured as on the z-axis, when both pitch and roll angles are zero, but when the sensor is tilted either the x-axis or the y-axis experiences a component of the upward acceleration, whose magnitude depends on the tilt angle.
Pitch & Roll estimation
Obtaining the pitch and roll angles is then a matter of being able to read the accelerometer, convert these readings to the g unit (1g = 9.8 m/s²), and apply the corresponding equations. The process of obtaining and converting the accelerometer readings depends on the accelerometer you are using, in my case, the ADXL345 in its basic configuration, provides 10-bit resolution for ±2g, but has several other ranges (±2g, ±4g, ±8g, ±16g) and resolutions (from 10 to 13 bits depending on the range) . Generalizing, the formula used to calculate the acceleration from the accelerometer readings is:
Once we have the correct acceleration components, we can proceed to calculate the different angles using the following equations:
For more information about where these equations come from, you can read the documentation I include at the end of this post. As you can see, the denominator of the pitch equation is defined to be always positive, so the equation itself only provides range, which is exactly what is expected for the pitch angle. In contrast, the roll equation provides
range. It is important to take into account that when the pitch angle is 90º, the surge axis (roll) is directly aligned with the gravity vector, thus we cannot measure the roll angle anymore, this is what is called Gimbal Lock.
Also, be aware that the roll equation is undefined when both and
are equal to zero, and that for each possible value of the calculation done inside the arctan function there are two valid solutions, not only on the roll but also on the pitch equation. These problems can be easily solved in code by using the function atan2, which eliminates the angle calculation ambiguity by taking into account the quadrant.
Removing short-term fluctuations using a Low-Pass filter
At this point we already have a fully functional pitch & roll estimation system, but if we experiment with it we will discover that the readings fluctuate quite a bit and this may be very annoying for some applications. Removing these short-term fluctuations can be achieved by means of what is called a Low-Pass filter. This type of filter attenuates the higher frequencies of the signal, thus providing a smoother reading. The Low-Pass filter is easily implemented by using the following equation:
Where is our filtered signal,
the previous filtered signal,
the accelerometer reading and
the smoothing factor. It probably may seem obvious, but filtering should be done to the accelerometer readings before calculating the angles, instead of to the angles themselves. Regarding the smoothing factor, the lower we set it, the more it will take for the angle to stabilize, so we should not set it too low because then we could lose real-time behaviour. With this I mean that the reading will not correspond to the real angle until it stabilizes, and this could take some time.
The source code & the ADXL345 library
I developed a small library to interface with the accelerometer, even though at the moment I have only implemented the basic functionality, I plan on supporting all of the device features. You can find it in my github account, where you can also find the processing code I used for the video example below. Thanks to the library, the code is pretty straightforward. It just reads the sensor accelerations which are already converted into gs by the library, applies the Low-Pass filter and then uses the roll and pitch equations to calculate the angles.
#include <Wire.h>
#include <ADXL345.h>
const float alpha = 0.5;
double fXg = 0;
double fYg = 0;
double fZg = 0;
ADXL345 acc;
void setup()
{
acc.begin();
Serial.begin(9600);
delay(100);
}
void loop()
{
double pitch, roll, Xg, Yg, Zg;
acc.read(&Xg, &Yg, &Zg);
//Low Pass Filter
fXg = Xg * alpha + (fXg * (1.0 - alpha));
fYg = Yg * alpha + (fYg * (1.0 - alpha));
fZg = Zg * alpha + (fZg * (1.0 - alpha));
//Roll & Pitch Equations
roll = (atan2(-fYg, fZg)*180.0)/M_PI;
pitch = (atan2(fXg, sqrt(fYg*fYg + fZg*fZg))*180.0)/M_PI;
Serial.print(pitch);
Serial.print(":");
Serial.println(roll);
delay(10);
}
The result
For a more interactive visualization of the data, I also developed an example using processing, which consists on a rotating 3D cube. You can see the results in the following video.
In the next post about my Arduino IMU, I will talk about how gyroscopes work and how to interpret the information they provide.
- Source | ADXL345-Accelerometer Arduino Library & Processing
- Documentation | AN3461 – Tilt Sensing Using Linear Accelerometers
- Fritzing Part | GY-80


Reblogged this on Gigable – Tech Blog.
Thanks. I may need to use this technique some time.
Pingback: Tutorial explains the concepts behind an IMU - Hack a Day
Reblogged this on Kris Unnikannan and commented:
IMU
Very clear presentation! Just a comment that there is a noticeable delay between you moving the accelerometer and the cube image moving. This could significantly detract from the agility of a robot or game player using this system. Considering that the mechanics processing required is negligible, this leaves the sensor latency, smoothing filter and graphics processor as possible sources of delay. Could this lag be reduced by assuming continuity using something like Taylor series prediction?
I would have to look into it, but it probably can be done if you assume continuity. For most applications I can think of, it wouldn’t be very useful though.
How about calling it ” ArduIMU “
Thank you for your suggestion, although that name is already used in a similar project.
hey buddy.. here’s my contribution, how about calling it imuino, you could use the emu bird as a logo or am I going too far with it?
I like the name, thanks!
But I’m not sure about the bird…
hahaha.. I understand!!!
Hi , i have the exact same sensor (you can buy it for 20bucks on dx.com) , but i didnt start to work on it yet , but your tutorial will be really useful, thank you .
i have a question thou ,
can you get SWAY SURGE and HEAVE “like” data , by subtracting the angle from the gyro to data of the accelerometer , and use the result to get translation (or more like the position relative to the starting point), with doing something like x+=x; y+=y; z+=z; (in the loop) with the result ?
? (not sure if i am clear , i am a beginner).
you could use something with DOF in your lib name (Degree Of Freedom) .
Cheers
Thanks! Well, the gyro doesn’t really give you an angle but an angular rate. Giving that you don’t have translational speed, nor is it calculated anywhere, you can’t really measure translation. What you are asking falls more within the grounds of an Inertial Navigation System (INS), and in itself is very a complicated problem, but an inaccurate approximation could be done by integrating over time the acceleration.
i am getting confused , (it is quite out of my league but it is so fascinating!)
the accelerometer gives the acceleration (relative to gravity) (if not translating , gives roll and pitch)
the gyro gives the angular rate (=angular velocity=speed of rotation ; different from the acceleration of the rotation ?) (if integrated gives the orientation ?)
but then the magnetometer (understand compass) gives the orientation ,right ?
so all the youtube videos of people doing the Euler thing (orientation tracking) with 6DOF sensor , are basically doing the work of the magnetometer ?
if i want to do the integration over time (extract translation and find position) (solving the shifting with a regular manual reset/recalibration) , i would need to remove the pitch yaw roll from the accelerometer data resulting only in the translation acceleration , right ?
also this is relevant http://www.youtube.com/watch?v=6ijArKE8vKU
do you want we continue this “talk” on a forum ? i don t want to “spam” your comment space.
First of all, the accelerometer gives yo the acceleration relative to free-fall, so can actually extract a “gravity” vector from it when at rest, that may have a component on the x, y and z axis. Since the gravity vector es pointing up because it’s not really gravity but the acceleration that counters it, you can only extract tilt from it, i.e. pitch and roll.
The gyroscope gives you the angular rate, which I believe it’s equivalent to angular velocity, certainly not to acceleration. So if you integrate over time you can obtain the orientation, but not quite, it’s something I’ll talk on the next post about the Arduino IMU.
Magnetometers measure magnetic field in each axis, so you can “sense” the earths magnetic field and calculate the orientation relative to the magnetic north (yaw), but there are techniques to calculate pitch and roll also. I will talk about it in future posts.
I don’t really know about the videos you’re talking about, but calculating precise orientation usually requires a combination of sensors.
Regarding the translation measurement, you can extract the gravity vector from the accelerometer readings, so all you have left is the acceleration you need for calculating the translation. But you must remember that integrating over time accumulates a noticeable error and, in this case, you must integrate twice (acceleration->speed, speed->translation).
Pingback: UAV / Quadcopter roundup | The Circuit Farm
Pingback: Wired In Mag » This could be pretty useful for FIRST ROBOTICS
Pingback: Sete Leituras para o domingo (V) | Zeletron
There is a gyro on that board too, mix it with the accelerometer. Combine the outputs with a complementary filter first. Fool with the crossover points while graphing the outputs, adjust until you get an acceptable error from the fastest response you want to perform in. After that, you can start playing with extended kalman filters, they do a great job of mixing the best way possible, but they might run a little slow.
Nice job.
Hi everybody, could you please tell me about formula of yaw estimation ?
I mean that, there is written that to get roll from adxl345 is arctan(-Gx/Gz), so what about yaw ?
I hope understand later, thanks.
There is no way to extract yaw from an accelerometer.
Hi, i have a problem with my sensor, it seems that it only shows one value for pitch and for roll..
This is my output in the Arduino Serial
-34.09:135.67
I only get to print something when SDA and SCL is disconnected, when I connect the wires, the serial stops.
Any idea why? Is my gyro damaged?
I am using an Arduino Mega
any idea why? anyone?
Well, if you could tell us more about what you are doing and using and how it’s all connected…
I am using the library that you posted here. All I want is to make it work and display the pitch and roll.. it is connected to 5V-GND and the SDA and SCL to pins 20/21 in the Arduino MEGA
Nice post! Really liked it! Helped me a lot. Congrats!
Just one thing: isnt the Low-Pass filter equation with a sign error? Shouldnt it be alpha*x + (1-alpha)*y ?
Hi found this very interesting I’m going to convert this to python and give it a go in the next couple of days it actually looks pretty simple. Any chance of getting the next part up on the gyro?
Yes, I will! I’ve just had two pretty busy months and haven’t had much time. Thanks for following and please be patient.
cool thanks!
Thought i’d post a quick message I implemented your code in python on my Raspberry Pi and am seeing very good results. I do get some odd noise on occasion which will give me a 2g spike (in a +-4g range) on the Z and X axis but never Y! Not sure why. I’m currently writing out to a txt file and then importing the results into excel for graphing. Now i’m happy my code is working ok i’m going to start creating a real time GUI. Not bad for my first bit of programming.
I’m happy it worked, thanks for writing! I hope in less than a month I’ll be able to write the next step on this project. I’m actually two/three steps ahead, but I don’t find the time!
Great job and a great post. Did you ever post your source code for the cube visualization? I’m very interested in doing something similar, so any guidance would be appreciated.
Thanks, you can find a link to the source code at the end of the post.
This is the perfect site for anyone who would like to understand
this topic. You understand so much its almost tough to argue with you (not that I actually
will need to…HaHa). You definitely put a brand new spin on a
topic which has been written about for years. Wonderful stuff, just great!
You have observed very interesting points !
ps nice site. “Formal education will make you a living self-education will make you a fortune.” by Jim Rohn.
Hi, Nice project, I have the exact same sensor and want to start playing with it.
I have been to your github and downloaded the zip, I renamed the arduino folder as suggested, opened it in arduino , and it wont compile,
I get the following message :
“pitch_roll:20: error: ‘ADXL345′ does not name a type
pitch_roll.cpp: In function ‘void setup()’:
pitch_roll:24: error: ‘acc’ was not declared in this scope
pitch_roll.cpp: In function ‘void loop()’:
pitch_roll:33: error: ‘acc’ was not declared in this scope
”
do you know what it going wrong ? from my knolwege of arduino the ACC function is not being recognised, but I have the folder correctly named with all files inside it and in the library folder,
thanks for any help , I look forward to playing with this
You need to put the renamed arduino directory in your workspace under another directory called libraries. If this directory doesn’t exist you should create it. Then open the example and try again. Cheers.