MAV'RIC
mavlink_conversions.h
Go to the documentation of this file.
1 #ifndef _MAVLINK_CONVERSIONS_H_
2 #define _MAVLINK_CONVERSIONS_H_
3 
4 /* enable math defines on Windows */
5 #ifdef _MSC_VER
6 #ifndef _USE_MATH_DEFINES
7 #define _USE_MATH_DEFINES
8 #endif
9 #endif
10 #include <math.h>
11 
12 #ifndef M_PI_2
13  #define M_PI_2 ((float)asin(1))
14 #endif
15 
37 MAVLINK_HELPER void mavlink_quaternion_to_dcm(const float quaternion[4], float dcm[3][3])
38 {
39  double a = quaternion[0];
40  double b = quaternion[1];
41  double c = quaternion[2];
42  double d = quaternion[3];
43  double aSq = a * a;
44  double bSq = b * b;
45  double cSq = c * c;
46  double dSq = d * d;
47  dcm[0][0] = aSq + bSq - cSq - dSq;
48  dcm[0][1] = 2.0 * (b * c - a * d);
49  dcm[0][2] = 2.0 * (a * c + b * d);
50  dcm[1][0] = 2.0 * (b * c + a * d);
51  dcm[1][1] = aSq - bSq + cSq - dSq;
52  dcm[1][2] = 2.0 * (c * d - a * b);
53  dcm[2][0] = 2.0 * (b * d - a * c);
54  dcm[2][1] = 2.0 * (a * b + c * d);
55  dcm[2][2] = aSq - bSq - cSq + dSq;
56 }
57 
58 
67 MAVLINK_HELPER void mavlink_dcm_to_euler(const float dcm[3][3], float* roll, float* pitch, float* yaw)
68 {
69  float phi, theta, psi;
70  theta = asin(-dcm[2][0]);
71 
72  if (fabsf(theta - (float)M_PI_2) < 1.0e-3f) {
73  phi = 0.0f;
74  psi = (atan2f(dcm[1][2] - dcm[0][1],
75  dcm[0][2] + dcm[1][1]) + phi);
76 
77  } else if (fabsf(theta + (float)M_PI_2) < 1.0e-3f) {
78  phi = 0.0f;
79  psi = atan2f(dcm[1][2] - dcm[0][1],
80  dcm[0][2] + dcm[1][1] - phi);
81 
82  } else {
83  phi = atan2f(dcm[2][1], dcm[2][2]);
84  psi = atan2f(dcm[1][0], dcm[0][0]);
85  }
86 
87  *roll = phi;
88  *pitch = theta;
89  *yaw = psi;
90 }
91 
92 
101 MAVLINK_HELPER void mavlink_quaternion_to_euler(const float quaternion[4], float* roll, float* pitch, float* yaw)
102 {
103  float dcm[3][3];
104  mavlink_quaternion_to_dcm(quaternion, dcm);
105  mavlink_dcm_to_euler((const float(*)[3])dcm, roll, pitch, yaw);
106 }
107 
108 
117 MAVLINK_HELPER void mavlink_euler_to_quaternion(float roll, float pitch, float yaw, float quaternion[4])
118 {
119  double cosPhi_2 = cos((double)roll / 2.0);
120  double sinPhi_2 = sin((double)roll / 2.0);
121  double cosTheta_2 = cos((double)pitch / 2.0);
122  double sinTheta_2 = sin((double)pitch / 2.0);
123  double cosPsi_2 = cos((double)yaw / 2.0);
124  double sinPsi_2 = sin((double)yaw / 2.0);
125  quaternion[0] = (cosPhi_2 * cosTheta_2 * cosPsi_2 +
126  sinPhi_2 * sinTheta_2 * sinPsi_2);
127  quaternion[1] = (sinPhi_2 * cosTheta_2 * cosPsi_2 -
128  cosPhi_2 * sinTheta_2 * sinPsi_2);
129  quaternion[2] = (cosPhi_2 * sinTheta_2 * cosPsi_2 +
130  sinPhi_2 * cosTheta_2 * sinPsi_2);
131  quaternion[3] = (cosPhi_2 * cosTheta_2 * sinPsi_2 -
132  sinPhi_2 * sinTheta_2 * cosPsi_2);
133 }
134 
135 
142 MAVLINK_HELPER void mavlink_dcm_to_quaternion(const float dcm[3][3], float quaternion[4])
143 {
144  quaternion[0] = (0.5 * sqrt(1.0 +
145  (double)(dcm[0][0] + dcm[1][1] + dcm[2][2])));
146  quaternion[1] = (0.5 * sqrt(1.0 +
147  (double)(dcm[0][0] - dcm[1][1] - dcm[2][2])));
148  quaternion[2] = (0.5 * sqrt(1.0 +
149  (double)(-dcm[0][0] + dcm[1][1] - dcm[2][2])));
150  quaternion[3] = (0.5 * sqrt(1.0 +
151  (double)(-dcm[0][0] - dcm[1][1] + dcm[2][2])));
152 }
153 
154 
163 MAVLINK_HELPER void mavlink_euler_to_dcm(float roll, float pitch, float yaw, float dcm[3][3])
164 {
165  double cosPhi = cos(roll);
166  double sinPhi = sin(roll);
167  double cosThe = cos(pitch);
168  double sinThe = sin(pitch);
169  double cosPsi = cos(yaw);
170  double sinPsi = sin(yaw);
171 
172  dcm[0][0] = cosThe * cosPsi;
173  dcm[0][1] = -cosPhi * sinPsi + sinPhi * sinThe * cosPsi;
174  dcm[0][2] = sinPhi * sinPsi + cosPhi * sinThe * cosPsi;
175 
176  dcm[1][0] = cosThe * sinPsi;
177  dcm[1][1] = cosPhi * cosPsi + sinPhi * sinThe * sinPsi;
178  dcm[1][2] = -sinPhi * cosPsi + cosPhi * sinThe * sinPsi;
179 
180  dcm[2][0] = -sinThe;
181  dcm[2][1] = sinPhi * cosThe;
182  dcm[2][2] = cosPhi * cosThe;
183 }
184 
185 #endif