Introduction
This article is a continuation of my IMU Guide, covering additional orientation kinematics topics. I will go through some theory first and then I will present a practical example with code build around an Arduino and a 6DOF IMU sensor (acc_gyro_6dof). The scope of this experiment is to create an algorithm for fusing gyroscope and accelerometer data in order to create an estimation of the device orientation in space. Such an algorithm was already presented in part 3 of my “IMU Guide” and a practical Arduino experiment with code was presented in the “Using a 5DOF IMU” article and was nicknamed “Simplified Kalman Filter”, providing a simple alternative to the well known Kalman Filter algorithm. In this article we’ll use another approach utilizing the DCM (Direction Cosine Matrix). For the reader that is unfamiliar with MEMS sensors it is recommended to read Part 1 and 2 of the IMU Guide article. Also for following the experiments presented in this text it is recommended to acquire an Arduino board and an acc_gyro_6dof sensor.
Prerequisites
No really advanced math is necessary. Find a good book on matrix operations, that’s all you might need above school math course. If you would like to refresh your knowledge below are some quick articles:
Cartesian Coordinate System – http://en.wikipedia.org/wiki/Cartesian_coordinate_system
Rotation – http://en.wikipedia.org/wiki/Rotation_%28mathematics%29
Vector scalar product – http://en.wikipedia.org/wiki/Dot_product
Vector cross product – http://en.wikipedia.org/wiki/Cross_product
Matrix Multiplication – http://en.wikipedia.org/wiki/Matrix_multiplication
Block Matrix – http://en.wikipedia.org/wiki/Block_matrix
Transpose Matrix – http://en.wikipedia.org/wiki/Transpose
Triple Product – http://en.wikipedia.org/wiki/Triple_product
Notations
Vectors are marked in bold text - so for example “v” is a vector and “v” is a scalar (if you can’t distinguish the two there’s problem with the text formatting wherever you’re reading this).
Part 1. The DCM Matrix
Generally speaking orientation kinematics deals with calculating the relative orientation of a body relative to a global coordinate system. It is useful to attach a coordinate system to our body frame and call it Oxyz, and another one to our global frame and call it OXYZ. Both the global and the body frames have the same fixed origin O (see Fig. 1). Let’s also define i, j, k to be unity vectors co-directional with the body frame’s x, y, and z axes – in other words they are versors of Oxyz and let I, J, K be the versors of global frame OXYZ.
Figure 1
Thus, by definition, expressed in terms of global coordinates vectors I, J, K can be written as:
IG = {1,0,0} T, JG={0,1,0} T , KG = {0,0,1} T
Note: we use {…} T notation to denote a column vector, in other words a column vector is a translated row vector. The orientation of vectors (row/column) will become relevant once we start multiplying them by a matrix later on in this text.
And similarly, in terms of body coordinates vectors i, j, k can be written as:
iB = {1,0,0} T, jB={0,1,0} T , kB = {0,0,1} T
Now let’s see if we can write vectors i, j, k in terms of global coordinates. Let’s take vector i as an example and write its global coordinates:
iG = {ixG , iyG , izG} T
Again, by example let’s analyze the X coordinate ixG, it’s calculated as the length of projection of the i vector onto the global X axis.
ixG = |i| cos(X,i) = cos(I,i)
Where |i| is the norm (length) of the i unity vector and cos(I,i) is the cosine of the angle formed by the vectors I and i. Using the fact that |I| = 1 and |i| = 1 (they are unit vectors by definition). We can write:
ixG = cos(I,i) = |I||i| cos(I,i) = I.i
Where I.i. is the scalar (dot) product of vectors I and i. For the purpose of calculating scalar product I.i it doesn’t matter in which coordinate system these vectors are measured as long as they are both expressed in the same system, since a rotation does not modify the angle between vectors so: I.i = IB.iB = IG.iG = cos(IB.iB) = cos(IG.iG) , so for simplicity we’ll skip the superscript in scalar products I.i , J.j , K.k and in cosines cos(I,i), cos(J,j), cos(K,k).
Similarly we can show that:
iyG = J.i , izG=K.i , so now we can write vector i in terms of global coordinate system as:
iG= { I.i, J.i, K.i}T
Furthermore, similarly it can be shown that jG= { I.j, J.j, K.j} T , kG= { I.k, J.k, K.k} T.
We now have a complete set of global coordinates for our body’s versors i, j, k and we can organize these values in a convenient matrix form:
This matrix is called Direction Cosine Matrix for now obvious reasons – it consists of cosines of angles of all possible combinations of body and global versors.
The task of expressing the global frame versors IG, JG, KG in body frame coordinates is symmetrical in nature and can be achieved by simply swapping the notations I, J, K with i, j, k, the results being:
IB= { I.i, I.j, I.k}T , JB= { J.i, J.j, J.k}T , KB= { K.i, K.j, K.k}T
and organized in a matrix form:
It is now easy to notice that DCMB = (DCMG)T or DCMG = (DCMB)T , in other words the two matrices are translates of each other, we’ll use this important property later on.
Also notice that DCMB. DCMG = (DCMG)T .DCMG = DCMB. (DCMB)T = I3 , where I3 is the 3×3 identity matrix. In other words the DCM matrices are orthogonal.
This can be proven by simply expanding the matrix multiplication in block matrix form:
To prove this we use such properties as for example: iGT. iG = | iG|| iG|cos(0) = 1 and iGT. jG = 0 because (i and j are orthogonal) and so forth.
The DCM matrix (also often called the rotation matrix) has a great importance in orientation kinematics since it defines the rotation of one frame relative to another. It can also be used to determine the global coordinates of an arbitrary vector if we know its coordinates in the body frame (and vice versa).
Let’s consider such a vector with body coordinates:
rB= { rxB, ryB, rzB} T and let’s try to determine its coordinates in the global frame, by using a known rotation matrix DCMG.
We start by doing following notation:
rG = { rxG , ryG , rzG } T.
Now let’s tackle the first coordinate rxG:
rxG = | rG| cos(IG,rG) , because rxG is the projection of rG onto X axis that is co-directional with IG.
Next let’s note that by definition a rotation is such a transformation that does not change the scale of a vector and does not change the angle between two vectors that are subject to the same rotation, so if we express some vectors in a different rotated coordinate system the norm and angle between vectors will not change:
| rG| = | rB| , | IG| = | IB| = 1 and cos(IG,rG) = cos(IB,rB), so we can use this property to write
rxG = | rG| cos(IG,rG) = | IB || rB| cos(IB,rB) = IB. rB = IB. { rxB, ryB, rzB} T , by using one the two definition of the scalar product.
Now recall that IB= { I.i, I.j, I.k}T and by using the other definition of scalar product:
rxG = IB. rB = { I.i, I.j, I.k}T . { rxB, ryB, rzB} T = rxB I.i + ryB I.j + rzB I.k
In same fashion it can be shown that:
ryG = rxB J.i + ryB J.j + rzB J.k
rzG = rxB K.i + ryB K.j + rzB K.k
Finally let’s write this in a more compact matrix form:
Thus the DCM matrix can be used to covert an arbitrary vector rB expressed in one coordinate system B, to a rotated coordinate system G.
We can use similar logic to prove the reverse process:
Or we can arrive at the same conclusion by multiplying both parts in (Eq. 1.4) by DCMB which equals to DCMGT, and using the property that DCMGT.DCMG = I3 , see (Eq. 1.3):
DCMB rG = DCMB DCMG rB = DCMGT DCMG rB = I3 rB = rB
Part 2. Angular Velocity
So far we have a way to characterize the orientation of one frame relative to another rotated frame, it is the DCM matrix and it allows us to easily convert the global and body coordinates back and forth using (Eq. 1.4) and (Eq. 1.5). In this section we’ll analyze the rotation as a function of time that will help us establish the rules of updating the DCM matrix based on a characteristic called angular velocity. Let’s consider an arbitrary rotating vector r and define it’s coordinates at time t to be r(t). Now let’s consider a small time interval dt and make the following notations: r = r (t) , r’= r (t+dt) and dr = r’ – r:
Figure 2
Let’s say that during a very small time interval dt → 0 the vector r has rotated about an axis co-directional with a unity vector u by an angle dθ and ended up in the position r’. Since u is our axis of rotation it is perpendicular to the plane in which the rotation took place (the plane formed by r and r’) so u is orthogonal to both r and r’. There are two unity vectors that are orthogonal to the plane formed by r and r’, they are shown on the picture as u and u’ since we’re still defining things we’ll choose the one that is co-directional with the cross product r x r’, following the rule of right-handed coordinate system. Thus because u is a unity vector |u| = 1 and is co-directional with r x r’ we can deduct it as follows:
u = (r x r’) / |r x r’| = (r x r’) / (|r|| r’|sin(dθ)) = (r x r’) / (|r|2 sin(dθ)) (Eq. 2.1)
Since a rotation does not alter the length of a vector we used the property that| r’| = |r|.
The linear velocity of the vector r can be defined as the vector:
v = dr / dt = ( r’ – r) / dt (Eq. 2.2)
Please note that since our dt approaches 0 so does dθ → 0, hence the angle between vectors r and dr (let’s call it α) can be found from the isosceles triangle contoured by r , r’ and dr:
α = (π – dθ) / 2 and because dθ → 0 , then α → π/2
What this tells us is that r is perpendicular to dr when dt → 0 and hence r is perpendicular to v since v and dr are co-directional from (Eq. 2.2):
v ⊥ r (Eq. 2.21)
We are now ready to define the angular velocity vector. Ideally such a vector should define the rate of change of the angle θ and the axis of the rotation, so we define it as follows:
w = (dθ/dt ) u (Eq. 2.3)
Indeed the norm of the w is |w| = dθ/dt and the direction of w coincides with the axis of rotation u. Let’s expand (Eq. 2.3) and try to establish a relationship with the linear velocity v:
Using (Eq. 2.3) and (Eq. 2.1):
w = (dθ/dt ) u = (dθ/dt ) (r x r’) / (|r|2 sin(dθ))
Now note that when dt → 0, so does dθ → 0 and hence for small dθ, sin(dθ) ≈ dθ , we end up with:
w = (r x r’) / (|r|2 dt) (Eq. 2.4)
Now because r’ = r + dr , dr/dt = v , r x r = 0 and using the distributive property of cross product over addition:
w = (r x (r + dr)) / (|r|2 dt) = (r x r + r x dr)) / (|r|2 dt) = r x (dr/dt) / |r|2
And finally:
w = r x v / |r|2 (Eq. 2.5)
This equation establishes a way to calculate angular velocity from a known linear velocity v.
We can easily prove the reverse equation that lets us deduct linear velocity from angular velocity:
v = w x r (Eq. 2.6)
This can be proven simply by expanding w from (Eq. 2.5) and using vector triple product rule (a x b) x c = (a.c)b – (b.c)a. Also we’ll use the fact that v and r are perpendicular (Eq. 2.21) and thus v.r = 0
w x r = (r x v / |r|2) x r = (r x v) x r / |r|2 = ((r.r) v + (v.r)r) / |r|2 = ( |r|2 v + 0) |r|2 = v
So we just proved that (Eq. 2.6) is true. Just to check (Eq. 2.6) intuitively – from Figure 2 indeed v has the direction of w x r using the right hand rule and indeed v ⊥ r and v ⊥ w because it is in the same plane with r and r’.
Part 3. Gyroscopes and angular velocity vector
A 3-axis MEMS gyroscope is a device that senses rotation about 3 axes attached to the device itself (body frame). If we adopt the device’s coordinate system (body’s frame), and analyze some vectors attached to the earth (global frame), for example vector K pointing to the zenith or vector I pointing North – then it would appear to an observer inside the device that these vector rotate about the device center. Let wx , wy , wz be the outputs of a gyroscope expressed in rad/s – the measured rotation about axes x, y , z respectively. Converting from the raw output of the gyroscope to physical values is discussed for example here: http://www.starlino.com/imu_guide.html . If we query the gyroscope at regular, small time intervals dt, then what gyroscope output tells us is that during this time interval the earth rotated about gyroscope’s x axis by an angle of dθx = wxdt, about y axis by an angle of dθy = wydt and about z axis by an angle of dθz = wzdt. These rotations can be characterized by the angular velocity vectors: wx = wx i = {wx , 0 , 0 }T , wy = wy j = { 0 , wy , 0 }T , wz = wz k = { 0 , 0, wz }T , where i,j,k are versors of the local coordinate frame (they are co-directional with body’s axes x,y,z respectively). Each of these three rotations will cause a linear displacement which can be expressed by using (Eq. 2.6):
dr1 = dt v1 = dt (wx x r) ; dr2 = dt v2 = dt (wy x r) ; dr3 = dt v3 = dt (wz x r) .
The combined effect of these three displacements will be:
dr = dr1 + dr2 + dr3 = dt (wx x r + wy x r + wz x r) = dt (wx + wy + wz) x r (cross product is distributive over addition)
Thus the equivalent linear velocity resulting from these 3 transformations can be expressed as:
v = dr/dt = (wx + wy + wz) x r = w x r , where we introduce w = wx + wy + wz = {wx , wy , wz }
Which looks exactly like (Eq. 2.6) and suggests that the combination of three small rotations about axes x,y,z characterized by angular rotation vectors wx , wy , wz is equivalent to one small rotation characterized by angular rotation vector w = wx + wy + wz = {wx , wy , wz }. Please note that we’re stressing out that these are small rotations, since in general when you combine large rotations the order in which rotations are performed become important and you cannot simply sum them up. Our main assumption that let us go from a linear displacement to a rotation by using (Eq. 2.6) was that dt is really small, and thus the rotations dθ and linear displacement dr are small as well. In practice this means that the larger the dt interval between gyro queries the larger will be our accumulated error, we’ll deal with this error later on. Now, since wx , wy , wz are the output of the gyroscope, then we arrive at the conclusion that in fact a 3 axis gyroscope measures the instantaneous angular velocity of the world rotating about the device’s center.
Part 4. DCM complimentary filter algorithm using 6DOF or 9DOF IMU sensors
In the context of this text a 6DOF device is an IMU device consisting of a 3 axis gyroscope and a 3 axis accelerometer. A 9DOF device is an IMU device of a 3 axis gyroscope, a 3 axis accelerometer and a 3 axis magnetometer. Let’s attach a global right-handed coordinate system to the Earth’s frame such that the I versor points North, K versor points to the Zenith and thus, with these two versors fixed, the J versor will be constrained to point West.
Figure 3
Also let’s consider the body coordinate system to be attached to our IMU device (acc_gyro used as an example),
Figure 4
We already established the fact that gyroscopes can measure the angular velocity vector. Let’s see how accelerometer and magnetometer measurements will fall into our model.
Accelerometers are devices that can sense gravitation. Gravitation vector is pointing towards the center of the earth and is opposite to the vector pointing to Zenith KB. If the 3 axis accelerometer output is A = {Ax , Ay , Az } and we assume that there are no external accelerations or we have corrected them then we can estimate that KB = -A. (See this IMU Guide for more clarifications http://www.starlino.com/imu_guide.html).
Magnetometers are devices that are really similar to accelerometers, except that instead of gravitation they can sense the Earth’s magnetic North. Just like accelerometers they are not perfect and often need corrections and initial calibration. If the corrected 3-axis magnetometer output is M = {Mx , My , Mz }, then according to our model IB is pointing North , thus IB = M.
Knowing IB and KB allows us calculate JB = KB x IB.
Thus an accelerometer and a magnetometer alone can give us the DCM matrix , expressed either as DCMB or DCMG
DCMG = DCMBT = [IB, JB, KB]T
The DCM matrix can be used to convert any vector from body’s(devices) coordinate system to the global coordinate system. Thus for example if we know that the nose of the plane has some fixed coordinates expressed in body’s coordinate system as rB = {1,0,0}, the we can find where the device is heading in other words the coordinates of the nose in global coordinate systems using (Eq. 1.4):
rG = DCMG rB
So far you’re asking yourself if an accelerometer and a magnetometer gives us the DCM matrix at any point in time, why do we need the gyroscope ? The gyroscope is actually a more precise device than the accelerometer and magnetomer are , it is used to “fine-tune” the DCM matrix returned by the accelerometer and magnetometer.
Gyroscopes have no sense of absolute orientation of the device , i.e. they don’t know where north is and where zenith is (things that we can find out using the accelerometer and magnetometer), instead if we know the orientation of the device at time t, expressed as a DCM matrix DCM(t) , we can find a more precise orientation DCM(t+dt) using the gyroscope , then the one estimated directly from the accelerometer and magnetometer direct readings which are subject to a lot of noise in form of external (non-gravitational) inertial forces (i.e. acceleration) or magnetically forces that are not caused by the earth’s magnetic field.
These facts call for an algorithm that would combine the readings from all three devices (accelerometer, magnetometer and gyroscope) in order to create our best guess or estimate regarding the device orientation in space (or space’s orientation in device’s coordinate systems), the two orientations are related since they are simply expressed using two DCM matrices that are transpose of one another (DCMG = DCMBT ).
We’ll now go ahead and introduce such an algorithm.
We’ll work with the DCM matrix that consists of the versors of the global (earth’s) coordinate system aligned on each row:
If we read the rows of DCMG we get the vectors IB, JB, KB. We’ll work mostly with vectors KB (that can be directly estimated by accelerometer) and vector IB (that can be directly estimated by the magnetometer). The vector JB is simply calculated as JB = KB x IB , since it’s orthogonal to the other two vectors (remember versors are unity vectors with same direction as coordinate axes).
Let’s say we know the zenith vector expressed in body frame coordinates at time t0 and we note it as KB0. Also let’s say we measured our gyro output and we have determined that our angular velocity is w = {wx , wy , wz }. Using our gyro we want to know the position of our zenith vector after a small period of time dt has passed we’ll note it as KB1G . And we find it using (Eq. 2.6):
KB1G ≈ KB0 + dt v = KB0 + dt (wg x KB0) = KB0 + ( dθg x KB0)
Where we noted dθg = dt wg. Because wg is angular velocity as measured by the gyroscope. We’ll call dθg angular displacement. In other words it tells us by what small angle (given for all 3 axis in form of a vector) has the orientation of a vector KB changed during this small period of time dt.
Obviously, another way to estimate KB is by making another reading from accelerometer so we can get a reading that we note as KB1A .
In practice the values KB1G will be different from from KB1A. One was estimated using our gyroscope and the other was estimated using our accelerometer.
Now it turns out we can go the reverse way and estimate the angular velocity wa or angular displacement dθa = dt wa , from the new accelerometer reading KB1A , we’ll use (Eq. 2.5):
wa = KB0 x va / | KB0|2
Now va = (KB1A - KB0) / dt , and is basically the linear velocity of the vector KB0. And | KB0|2 = 1 , since KB0 is a unity vector. So we can calculate:
dθa = dt wa = KB0 x (KB1A - KB0)
The idea of calculating a new estimate KB1 that combines both KB1A and KB1G is to first estimate dθ as a weighted average of dθa and dθg :
dθ = (sa dθa + sg dθg) / (sa + sg), we’ll discuss about the weights later on , but shortly they are determined and tuned experimentally in order to achieve a desired response rate and noise rejection.
And then KB1 is calculated similar to how we calculated KB1G:
KB1 ≈ KB0 + ( dθ x KB0)
Why we went all the way to calculate dθ and did not apply the weighted average formula directly to KB1A and KB1G ? Because dθ can be used to calculate the other elements of our DCM matrix in the same way:
IB1 ≈ IB0 + ( dθ x IB0)
JB1 ≈ JB0 + ( dθ x JB0)
The idea is that all three versors IB, JB, KB are attached to each other and will follow the same angular displacement dθ during our small interval dt. So in a nutshell this is the algorithm that allows us to calculate the DCM1 matrix at time t1 from our previous estimated DCM0 matrix at time t0. It is applied recursively at regular small time intervals dt and gives us an updated DCM matrix at any point in time. The matrix will not drift too much because it is fixed to the absolute position dictated by the accelerometer and will not be too noisy from external accelerations because we also use the gyroscope data to update it.
So far we didn’t mention a word about our magnetometer. One reasons being that it is not available on all IMU units (6DOF) and we can go away without using it, but our resulting orientation will then have a drifting heading (i.e. it will not show if we’re heading north, south, west or east), or we can introduce a virtual magnetometer that is always pointing North, to introduce stability in our model. This situation is demonstrated in the accompanying source code that used a 6DOF IMU.
Now we’ll show how to integrate magnetometer readings into our algorithm. As it turns out it is really simple since magnetometer is really similar to accelerometer (they even use similar calibration algorithms), the only difference being that instead of estimating the Zenith vector KB vector it estimates the vector pointing North IB. Following the same logic as we did for our accelerometer we can determine the angular displacement according to the updated magnetometer reading as being:
dθm = dt wm = IB0 x (IB1M - IB0)
Now let’s incorporate it into our weighted average:
dθ = (sa dθa + sg dθg + sm dθm) / (sa + sg + sm)
From here we go the same path to calculate the updated DCM1
IB1 ≈ IB0 + ( dθ x IB0) , KB1 ≈ KB0 + ( dθ x KB0) and JB1 ≈ JB0 + ( dθ x JB0),
In practice we’ll calculate JB1 = KB1 x IB1, after correcting KB1 and IB1 to be perpendicular unity vectors again , note that all our logic is approximated and dependent on dt being small, the larger the dt the larger the error we’ll accumulate.
So if vectors IB0, JB0, KB0 form a valid DCM matrix , in other words they are orthogonal to each other and are unity vectors, then we can’t say the same about IB1, JB1, KB1 , the formulas used for calculating them does not guarantee the orthogonality or length of the vector to be preserved , however we will not get a big error if dt is small, all we need to do is to correct them after each iteration.
First let’s see how we can ensure that two vectors are orthogonal again. Let’s consider two unity vectors a and b that are “almost orthogonal” in other words the angle between these two vectors is close to 90°, but not exactly 90°. We’re looking to find a vector b’ that is orthogonal to a and that is in the same plane formed by the vectors a and b. Such a vector is easy to find as shown in Figure 5. First we find vector c = a x b that by the rules of cross product is orthogonal to both a and b and thus is perpendicular to the plane formed by a and b. Next the vector b’ = c x a is calculated as the cross product of c and a. From the definition of cross product b’ is orthogonal to a and because it is also orthogonal to c – it end up in the plane orthogonal to c , which is the plane formed by a and b. Thus b’ is the corrected vector we’re seeking that is orthogonal to a and belongs to the plane formed by a and b.
![]()
Figure 5
We can extend the equation using the triple product rule and the fact that a.a = |a| = 1:
b’ = c x a = (a x b) x a = -a (a.b) + b(a.a) = b – a (a.b) = b + d , where d = – a (a.b) (Scenario 1, a is fixed b is corrected)
You can reflect a little bit on the results … So we obtain corrected vector b’ from vector b by adding a “correction” vector d = – a (a.b). Notice that d is parallel to a. Its direction is dependent upon the angle between a and b, for example in Figure 5 a.b = cos (a,b) > 0 , because angle between a and b is less than 90°thus d has opposite direction from a and a magnitutde of cos(a,b) = sin(b,b’).
In the scenario above we considered that vector a is fixed and we found a corrected vector b’ that is orthogonal to a. We can consider the symmetric problem – we fix b and find the corrected vector a’:
a’ = a – b (b.a) = a – b (a.b) = a + e, where e = - b (a.b) (Scenario 2, b is fixed a is corrected)
Finally in the third scenario we want both vectors to move towards their corrected state, we consider them both “equally wrong”, so intuitively we apply half correction to both vectors from scenario 1 and 2:
a’ = a – b (a.b) / 2 (Scenario 3, both a and b are corrected)
b’ = b – a (a.b) / 2
Figure 6
This is an relatively easy formula to calculate on a microprocessor since we can pre-compute Err = (a.b)/2 and then use it to correct both vectors:
a’ = a – Err * b
b’ = b – Err * a
Please note that we’re not proving that a’ and b’ are orthogonal in Scenario 3, but we presented the intuitive reasoning why the angle between a’ and b’ will get closer to 90°if we apply the above corrective transformations.
Now going back to our updated DCM matrix that consists of three vectors IB1, JB1, we apply the following corrective actions before reintroducing the DCM matrix into the next loop:
Err = ( IB1 . JB1 ) / 2
IB1’ = IB1 – Err * JB1
JB1’ = JB1 – Err * IB1
IB1’’ = Normalize[IB1’]
JB1’’ = Normalize[JB1’]
KB1’’ = IB1’’ x JB1’’
Where Normalize[a] = a / |a| , is the formula calculating the unit vector co-directional with a.
So finally our corrected DCM1 matrix can be recomposed from vectors IB1’’, JB1’’, KB1’’ that have been ortho-normalized (each vector constitutes a row of the updated and corrected DCM matrix).
We repeat the loop to find DCM2 , DCM3 , or in general DCM n , at any time interval n.
References
1. Theory of Applied Robotics: Kinematics, Dynamics, and Control (Reza N. Jazar)
2. Linear Algebra and Its Applications (David C. Lay)
3. Fundamentals of Matrix Computations (David S. Watkins)
4. Direction Cosine Matrix IMU: Theory (W Premerlani)
Additional Notes
For the implementation of the algorithm for now see my quadcopter project in particular releases 6/7 have a nice Processing program for visual display of the DCM matrix and a model plane. The entire code is on SVN repository:
http://code.google.com/p/picquadcontroller/source/browse/?r=7#svn%2Ftrunk
The code is in imu.h file:
http://code.google.com/p/picquadcontroller/source/browse/trunk/imu.h?r=7
A PDF Version of this article is available here
DCM Tutorial – An Introduction to Orientation Kinematics by Starlino (PDF, Rev 0.1 Draft)
Please mention and link to the source when using information in this article:
http://www.starlino.com/dcm_tutorial.html
Starlino Electronics // Spring , 2011



58 COMMENTS | Add Comment | RSS
Hi Starlino,
I’m trying to understand this. As per diydrones post…
The thing that I keep struggling with is why I don’t see a Euler rotation equation anywhere.
When you say:
“Please note that we’re stressing out that these are small rotations, since in general when you combine large rotations the order in which rotations are performed become important and you cannot simply sum them up.”
I just can’t work out why small rotations would make any difference. Could this hold true for a gyro only solution? Can you help me understand this?
Peter, really good question …
To understand why the order of rotations becomes more important with angle magnitude and less important for small angles try to perform following experiments. Pick an object like a book and choose the local X and Y axis attached to the object , for example X axis is along bottom side and Y axis is along left side.
Now being each experiment from a fixed start position.
1) Rotate the object roughly 5 degrees about X axis then , 5 degrees about Y axis remember end position.
2) Rotate the object roughly 5 degrees about Y axis then , 5 degrees about X axis remember end position.
Compare the end position on experiments 1) and 2) they will be roughly the same.
Now let’s see what happens with larger angles, by performing:
3) Rotate the object roughly 90 degrees about X axis then , 90 degrees about Y axis remember end position.
4) Rotate the object roughly 90 degrees about Y axis then , 90 degrees about X axis remember end position.
The end positions of 3) and 4) are obviously different, so order of rotation is important for larger angles.
Now what I am trying to explain “with small angles” is actually decomposition of angular velocity vector. And what I am trying to avoid is vector derivatives in order to make it simple for all folks to grasp it. However if you prefer, a more robust proof is given for example in [Jazar, Ex. 200, 201 pg 385-387, see Refences section of the article ] using vector analysis.
The problem arises form the fact that a 3 axis gyro tells us the angular velocity about each axis separately w1 about X, w2 about Y, w3 about Z, after each interval dt we don’t know in which order these rotations happened, but for small rotation we’re showing that we can consider these three rotations to be (roughly) equivalent to one rotation about a vector w= {w1,w2,w3} , with an angle of |w|. This proves to be convenient in updating the DCM matrix in one step, however theoretically one could apply 3 separate updates (again order is not important as long as we update really often and w1,w2,w3 are not large).
Yes I think you could use this algorithm with gyro only, just set the weight of magnetometer and accelerometer to 0 and reduce it to see what happens. You will basically skip the step where wG , wA, wM are combined by a weighted average and just use wG to update the DCM matrix.
[...] http://www.starlino.com/dcm_tutorial.html Share this:TwitterFacebookLike this:LikeBe the first to like this post. [...]
Thx a lot Starlino , you rock !!
hi,
Plz i need to calculate the Inertia matrix of the Quadcopter to simulate the Quad on Matlab
any help plz
[...] been working on stabilization code for the tricopter using direction cosine matrices but haven’t yet gotten too far because the DCM updates too slowly. I must be doing something [...]
I have a question
What is the best method
DCM
or
Kalman Filter (Acc+Gyro)
DCM is not really an algorithm for IMU fusion, I think you mean complimentary filter applied to DCM (direction cosine matrix). Complimentary filter + DCM matrix is easier to understand and tune-up in my opinion. You can also “upgrade” your complimentary filter with auto-adjusting weights to trigger even better results.
[...] The Starlino DCM Tutorial [...]
Hello Starlino,
Big thanks for this tutorial. I’ve been brought here because I’m developing an Android app that is trying to calculate best YAW (azimuth) angle possible. The Android SDK provide a method to get the OrientationMatrix but it’s really buggy. This is way I wanted to give a try to the DCM. My phone is 9DOF (3axes accel + gyro + magneto)
I tried to implement the code you provide in Java. I display the rotation using a cube in openGL. But I’m running into a some problem:
1. Sometimes but not always when I start the App the cube is flicking from 0 to 180 on the yaw and pitch angle (the roll seems OK..)
if a shake a bit the phone “sometimes” it stabilies !! and seemed to work really well “visualy” the cube behave exactly how I want (pitch, roll yaw)
TO debug I tried to print the Euler angle with
angle[YAW] = atan2(dcmMatrix[3], dcmMatrix[0]);
angle[PITCH] = -asin(dcmMatrix[6]);
angle[ROLL] = atan2(dcmMatrix[7], dcmMatrix[8]);
When the cube is stabilized and the phone still on the table (screen facing up) the values are
yaw: 0 pitch = 0 roll = 180 (it should be 0 no) ??
if a yaw the phone the printed yaw increase (OK) if I roll the phone.. the printed PITCH increase???? and if a pitch the phone the printed pitch seemed to be wrong :S
WHy is there that are the axes mixup ??
2. Now.. in your code the Imag vector is always pointing at the same direction because you don’t have magnetometer. But since i have, I put the magnetomer value on the Img vector
And now.. (well the problem of the flicking is still here I have to shake the phone I don’t know How and it stabilizes..) But now the cube is not reacting correctly “visualy”
When i YAW the phone the cube is rotating around XY (YAW) AND AT THE SAME TIME around XZ (PITH) ?? But when I roll the phone not problem! the cube roll
Why is this happening ?
TO test i’m check if the matrix is orthogonal (i^2 + j^2 + k^2) = 1 all do it on all the line and column
thanks
if I print out the first line of he DCM at each iteration I get that
-0.99600416 0.028452467 0.08465337
-0.99596983 0.02799713 0.085207015
-0.99591947 0.027649324 0.085906744
-0.9958669 0.027320543 0.08661838
-0.9958056 0.027040107 0.087407134
0.9956389 -0.026996411 -0.089299254
0.9955801 -0.02681771 -0.09000592
0.99550337 -0.026562588 -0.09092565
0.9954371 -0.026288053 -0.09172788
0.99537075 -0.026074352 -0.09250489
I have a signed problem that why it is flicking… that might come from the accelerometer
Sorry Starlino As you haven’t yet valided my comment I just post this on to say that the problem I ha when adding the magnetometer has been fixed.. (I just forgot to normalize the vector Imag.. !)
But the problem of the flicking is still here !
Humm hello again Starlino… I think I found out the flicking problem..
The problem is the orthonormalization !
When I do the dot product between the line I and J the error is reaaaaaly small (something like 0.00004)
So if a comment out this part
temporary_dot_I = DCM_I.scale(-err / 2);
DCM_J.add(temporary_dot_I);
temporary_dot_J = DCM_J.scale(-err / 2);
DCM_I.add(temporary_dot_J);
No flicking anymore !! And the cube seems to always be quite orthogonal (not deformed… ) if I a shake the phone really hard :)
So actually we don’t need to do this correction EVER TIME ? but maybe only off error > 0.5 or something ?
[...] [...]
Hi Starlino,
This is a very nice article. It explains the concepts of a DCM very well.
I wonder about one thing though. The North vector the magnetometer is pointing at is not perpendicular to the Zenith vector. It is pointing into the ground in a northerly direction. The angle with the XY plane, or surface of the earth, is the inclination of the earth magnetic field.
I myself am in the middle of incorperating the magnetometer into a 6DOF IMU so I am not really sure about how to cope with this. But I think you have to transform the compass vector to the world frame, then you can correct for the inclination to make the Vector perpendicular to the Zenith vector. The result is transformed back to the body frame. After that it can be used like you describe.
Aswin: Good question, let Z be the zenith UNIT vector (obtained from accelerometer) and M be the raw magnetometer reading UNIT vector that is not necessarily perpendicular to Z. To obtain true North perpendicular to Z and parallel to the ground use the following transformation.
First obtain a vector that is perpendicular to plain formed by Z and M, that happens to be W (West):
W = Z x M ( where “x” is the vector cross product), note order is important, use right-hand coordinate system rule.
Then obtain North (N) , as a vector perpendicular to bot Z and W simply get:
N = W x Z
Or in one formula
N = (Z x M) x Z , using triple product formula
N = (Z.Z) M – (M.Z)Z , where “.” is the scalar dot product , since Z is a unit vector this becomes
N = M – (M.Z) Z
The scalar -(M.Z) = -cos(M,Z)|M||Z| = -cos(M,Z) ( since M,Z unit vectors) is the correction term , you can visualize this as if it pulls the uncorrected vector M away from Z depending on the angle between M and Z.
Note that in particular if M is perpendicular to Z , then M.Z = 0 , so N = M as expected.
Finally you may want to normalize N to make sure it is a unit vector:
N’ = Normalize(N)
[...] – LIS331AL (datasheet) – analog 3-axis 2G accelerometer – LPR550AL (datasheet) – a dual-axis (Pitch and Roll), 500deg/second gyroscope – LY550ALH (datasheet) – a single axis (Yaw) gyroscope (this last device is not used in this tutorial but it becomes relevant when you move on to DCM Matrix implementation) [...]
You rocks Starlino!!
:-)
your writings help me very much . . Don’t know what to say, without you, i will not be able to finish my Bachelor degree Final Project.
bless you :’-)
May i ask you something?
How to convert your DCMg / DCMb to euler angles? (Pitch, Yaw, Roll)
I’am really confused with that problem. . .
Thx Starlino :-)
Alfiansyah, You’ll find DCM to Euler angles conversion in this book: http://astore.amazon.com/librarian06-20/detail/1441917497
page 21 , section 3.6.3 “Euler Angles”, it is not a one-to-one conversion so I would recommend reading the entire chapter, to be aware of potential pitfalls.http://www.starlino.com/wp-admin/edit-comments.php?p=226&approved=1#comments-form
Thx Starlino! :D
I will soon take a look at your suggestion,
But how about an explanation from this page : http://www.weizmann.ac.il/matlab/toolbox/aeroblks/directioncosinematrixtoeulerangles.html
Simple and clear explanation there, but are the final formula could be directly applied to your DCM?
Thank you, for your replies :-)
Yes , this is same DCM (Direction Cosine Matrix).
Great book you suggest me, i’m still reading it, but i got really confused (like the “first time” i read your(DCM tutorial) article) because it uses different formula compared to articles i read before to get euler angles from Rotation Matrices.
I think i will close the book for today, it,s 2 am in Indonesia, Time to Sleep, Thx for your help, thx for the book :D
Thank you very much :D
Hallo starlino, this is a real good tutorial, thx!!!
But i have a small question:
If i have computed my DCM_(n), do i need to multiply DCM_(n) with DCM_(n-1)? insofar i understand DCM_(n) is the rotation matrix from step n-1 to n. If i want get the orientation DCM must i multiply them?
ps: sry for my english, i hope could understand me.
imunoob: no you don’t need to multiply DMC(n) with DCM(n-1). DCM(n) already contains absolute rotation from initial position. The initial position is chosen as DCM(0) = I (where I is 3×3 identity matrix, all 1-s on the diagonal). So all DCM-s after that are relative to that position.
Starlino, i almost forgot, i’m keeping this question by my self till now but the harder i think more confused i get.
Ok here it is, there is some diference between your DCM tutorial and your Code.
In your algortm tutorial, the way you produce Angular displacement from Acc or Magneto is like this :
dθa = KB0 x (KB1A – KB0)
But in your Code it look like this :
vector3d_cross(dcmGyro[2],Kacc,wA);
doesn’t it has the same meaning as Doing cross Product between dcm_est[2] and dcm_acc[2] to get angular displacement? (dθa = KB0 x KB1A)
Did i miss something? In my program run on STM32 i build a program based on your DCM tutorial , and every things goes as expected. . . but till now i can’t figure out what are you planning to calculate in your program. . (This line of code = vector3d_cross(dcmGyro[2],Kacc,wA);)
Can you help me to explain your line of code that i’m asking you? Thx :-)
Alfiansyah : KB0 x (KB1A – KB0) = KB0 x KB1A – KB0 x KB0 = KB0 x KB1A , since KB0 x KB0 = 0
Part 1:
Thx Starlino :D
several test about your dynamic weight algorithm were done . . .
one disadvantage i found is, because of high vibration from quadrotor, acc value became noisy. . very noisy. And it is possible to cause 1 g value in opposite direction of stable condition, causing the IMU to trust the accelerometer just in time were it should not be trusted , causing the angle estimation jump crazy to opposite direction it should be.
Example, in my first experiment i manually tilted my quad pitch to -9 degree, using maximum acc_w 0.1(large indeed , just for test) and linearly decrease it to zero using 0.8>X<1.2 range.
And then i got this result as shown in figure : http://4.bp.blogspot.com/-eBINhwn0M_k/T_YBFLHtBfI/AAAAAAAABDg/cpIun_lWVzA/s1600/IMU+Pitch.png
Part 2:
Realtime 10 sec sensor reading in that condition shown in figure:
http://1.bp.blogspot.com/-T64uV4etfP8/T_X9Oz1FtkI/AAAAAAAABDQ/aAKuTibFSSQ/s1600/IIII.png
you can see that quadrotor (i’am using the same draganflyer as yours) motor vibration really make the accelerometer became crazy. next interesting point from that image is magnetometer an gyroscope is steady as nothing happen (no magnetic field analysis for magnetometer were made though)
Second experiment is to remove the dynamic weight algorithm and manually change the acc weight from 0.1 to 0.01,
One trial sample is shown in this figure : http://2.bp.blogspot.com/-rJLCDqT8fUM/T_YMWn-5OgI/AAAAAAAABDs/rFt2A-Mrhzs/s1600/imu_est.png
I got RMS error result Moving from 4.4degree to 4.0 degree (decrease) but i know that “if i decrease the acc weight more, gyro drift will dominate estimation result” and “if i keep increasing acc weight, more noise will dominate estimation result”
Part 3:
So in third experiment i decide to low pass filter the accelerometer raw data before using it to produce zenith vector
(lpf i use is => acc_x = (coef1)acc_x + (coef2)raw_acc_x ; were coef1+coef2 = 1) and i got better result in static condition. RMS error became 0.3 degree.
As shown is this figure : http://1.bp.blogspot.com/-Pbm54grQzxo/T_YOtu6wsyI/AAAAAAAABD0/hr3CRHdzzu8/s1600/imu_est2.png
But i believe it will produce huge lag in dynamic analysis, and that is what gyroscope exist for. . . to remove lag in dynamic condition. so we need your dynamic weight algorithm once again but in different structure
I propose using Gyroscope and accelerometer raw data to detect translation, rotation movement and noisy environment, so that we can decide when and how much we change the weight of “angular displacement produce from gyro” and “angular displacement produce from lowpassfiltered accelerometer (not raw accelerometer)” in fusing angular displacement phase. i still don’t have an idea how to take an advantage from “stable raw magnetometer data due to high vibration” is this analysis.
what do you think about my opinion sir?
Alfiansyah: the dynamic weighting algorithm purpose is to remove or decrease the acceleration data from the equation during SHORT periods of external acceleration for example a turn, a fall or a speed-up. It is not a solution for a constant noise. If the dynamic weighting algorithm is excluding accelerometer data all the time you’re left with gyro only that will drift over time. As you noticed a noisy and uncalibrated accelerometer is worst than no accelerometer. Another good thing you noticed is that the low pass filter will introduce a delay. So what is the solution ?
It is actually not in the code or electronics, it’s in the mechanics. First: the draganfly frame is really noisy and shaky, it’s a real challenge. Nowadays you can buy good ‘solid’ frames for under $20, look at ‘hobbyking’ site for example. Second: how is your accelerometer mounted ? Did you use solid screws ? Because I would recommend soft foam mounting tape , use several layers to dampen the effect of vibration.
Treat the problem at the source first. Eliminate noise, with your software I am sure you can measure it. So get a good frame and mounting that will minimize noise. Next,treat the remaining noise with a low pass-filter (you can use by-pass caps on a analog accelerometer or implement it in code). My acc_gyro_6dof for example has 0.1uF by pass caps that can be increased by external caps. Finally, don’t use dynamic weighting to eliminate something that would be constant (noise from motors). On the opposite you must include noise in the acceptable accelerometer data range since it’s a constant during flight.
I really like your concept of “Treat the problem at the source first”, I’am actually mounted it by softfoam but just one layer. . . I’am not thinking to find a solution from mechanics point of view, And now i realize it is important :P as you say.
Btw my friend and I succesfully implemented draganflyer to fly low using 4 IR range sensor. . i want to share the video but i think it is not good enough to show to you, i will improve it so than i will share it.
Hi Starlino,
Must thank you for the clear explanations you have given. I have a question regarding the code that you used to calculate the pitch and roll of your quadcopter.
float errorPitch = dcmEst[0][0] – RwTrg[0]; (1)
float errorRoll = dcmEst[0][1] – RwTrg[1]; (2)
I gather that dcmEst[0][x] is the bodyvector expressed in the global cordinate system and you have taken the pitch and roll as the i and j components of this vector. However
if we are to derive the euler angles as per
http://gentlenav.googlecode.com/files/EulerAngles.pdf
the calculations are different, needing a negative inverse sin and a tan inverse to get the roll and pitch angles respectively.
Have you used the simpler appoximation as the quadcopter is constrained from going beyond a certain (0.3 in the code) roll and pitch limits ?
Many Thanks
Ash
You must be looking at rev6 of main.c (that part of the code was still work in progress , and yes I believe the intention was just to get an estimate of the angle since for small angles arcsin(x) ~ x since I was probably just trying to get the device stabilized and hovering, although I should have used dcm[2][0] and dcm[2][1] which is the global Z axis in local coordinates … ) , please have a look at rev 8,
http://code.google.com/p/picquadcontroller/source/browse/trunk/main.c?r=8
hopefully it makes more sense. Also rev7 of imu.h has some fixes based on few comments here.
I’ve ported your imu.h rev 7 code to R to use to process gyro, accelerometer and GPS data collected while driving a car using an iPod with an external GPS dongle(Emprum Ultimate). I wanted to get more accurate lateral and lineal acceleration corrected for gravity while driving on a non-level surface and errors in orienting the iPod axes to the vehicle axes. After many stumbles, I think I’ve actually got it working. I’ve even managed to back out the approximate change in altitude. Your code and articles were a big help.
Thanks.
DeWitt Payne
By the way, the dcm_rotate function in rev 7 and 8 didn’t work correctly for me. I went back to the code you commented out, matrix multiplication of the old dcm times the skew plus identity matrix. You had that coded incorrectly too. You were multiplying W*dcm, which is the wrong order. Matrix multiplication isn’t commutative. It’s dcm*W in Premerlani’s article. The R language has matrix multiplication built in. The code is dcm%*%W. Once I fixed that, everything fell into place.
DeWitt, the reason Premerlani has it the other way http://gentlenav.googlecode.com/files/DCMDraft2.pdf is becasue of the reference coordinate system . In fact he explains it after Eqn.13 on page 14 .
“..Ideally,
we would like to track the axes of the aircraft in the earth frame of reference,
but the gyro measurements are made in the aircraft frame of reference. There
is an easy solution to the issue by recognizing the symmetry in the rotation. In
the frame of reference of the plane, the earth frame is rotating equal and
opposite to the rotation of the plane in the earth frame. So we can track the
earth axes as seen in the plane frame by flipping the sign of the gyro signals.”
…
so (-w) x r = r x w
Rather than change the formula I change the sign of gyro’s w, see http://code.google.com/p/picquadcontroller/source/browse/trunk/imu.h?r=7
//—————
//dcmGyro
//—————
float w[3]; //gyro rates (angular velocity of a global vector in local coordinates)
w[0] = -getGyroOutput(1); //rotation rate about accelerometer’s X axis (GY output) in rad/ms
w[1] = -getGyroOutput(0); //rotation rate about accelerometer’s Y axis (GX output) in rad/ms
w[2] = -getGyroOutput(2); //rotation rate about accelerometer’s Z axis (GZ output) in rad/ms
note the – sign in front of getGyroOutput.
Hope this clarifies the issue. You gotta pay attention to the sign of gyro output. The best way to test is to set the weights of Acc and Mag to 0 and see if the algorithm triggers correct results.
Hi Starlino,
I really enjoyed your tutorial. It is well written, interesting, comprehensive, and accurate. Nice work!
Bill Premerlani
I see the difference now. But what I want is the lateral and lineal acceleration in the vehicle frame corrected for changes in the gravity vector caused mainly by driving on a non-level surface and for any error in orientation of the sensor axes relative to the vehicle axes. Pitch and roll of the vehicle itself from lineal and lateral acceleration because the center of mass is above the vehicle roll and pitch axes is usually smaller. Since I’m post processing, I don’t care all that much if the code isn’t the most efficient. That might change if I try to do this in real time, but I’m not there yet.
Setting Acc and Mag to zero was indeed how I tested my code.
DeWitt have a look at Bill’s simple dead reckoning algorithm: http://diydrones.com/profiles/blogs/a-simple-deadreckoning it might provide you some clues. Basically you first need to compute an accurate orientation using DCM algorithm , then extract the gravitation vector from it ( G ). Then: True Acceleration(vector) = Accelerometer Reading(vector) – G(vector) .
That’s sort of what I’m doing except right now I’m just use the GPS speed and direction data. The implementation of the dead reckoning algorithm isn’t all that obvious to me from the code, particularly the rather important correction for GPS latency. Right now I use a fixed latency determined by comparing the accelerometer data to acceleration calculated from the GPS speed and direction data. I adjust the latency to make the curves overlap. I only just realized that the dead reckoning code contains assembly language commands and uses integer data in the registers with left and right shifts to multiply and divide by factors of 2. Efficient code, but hard to read for someone who hasn’t done assembly language programming for over forty years.
When I calculate the Euler angles from the calculated DCM, I get what looks like reasonable values. I can integrate the pitch angle and velocity to calculate altitude and get a plot that looks reasonable. It’s not perfect because I don’t include measured altitude in the correction feedback. The altitude changes are not large and the GPS I’m using doesn’t measure altitude as well as it does horizontal position even when it says it has a 3D lock. Specifically, when I drive around a loop, the difference in GPS measured altitude at the start and finish is larger than the difference in horizontal position. It’s about as far off as my calculated altitude. I’m using an Emprum Ultimate GPS on a gen 4 iPod and collecting the accelerometer, gyro rate and GPS data using the Sensor Data app.
There have been a few recent improvements to the basic DCM algorithm. One of them is a method for accounting for acceleration in the roll-pitch drift compensation without requiring any sort of dynamic model of the vehicle or aircraft. So, it could be used on anything, such as a motorcycle, automobile, boat, luge sled, etc. It has been successfully used by the Ardu team. Here are a couple of links:
http://diydrones.com/forum/topics/an-improved-method-for-accounting-for-acceleration-in-gyro-roll
http://www.diydrones.com/profiles/blogs/acceleration-compensation-flight-testing
Best regards,
Bill Premerlani
On inverting the axes:
I’m using the iPod in portrait orientation with the dock down. Because the z axis of the iPod is perpendicular to the face, I transpose the data so that the z axis data is treated as x axis data, the x axis is the y axis and the z axis is x axis. The directions of the axes are such that in this position, the z and x axis are already inverted, so if I invert the y axis data, I’m home. I did this to make things come out right, but now I understand why it needed to be done.
The correct accelerometer axis orientation would be face up with the dock to the right. But that’s not exactly the most convenient position for use.
Bill Premerlani,
Since I’m currently doing the calculations off-line because I don’t have the time to deal with real time data while I’m driving, I can fake faster GPS updates by applying a cubic spline smooth to the GPS data and using that fit to interpolate between readings. Then I have GPS data at the same rate as accelerometer data. So for me, it makes little difference whether I’m doing the calculations in body or earth frame.
Hi Starlino,
Many thanks for the wonderful tutorial. I’ve got a question about the getting Euler angles from the gyro output. I’ve read somewhere that Gyro output (rad/s) is not the derivative of Euler angles.
So can we actually integrate Gyro output(rad/s),w=[wx,wy,wz]to get Euler angles?? (Euler angles= wx(dt),wy(dt),wz(dt)??)
Thank you!!Really appreciate it.
Ken, you’re right you need to obtain first the DCM by integration, by following the algorithm in this article for example. Then you convert the DCM to Euler angles. “Theory of applied robotics” has all the formulas also some cautionary notes when working with Euler angles . Amazon Link: http://www.amazon.com/gp/product/1441917497/ref=as_li_qf_sp_asin_tl?ie=UTF8&tag=librarian06-20&linkCode=as2&camp=217145&creative=399353&creativeASIN=1441917497
Starlino, thanks for the fast reply! In your algorithm, when calculating the weighted avaverage d(theta), how can we determine the weight ‘sa’ and ‘sg’ ?
Many thanks!
sa=1 , sg= 20 will give good results in most cases. You can decreased sa dynamically if there’s external acceleration detected (when acc is noisy it’s modulus usually != 1g ), this was discussed somewhere in the comments in one of the articles under “IMU Theory and Experiments”.
Hi Starlino, GREAT tutorial! I understand how your DCM algorithm works by making use of accelerometer, magnetometer and gyro readings.
This might sound like a stupid question, but would it be possible for you to explain a bit on Eq 15 and Eq 17 (page 14-15) of ” Direction Cosine Matrix IMU: Theory (W Premerlani)” ? i.e. where’s the term R(t) on the RHS of Eq17 comes from? and is R(t+dt)the same as DCM[G] which is Eq1.1 in your tutorial? Also, the only way to know r{earth}(0) in Eq 15 is to query accelerometer right?
Thanks a bunch!:)
Jess, William put up a file explaining those equations , see: http://gentlenav.googlecode.com/files/MatrixRotation.pdf , hope this will lead you to the answers to the rest of the questions.
More docs related to DCMDraft2 can be found here: http://code.google.com/p/gentlenav/downloads/list (including the above document).
Also Ken, here is a pdf explaining one way to convert DCM matrix to Euler angles: http://gentlenav.googlecode.com/files/EulerAngles.pdf
I’m hopefully misunderstanding something here but shouldn’t the angular displacement be (let’s ignore magnetometer)
dθ = dθg + sa dθa
as dθg is the gyro-based displacement and dθa is just a correction term which is ideally zero?
I think Premerlani had it so in http://gentlenav.googlecode.com/files/DCMDraft2.pdf?
When you have
dθ = (sa dθa + sg dθg) / (sa + sg)
with sa=1 and sg=20 it’s almost correct because 20/21 \approx 1.
this topic is very good
Awesome tutorial. Thank you!
I’m a little confused with your derivation of equation 2.5. In the derivation, you assume that your instantaneous axis of rotation of r is orthogonal to r. But this is not the case in general.
The equation
v = w x r
does work in general, as long as the origin of your coordinate system lies on the axis of rotation (parallel to w). But if we manipulate this equation, cross multiplying both sides by r:
r x v = r x (w x r)
r x v = w(r.r) – r(r.w)
Rearranging,
w = ((r x v) – r(r.w))/|r|^2
We obtain your equation 2.5 only if (r.w) = 0.
Now if you are measuring the yaw component of w I can see why this would work, because you would have r = Ib = (Ibx,Iby) and w = (0,0,wz), so (r.w) = 0.
Care to elaborate?
Matt , the coordinate system was chosen to have same origin as w and r on purpose . Also w is perpendicular to r and r’ by definition (it’s perpendicular to the plain of rotation formed by r and r’), hence w.r = |w||r| cos(w,r) = 0 . If you need to work with a different coordinate system you will need to perform a liniar translation and then perform the rotation and then translate the result back.
Dear Starlino, thank you for this good article!
I have a question, please help me!
I want to extract the Euler angels relative to earth frame from gyro's outputs in a simulation study by using eqs: 17-21. Hence, in my code it is assumed that the gyro rotate about its x axis with angular velocity of 1 deg/sec and dt=20msec.
I except that after 1 second; pitch, roll and yaw values to be 0, 1 and 1 degree respectively. But I never receive to this result. I am very confused. Are my exception is correct? Furthermore, these angles have large variation. What is my mistake point?
Best regards
How does DCM do a basic complementary filter? I am not able to understand which block of the DCM does this. Could someone throw light on this?