1 #ifndef _MAVLINK_CONVERSIONS_H_ 2 #define _MAVLINK_CONVERSIONS_H_ 4 #ifndef MAVLINK_NO_CONVERSION_HELPERS 8 #ifndef _USE_MATH_DEFINES 9 #define _USE_MATH_DEFINES 15 #define M_PI_2 ((float)asin(1)) 42 double a = quaternion[0];
43 double b = quaternion[1];
44 double c = quaternion[2];
45 double d = quaternion[3];
50 dcm[0][0] = aSq + bSq - cSq - dSq;
51 dcm[0][1] = 2 * (b * c - a * d);
52 dcm[0][2] = 2 * (a * c + b * d);
53 dcm[1][0] = 2 * (b * c + a * d);
54 dcm[1][1] = aSq - bSq + cSq - dSq;
55 dcm[1][2] = 2 * (c * d - a *
b);
56 dcm[2][0] = 2 * (b * d - a * c);
57 dcm[2][1] = 2 * (a * b + c * d);
58 dcm[2][2] = aSq - bSq - cSq + dSq;
72 float phi, theta, psi;
73 theta = asin(-dcm[2][0]);
75 if (fabsf(theta - (
float)
M_PI_2) < 1.0
e-3
f) {
77 psi = (atan2f(dcm[1][2] - dcm[0][1],
78 dcm[0][2] + dcm[1][1]) + phi);
80 }
else if (fabsf(theta + (
float)M_PI_2) < 1.0e-3
f) {
82 psi = atan2f(dcm[1][2] - dcm[0][1],
83 dcm[0][2] + dcm[1][1] - phi);
86 phi = atan2f(dcm[2][1], dcm[2][2]);
87 psi = atan2f(dcm[1][0], dcm[0][0]);
122 float cosPhi_2 = cosf(roll / 2);
123 float sinPhi_2 = sinf(roll / 2);
124 float cosTheta_2 = cosf(pitch / 2);
125 float sinTheta_2 = sinf(pitch / 2);
126 float cosPsi_2 = cosf(yaw / 2);
127 float sinPsi_2 = sinf(yaw / 2);
128 quaternion[0] = (cosPhi_2 * cosTheta_2 * cosPsi_2 +
129 sinPhi_2 * sinTheta_2 * sinPsi_2);
130 quaternion[1] = (sinPhi_2 * cosTheta_2 * cosPsi_2 -
131 cosPhi_2 * sinTheta_2 * sinPsi_2);
132 quaternion[2] = (cosPhi_2 * sinTheta_2 * cosPsi_2 +
133 sinPhi_2 * cosTheta_2 * sinPsi_2);
134 quaternion[3] = (cosPhi_2 * cosTheta_2 * sinPsi_2 -
135 sinPhi_2 * sinTheta_2 * cosPsi_2);
150 float tr = dcm[0][0] + dcm[1][1] + dcm[2][2];
152 float s = sqrtf(tr + 1.0
f);
153 quaternion[0] = s * 0.5f;
155 quaternion[1] = (dcm[2][1] - dcm[1][2]) * s;
156 quaternion[2] = (dcm[0][2] - dcm[2][0]) * s;
157 quaternion[3] = (dcm[1][0] - dcm[0][1]) * s;
163 for (i = 1; i < 3; i++) {
164 if (dcm[i][i] > dcm[dcm_i][dcm_i]) {
169 int dcm_j = (dcm_i + 1) % 3;
170 int dcm_k = (dcm_i + 2) % 3;
172 float s = sqrtf((dcm[dcm_i][dcm_i] - dcm[dcm_j][dcm_j] -
173 dcm[dcm_k][dcm_k]) + 1.0
f);
174 quaternion[dcm_i + 1] = s * 0.5f;
176 quaternion[dcm_j + 1] = (dcm[dcm_i][dcm_j] + dcm[dcm_j][dcm_i]) * s;
177 quaternion[dcm_k + 1] = (dcm[dcm_k][dcm_i] + dcm[dcm_i][dcm_k]) * s;
178 quaternion[0] = (dcm[dcm_k][dcm_j] - dcm[dcm_j][dcm_k]) * s;
193 float cosPhi = cosf(roll);
194 float sinPhi = sinf(roll);
195 float cosThe = cosf(pitch);
196 float sinThe = sinf(pitch);
197 float cosPsi = cosf(yaw);
198 float sinPsi = sinf(yaw);
200 dcm[0][0] = cosThe * cosPsi;
201 dcm[0][1] = -cosPhi * sinPsi + sinPhi * sinThe * cosPsi;
202 dcm[0][2] = sinPhi * sinPsi + cosPhi * sinThe * cosPsi;
204 dcm[1][0] = cosThe * sinPsi;
205 dcm[1][1] = cosPhi * cosPsi + sinPhi * sinThe * sinPsi;
206 dcm[1][2] = -sinPhi * cosPsi + cosPhi * sinThe * sinPsi;
209 dcm[2][1] = sinPhi * cosThe;
210 dcm[2][2] = cosPhi * cosThe;
213 #endif // MAVLINK_NO_CONVERSION_HELPERS 215 #endif // _MAVLINK_CONVERSIONS_H_ MAVLINK_HELPER void mavlink_quaternion_to_euler(const float quaternion[4], float *roll, float *pitch, float *yaw)
MAVLINK_HELPER void mavlink_euler_to_dcm(float roll, float pitch, float yaw, float dcm[3][3])
MAVLINK_HELPER void mavlink_dcm_to_euler(const float dcm[3][3], float *roll, float *pitch, float *yaw)
MAVLINK_HELPER void mavlink_quaternion_to_dcm(const float quaternion[4], float dcm[3][3])
MAVLINK_HELPER void mavlink_euler_to_quaternion(float roll, float pitch, float yaw, float quaternion[4])
MAVLINK_HELPER void mavlink_dcm_to_quaternion(const float dcm[3][3], float quaternion[4])