Quaternions vs atan2

Here is the place for all your dsPic or autopilot questions.

Moderator: lukasz

Quaternions vs atan2

Postby nyd » Thu Mar 04, 2010 11:33 pm

Hi!

First of all, congratulations for your project.

I'm developing a movement quantification system, with a 3-axis gyro and a 3-axis accelerometer.
In my first approach i'm only using the 3-axis acc to get the rotation using for that purpose the atan2 function and the acceleration vectors.

Two questions, did you test this approach? And a newbie one, how did you used the quaternions with the gyroscopes?

thanks in advance for your answer.

Regards
nyd
 
Posts: 7
Joined: Thu Mar 04, 2010 11:28 pm

Re: Quaternions vs atan2

Postby Mitch » Fri Mar 05, 2010 3:29 pm

I'll jump in,

Using the inverse trig functions is a very common solution but there are several drawbacks. They have singularities at specific attitudes that have to be addressed separately. They converge at the north and south poles where roll is the same as yaw (where pitch = pi/2). The computation time for the trig functions is higher than for the simple multiplication required for manipulating quaternions. A direction cosine matrix is 9 scalar numbers where a quaternion rotation is only 4.

Here is an example of a routine that estimates the attitude from accelerometer readings:

/*
* This will convert from accelerometer and compass readings into
* [phi, theta, psi] (in radians).
*/
void accel2euler(
vector euler,
float ax,
float ay,
float az,
float compass
)
{
float g = sqrt( ax*ax + ay*ay + az*az );

euler[0] = atan2( ay, -az ); // Roll
euler[1] = asin( ax / -g ); // Pitch
euler[2] = compass; // Yaw
}

Note the accelerometer data alone is insufficient to determine the attitude because the accelerometers cannot measure the rotation about the gravity vector (vertical axis). Some other data is required. The g vector magnitude calculation is not required but it helps to minimize error due to accelerometer calibration. Any acceleration of the vehicle will be measured by the accelerometers and render the attitude estimate unreliable.

Quaternions eliminate the difficiencies I listed above. Accelerometers must be augmented with other data.

In Tom's code, he elegantly implemented a control loop that rotates the quaternion estimated attitude based on gyro measurements.
User avatar
Mitch
 
Posts: 118
Joined: Sat Dec 05, 2009 1:59 pm
Location: Florida, USA

Re: Quaternions vs atan2

Postby Tom » Sat Mar 06, 2010 11:29 am

Mitch already formulated a nice answer :-)

I would propose to take a look at the code and do some tests or simulations.
User avatar
Tom
Site Admin
 
Posts: 1016
Joined: Fri Nov 13, 2009 6:27 pm
Location: Belgium

Re: Quaternions vs atan2

Postby nyd » Sat Mar 06, 2010 5:27 pm

In did a good answer.

One question, in theta, why can't you calculate it using the atan2 function, like this:

theta= athan2(ax,az) ? similar for the phi rotattion.


From what i understood, since you are unable to get the vertical rotation using the accelerometer data, to develop a 3-axis rotation system you always need to have a 6-DOF data.

Whell... at least a 4-DOF system.

Thanks for your answer, once again.
nyd
 
Posts: 7
Joined: Thu Mar 04, 2010 11:28 pm

Re: Quaternions vs atan2

Postby Tom » Sat Mar 06, 2010 6:06 pm

It depends on how you want to have your angles.
For example:
pitch = 110°, roll = 0°, yaw = 0°
pitch = 70°, roll = 180°, yaw = 180°
These 2 attitudes are the same. I'm sure you can come up with some less obvious examples :-)
In my code, pitch never exceeds 90°, while roll does. Which means an asin would be fine for pitch.

The needed tools depend on what you want. You could have a 2 axis accelerometer and 1 yaw gyro without drift.
You could also have 3 gyros, 3 accelerometers and 3 magnetometers. A 9-DOF that does the same thing ;-)
But that's all theory. 6DOF defines that we have a system with 6 inputs which we use in our model.
User avatar
Tom
Site Admin
 
Posts: 1016
Joined: Fri Nov 13, 2009 6:27 pm
Location: Belgium

Re: Quaternions vs atan2

Postby nyd » Thu Mar 11, 2010 5:23 pm

Hmmmm... good point.

I searched for you implementation of quaternions but didn't found it on the download section. In which .c is it?


Regards.
nyd
 
Posts: 7
Joined: Thu Mar 04, 2010 11:28 pm

Re: Quaternions vs atan2

Postby Tom » Thu Mar 11, 2010 8:45 pm

I really should make the sourcecode more viewable somehow :-)

Here you can find the quaternion implementation: http://code.google.com/p/gluonpilot/sou ... aternion.c
User avatar
Tom
Site Admin
 
Posts: 1016
Joined: Fri Nov 13, 2009 6:27 pm
Location: Belgium

Re: Quaternions vs atan2

Postby nyd » Tue Mar 16, 2010 7:41 pm

Hi Again.

I was studying your code and in the update of the quaternion with the input rates you have:

Code: Select all
  q0 += 0.5f * (        - q[1]*w1 - q[2]*w2 - q[3]*w3)*dt;
        q1 += 0.5f * (q[0]*w1 +           q[2]*w3 - q[3]*w2)*dt;
        q2 += 0.5f * (q[0]*w2 - q[1]*w3 +           q[3]*w1)*dt;
        q3 += 0.5f * (q[0]*w3 + q[1]*w2 - q[2]*w1)*dt;


But here
http://www.euclideanspace.com/physics/kinematics/angularvelocity/

they present this differential equation:

d q0(t) / dt = − 1/2* (Wx (t) q1(t) + Wy (t) q2(t) + Wz (t) q3(t))
d q1(t) / dt = 1/2* (Wx (t) q0(t) + Wy (t) q3(t) − Wz (t) q2(t))
d q2(t) / dt = 1/2* (Wy (t) q0(t) + Wz (t) q1(t) − Wx (t) q3(t))
d q3(t) / dt = 1/2* (Wz (t) q0(t) + Wx (t) q2(t) − Wy (t) q1(t))

The difference between both case is the negative sinal when updating (for example) q2:

Code: Select all
+ Wz (t) q1(t) − Wx (t) q3(t)


and

Code: Select all
 - q[1]*w3 + q[3]*w1


is this an error ?
nyd
 
Posts: 7
Joined: Thu Mar 04, 2010 11:28 pm

Re: Quaternions vs atan2

Postby nyd » Tue Mar 16, 2010 8:19 pm

I searched for an answer and your code is the one thats right.

Regards.
nyd
 
Posts: 7
Joined: Thu Mar 04, 2010 11:28 pm

Re: Quaternions vs atan2

Postby nyd » Tue Mar 16, 2010 10:54 pm

Another step another doubt :D

Do you combine the Gyros data (rates) with accelerometers in the quaternions? and How?

Or you just do that in the Kalman filter.

Regards.
nyd
 
Posts: 7
Joined: Thu Mar 04, 2010 11:28 pm

Next

Return to Firmware

Who is online

Users browsing this forum: No registered users and 8 guests

cron