mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-22 15:53:56 -04:00
AP_Math: Fix bug in quaternion division
This commit is contained in:
parent
1660aefc90
commit
255252f387
@ -284,8 +284,8 @@ Quaternion Quaternion::operator/(const Quaternion &v) {
|
||||
float rquat3 = v.q4;
|
||||
|
||||
ret.q1 = (rquat0*quat0 + rquat1*quat1 + rquat2*quat2 + rquat3*quat3);
|
||||
ret.q1 = (rquat0*quat1 - rquat1*quat0 - rquat2*quat3 + rquat3*quat2);
|
||||
ret.q1 = (rquat0*quat2 + rquat1*quat3 - rquat2*quat0 - rquat3*quat1);
|
||||
ret.q1 = (rquat0*quat3 - rquat1*quat2 + rquat2*quat1 - rquat3*quat0);
|
||||
ret.q2 = (rquat0*quat1 - rquat1*quat0 - rquat2*quat3 + rquat3*quat2);
|
||||
ret.q3 = (rquat0*quat2 + rquat1*quat3 - rquat2*quat0 - rquat3*quat1);
|
||||
ret.q4 = (rquat0*quat3 - rquat1*quat2 + rquat2*quat1 - rquat3*quat0);
|
||||
return ret;
|
||||
}
|
||||
|
Loading…
Reference in New Issue
Block a user