mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 14:38:30 -04:00
AP_Math: add quaternion.initialise
This commit is contained in:
parent
c366fbbc96
commit
eaedeeb7bf
@ -98,6 +98,9 @@ public:
|
||||
float length(void) const;
|
||||
void normalize();
|
||||
|
||||
// initialise the quaternion to no rotation
|
||||
void initialise() { q1 = 1.0f; q2 = q3 = q4 = 0.0f; }
|
||||
|
||||
Quaternion inverse(void) const;
|
||||
|
||||
// allow a quaternion to be used as an array, 0 indexed
|
||||
|
Loading…
Reference in New Issue
Block a user