5
0
mirror of https://github.com/ArduPilot/ardupilot synced 2025-01-11 02:18:29 -04:00

uncrustify libraries/AP_Math/quaternion.h

This commit is contained in:
uncrustify 2012-08-16 23:20:14 -07:00 committed by Pat Hickey
parent 140aed0770
commit 6016a241b0

View File

@ -19,19 +19,26 @@ public:
// constructor creates a quaternion equivalent
// to roll=0, pitch=0, yaw=0
Quaternion() { q1 = 1; q2 = q3 = q4 = 0; }
Quaternion() {
q1 = 1; q2 = q3 = q4 = 0;
}
// setting constructor
Quaternion(const float _q1, const float _q2, const float _q3, const float _q4):
q1(_q1), q2(_q2), q3(_q3), q4(_q4) {}
Quaternion(const float _q1, const float _q2, const float _q3, const float _q4) :
q1(_q1), q2(_q2), q3(_q3), q4(_q4) {
}
// function call operator
void operator ()(const float _q1, const float _q2, const float _q3, const float _q4)
{ q1 = _q1; q2 = _q2; q3 = _q3; q4 = _q4; }
{
q1 = _q1; q2 = _q2; q3 = _q3; q4 = _q4;
}
// check if any elements are NAN
bool is_nan(void)
{ return isnan(q1) || isnan(q2) || isnan(q3) || isnan(q4); }
{
return isnan(q1) || isnan(q2) || isnan(q3) || isnan(q4);
}
// return the rotation matrix equivalent for this quaternion
void rotation_matrix(Matrix3f &m);