mirror of https://github.com/ArduPilot/ardupilot
uncrustify libraries/AP_Math/quaternion.h
This commit is contained in:
parent
140aed0770
commit
6016a241b0
|
@ -15,34 +15,41 @@
|
||||||
class Quaternion
|
class Quaternion
|
||||||
{
|
{
|
||||||
public:
|
public:
|
||||||
float q1, q2, q3, q4;
|
float q1, q2, q3, q4;
|
||||||
|
|
||||||
// constructor creates a quaternion equivalent
|
// constructor creates a quaternion equivalent
|
||||||
// to roll=0, pitch=0, yaw=0
|
// to roll=0, pitch=0, yaw=0
|
||||||
Quaternion() { q1 = 1; q2 = q3 = q4 = 0; }
|
Quaternion() {
|
||||||
|
q1 = 1; q2 = q3 = q4 = 0;
|
||||||
|
}
|
||||||
|
|
||||||
// setting constructor
|
// setting constructor
|
||||||
Quaternion(const float _q1, const float _q2, const float _q3, const float _q4):
|
Quaternion(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) {
|
||||||
|
}
|
||||||
|
|
||||||
// function call operator
|
// function call operator
|
||||||
void operator ()(const float _q1, const float _q2, const float _q3, const float _q4)
|
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
|
// check if any elements are NAN
|
||||||
bool is_nan(void)
|
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
|
// return the rotation matrix equivalent for this quaternion
|
||||||
void rotation_matrix(Matrix3f &m);
|
void rotation_matrix(Matrix3f &m);
|
||||||
|
|
||||||
// convert a vector from earth to body frame
|
// convert a vector from earth to body frame
|
||||||
void earth_to_body(Vector3f &v);
|
void earth_to_body(Vector3f &v);
|
||||||
|
|
||||||
// create a quaternion from Euler angles
|
// create a quaternion from Euler angles
|
||||||
void from_euler(float roll, float pitch, float yaw);
|
void from_euler(float roll, float pitch, float yaw);
|
||||||
|
|
||||||
// create eulers from a quaternion
|
// create eulers from a quaternion
|
||||||
void to_euler(float *roll, float *pitch, float *yaw);
|
void to_euler(float *roll, float *pitch, float *yaw);
|
||||||
};
|
};
|
||||||
#endif // QUATERNION_H
|
#endif // QUATERNION_H
|
||||||
|
|
Loading…
Reference in New Issue