Open matherp opened 8 years ago
No, this is expected. If you choose a North/East/Down convention (typical, but not the only one) then you have to choose which sensor axis is North. Let's say x. The you need to look at the sensor axes and make sure that the North, East, and Down responses are properly aligned. In this case, it is odd since I think the MPU9250 has the z-axes of the sensor responses all aligned up. But if you are using your sensor in the down position or something, maybe you need the minus sign to conform to the NED convention. Not really sure. . .
-----Original Message----- From: matherp [mailto:notifications@github.com] Sent: March 13, 2016 1:16 AM To: kriswiner/MPU-9250 Subject: [MPU-9250] +mz or -mz (#51)
Hi kris
I'm using the code as a simple tilt compensated compass by feeding in a north vector as the start quaternion and then subtracting the yaw angle from 360 to give the compass heading. This works perfectly.
However, to get the compass to compensate for tilt properly I've found that the update call must be
` MadgwickQuaternionUpdate(ax, ay, az, gx, gy, gz, my, mx, -mz)
With mz positive the yaw works but only when the board is level. With it negative the yaw angle is maintained perfectly even with significant tilt angles in pitch and roll. Is this a bug in the published code or am I missing something as usual
Thanks
Peter`
Reply to this email directly or view it on GitHub https://github.com/kriswiner/MPU-9250/issues/51 . https://github.com/notifications/beacon/AGY1qsVOg0QDuPAK3RP9xwUkExcNCvhnks5 ps9XlgaJpZM4HvftP.gif
Kris
Thanks for the input
Demo of your code ported to Basic on a PIC32MX470 with some added visualisation here
Actually, after a little more thought, I think this is correct for the MPU9250:
// Sensors x (y)-axis of the accelerometer/gyro is aligned with the y
(x)axis of the magnetometer;
// the magnetometer z-axis (+ down) is misaligned with z-axis (+ up) of
accelerometer and gyro!
// We have to make some allowance for this orientation mismatch in feeding
the output to the quaternion filter.
// We will assume that +y accel/gyro is North, then x accel/gyro is East.
So if we want te quaternions properly aligned
// we need to feed into the madgwick function Ay, Ax, -Az, Gy, Gx, -Gz,
Mx, My, and Mz. But because gravity is by convention
// positive down, we need to invert the accel data, so we pass -Ay, -Ax,
Az, Gy, Gx, -Gz, Mx, My, and Mz into the Madgwick
// function to get North along the accel +y-axis, East along the accel
+x-axis, and Down along the accel -z-axis.
// This orientation choice can be modified to allow any convenient
(non-NED) orientation convention.
// This is ok by aircraft orientation standards!
// Pass gyro rate as rad/s
MadgwickQuaternionUpdate(-ay, -ax, az, gy_PI/180.0f, gx_PI/180.0f,
-gz_PI/180.0f, mx, my, mz);
// if(passThru)MahonyQuaternionUpdate(-ay, -ax, az, gy_PI/180.0f,
gx_PI/180.0f, -gz_PI/180.0f, mx, my, mz);
Kris
-----Original Message----- From: matherp [mailto:notifications@github.com] Sent: March 14, 2016 2:55 PM To: kriswiner/MPU-9250 Cc: Kris Winer Subject: Re: [MPU-9250] +mz or -mz (#51)
Kris
Thanks for the input
Demo of your code ported to Basic on a PIC32MX470 with some added visualisation here
Reply to this email directly or view it on GitHub https://github.com/kriswiner/MPU-9250/issues/51#issuecomment-196537744 . https://github.com/notifications/beacon/AGY1qoozVKnrFamNicZGp6nkfr1RW8pVks5 ptdlQgaJpZM4HvftP.gif
Hi kris
I'm using the code as a simple tilt compensated compass by feeding in a north vector as the start quaternion and then subtracting the yaw angle from 360 to give the compass heading. This works perfectly.
However, to get the compass to compensate for tilt properly I've found that the update call must be
` MadgwickQuaternionUpdate(ax, ay, az, gx, gy, gz, my, mx, -mz)
With mz positive the yaw works but only when the board is level. With it negative the yaw angle is maintained perfectly even with significant tilt angles in pitch and roll. Is this a bug in the published code or am I missing something as usual
Thanks
Peter`