mirror of https://github.com/ArduPilot/ardupilot
AP_Math: quaternion: add from_euler(Vector3&)
This commit is contained in:
parent
6f3e3a913a
commit
118d3f085f
|
@ -417,6 +417,11 @@ void QuaternionT<T>::from_euler(T roll, T pitch, T yaw)
|
|||
q3 = cr2*sp2*cy2 + sr2*cp2*sy2;
|
||||
q4 = cr2*cp2*sy2 - sr2*sp2*cy2;
|
||||
}
|
||||
template <typename T>
|
||||
void QuaternionT<T>::from_euler(const Vector3<T> &v)
|
||||
{
|
||||
from_euler(v[0], v[1], v[2]);
|
||||
}
|
||||
|
||||
// create a quaternion from Euler angles applied in yaw, roll, pitch order
|
||||
// instead of the normal yaw, pitch, roll order
|
||||
|
|
|
@ -81,6 +81,7 @@ public:
|
|||
|
||||
// create a quaternion from Euler angles
|
||||
void from_euler(T roll, T pitch, T yaw);
|
||||
void from_euler(const Vector3<T> &v);
|
||||
|
||||
// create a quaternion from Euler angles applied in yaw, roll, pitch order
|
||||
// instead of the normal yaw, pitch, roll order
|
||||
|
|
Loading…
Reference in New Issue