1 #ifndef _MAVLINK_CONVERSIONS_H_ 2 #define _MAVLINK_CONVERSIONS_H_ 6 #ifndef _USE_MATH_DEFINES 7 #define _USE_MATH_DEFINES 13 #define M_PI_2 ((float)asin(1)) 40 double a = quaternion[0];
41 double b = quaternion[1];
42 double c = quaternion[2];
43 double d = quaternion[3];
48 dcm[0][0] = aSq + bSq - cSq - dSq;
49 dcm[0][1] = 2 * (b * c - a * d);
50 dcm[0][2] = 2 * (a * c + b * d);
51 dcm[1][0] = 2 * (b * c + a * d);
52 dcm[1][1] = aSq - bSq + cSq - dSq;
53 dcm[1][2] = 2 * (c * d - a * b);
54 dcm[2][0] = 2 * (b * d - a * c);
55 dcm[2][1] = 2 * (a * b + c * d);
56 dcm[2][2] = aSq - bSq - cSq + dSq;
70 float phi, theta, psi;
71 theta =
asin(-dcm[2][0]);
73 if (fabsf(theta - (
float)
M_PI_2) < 1.0e-3
f) {
75 psi = (atan2f(dcm[1][2] - dcm[0][1],
76 dcm[0][2] + dcm[1][1]) + phi);
78 }
else if (fabsf(theta + (
float)M_PI_2) < 1.0e-3
f) {
80 psi = atan2f(dcm[1][2] - dcm[0][1],
81 dcm[0][2] + dcm[1][1] - phi);
84 phi = atan2f(dcm[2][1], dcm[2][2]);
85 psi = atan2f(dcm[1][0], dcm[0][0]);
120 float cosPhi_2 = cosf(roll / 2);
121 float sinPhi_2 = sinf(roll / 2);
122 float cosTheta_2 = cosf(pitch / 2);
123 float sinTheta_2 = sinf(pitch / 2);
124 float cosPsi_2 = cosf(yaw / 2);
125 float sinPsi_2 = sinf(yaw / 2);
126 quaternion[0] = (cosPhi_2 * cosTheta_2 * cosPsi_2 +
127 sinPhi_2 * sinTheta_2 * sinPsi_2);
128 quaternion[1] = (sinPhi_2 * cosTheta_2 * cosPsi_2 -
129 cosPhi_2 * sinTheta_2 * sinPsi_2);
130 quaternion[2] = (cosPhi_2 * sinTheta_2 * cosPsi_2 +
131 sinPhi_2 * cosTheta_2 * sinPsi_2);
132 quaternion[3] = (cosPhi_2 * cosTheta_2 * sinPsi_2 -
133 sinPhi_2 * sinTheta_2 * cosPsi_2);
148 float tr = dcm[0][0] + dcm[1][1] + dcm[2][2];
150 float s = sqrtf(tr + 1.0
f);
151 quaternion[0] = s * 0.5f;
153 quaternion[1] = (dcm[2][1] - dcm[1][2]) * s;
154 quaternion[2] = (dcm[0][2] - dcm[2][0]) * s;
155 quaternion[3] = (dcm[1][0] - dcm[0][1]) * s;
161 for (i = 1; i < 3; i++) {
162 if (dcm[i][i] > dcm[dcm_i][dcm_i]) {
167 int dcm_j = (dcm_i + 1) % 3;
168 int dcm_k = (dcm_i + 2) % 3;
170 float s = sqrtf((dcm[dcm_i][dcm_i] - dcm[dcm_j][dcm_j] -
171 dcm[dcm_k][dcm_k]) + 1.0
f);
172 quaternion[dcm_i + 1] = s * 0.5f;
174 quaternion[dcm_j + 1] = (dcm[dcm_i][dcm_j] + dcm[dcm_j][dcm_i]) * s;
175 quaternion[dcm_k + 1] = (dcm[dcm_k][dcm_i] + dcm[dcm_i][dcm_k]) * s;
176 quaternion[0] = (dcm[dcm_k][dcm_j] - dcm[dcm_j][dcm_k]) * s;
191 float cosPhi = cosf(roll);
192 float sinPhi = sinf(roll);
193 float cosThe = cosf(pitch);
194 float sinThe = sinf(pitch);
195 float cosPsi = cosf(yaw);
196 float sinPsi = sinf(yaw);
198 dcm[0][0] = cosThe * cosPsi;
199 dcm[0][1] = -cosPhi * sinPsi + sinPhi * sinThe * cosPsi;
200 dcm[0][2] = sinPhi * sinPsi + cosPhi * sinThe * cosPsi;
202 dcm[1][0] = cosThe * sinPsi;
203 dcm[1][1] = cosPhi * cosPsi + sinPhi * sinThe * sinPsi;
204 dcm[1][2] = -sinPhi * cosPsi + cosPhi * sinThe * sinPsi;
207 dcm[2][1] = sinPhi * cosThe;
208 dcm[2][2] = cosPhi * cosThe;
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_euler(const float quaternion[4], 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])