mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-03-09 16:13:56 -03:00
AP_Math: add quaternion::angular_difference
This commit is contained in:
parent
72fabb5cd3
commit
07f7d793df
@ -366,3 +366,9 @@ Quaternion Quaternion::operator/(const Quaternion &v) const
|
||||
ret.q4 = (rquat0*quat3 - rquat1*quat2 + rquat2*quat1 - rquat3*quat0);
|
||||
return ret;
|
||||
}
|
||||
|
||||
// angular difference in radians between quaternions
|
||||
Quaternion Quaternion::angular_difference(const Quaternion &v) const
|
||||
{
|
||||
return v.inverse() * *this;
|
||||
}
|
||||
|
@ -141,4 +141,7 @@ public:
|
||||
Quaternion operator*(const Quaternion &v) const;
|
||||
Quaternion &operator*=(const Quaternion &v);
|
||||
Quaternion operator/(const Quaternion &v) const;
|
||||
|
||||
// angular difference between quaternions
|
||||
Quaternion angular_difference(const Quaternion &v) const;
|
||||
};
|
||||
|
Loading…
Reference in New Issue
Block a user