mavlink_conversions.h 6.3 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212
  1. #pragma once
  2. #ifndef MAVLINK_NO_CONVERSION_HELPERS
  3. /* enable math defines on Windows */
  4. #ifdef _MSC_VER
  5. #ifndef _USE_MATH_DEFINES
  6. #define _USE_MATH_DEFINES
  7. #endif
  8. #endif
  9. #include <math.h>
  10. #ifndef M_PI_2
  11. #define M_PI_2 ((float)asin(1))
  12. #endif
  13. /**
  14. * @file mavlink_conversions.h
  15. *
  16. * These conversion functions follow the NASA rotation standards definition file
  17. * available online.
  18. *
  19. * Their intent is to lower the barrier for MAVLink adopters to use gimbal-lock free
  20. * (both rotation matrices, sometimes called DCM, and quaternions are gimbal-lock free)
  21. * rotation representations. Euler angles (roll, pitch, yaw) will be phased out of the
  22. * protocol as widely as possible.
  23. *
  24. * @author James Goppert
  25. * @author Thomas Gubler <thomasgubler@gmail.com>
  26. */
  27. /**
  28. * Converts a quaternion to a rotation matrix
  29. *
  30. * @param quaternion a [w, x, y, z] ordered quaternion (null-rotation being 1 0 0 0)
  31. * @param dcm a 3x3 rotation matrix
  32. */
  33. MAVLINK_HELPER void mavlink_quaternion_to_dcm(const float quaternion[4], float dcm[3][3])
  34. {
  35. double a = (double)quaternion[0];
  36. double b = (double)quaternion[1];
  37. double c = (double)quaternion[2];
  38. double d = (double)quaternion[3];
  39. double aSq = a * a;
  40. double bSq = b * b;
  41. double cSq = c * c;
  42. double dSq = d * d;
  43. dcm[0][0] = aSq + bSq - cSq - dSq;
  44. dcm[0][1] = 2 * (b * c - a * d);
  45. dcm[0][2] = 2 * (a * c + b * d);
  46. dcm[1][0] = 2 * (b * c + a * d);
  47. dcm[1][1] = aSq - bSq + cSq - dSq;
  48. dcm[1][2] = 2 * (c * d - a * b);
  49. dcm[2][0] = 2 * (b * d - a * c);
  50. dcm[2][1] = 2 * (a * b + c * d);
  51. dcm[2][2] = aSq - bSq - cSq + dSq;
  52. }
  53. /**
  54. * Converts a rotation matrix to euler angles
  55. *
  56. * @param dcm a 3x3 rotation matrix
  57. * @param roll the roll angle in radians
  58. * @param pitch the pitch angle in radians
  59. * @param yaw the yaw angle in radians
  60. */
  61. MAVLINK_HELPER void mavlink_dcm_to_euler(const float dcm[3][3], float* roll, float* pitch, float* yaw)
  62. {
  63. float phi, theta, psi;
  64. theta = asinf(-dcm[2][0]);
  65. if (fabsf(theta - (float)M_PI_2) < 1.0e-3f) {
  66. phi = 0.0f;
  67. psi = (atan2f(dcm[1][2] - dcm[0][1],
  68. dcm[0][2] + dcm[1][1]) + phi);
  69. } else if (fabsf(theta + (float)M_PI_2) < 1.0e-3f) {
  70. phi = 0.0f;
  71. psi = atan2f(dcm[1][2] - dcm[0][1],
  72. dcm[0][2] + dcm[1][1] - phi);
  73. } else {
  74. phi = atan2f(dcm[2][1], dcm[2][2]);
  75. psi = atan2f(dcm[1][0], dcm[0][0]);
  76. }
  77. *roll = phi;
  78. *pitch = theta;
  79. *yaw = psi;
  80. }
  81. /**
  82. * Converts a quaternion to euler angles
  83. *
  84. * @param quaternion a [w, x, y, z] ordered quaternion (null-rotation being 1 0 0 0)
  85. * @param roll the roll angle in radians
  86. * @param pitch the pitch angle in radians
  87. * @param yaw the yaw angle in radians
  88. */
  89. MAVLINK_HELPER void mavlink_quaternion_to_euler(const float quaternion[4], float* roll, float* pitch, float* yaw)
  90. {
  91. float dcm[3][3];
  92. mavlink_quaternion_to_dcm(quaternion, dcm);
  93. mavlink_dcm_to_euler((const float(*)[3])dcm, roll, pitch, yaw);
  94. }
  95. /**
  96. * Converts euler angles to a quaternion
  97. *
  98. * @param roll the roll angle in radians
  99. * @param pitch the pitch angle in radians
  100. * @param yaw the yaw angle in radians
  101. * @param quaternion a [w, x, y, z] ordered quaternion (null-rotation being 1 0 0 0)
  102. */
  103. MAVLINK_HELPER void mavlink_euler_to_quaternion(float roll, float pitch, float yaw, float quaternion[4])
  104. {
  105. float cosPhi_2 = cosf(roll / 2);
  106. float sinPhi_2 = sinf(roll / 2);
  107. float cosTheta_2 = cosf(pitch / 2);
  108. float sinTheta_2 = sinf(pitch / 2);
  109. float cosPsi_2 = cosf(yaw / 2);
  110. float sinPsi_2 = sinf(yaw / 2);
  111. quaternion[0] = (cosPhi_2 * cosTheta_2 * cosPsi_2 +
  112. sinPhi_2 * sinTheta_2 * sinPsi_2);
  113. quaternion[1] = (sinPhi_2 * cosTheta_2 * cosPsi_2 -
  114. cosPhi_2 * sinTheta_2 * sinPsi_2);
  115. quaternion[2] = (cosPhi_2 * sinTheta_2 * cosPsi_2 +
  116. sinPhi_2 * cosTheta_2 * sinPsi_2);
  117. quaternion[3] = (cosPhi_2 * cosTheta_2 * sinPsi_2 -
  118. sinPhi_2 * sinTheta_2 * cosPsi_2);
  119. }
  120. /**
  121. * Converts a rotation matrix to a quaternion
  122. * Reference:
  123. * - Shoemake, Quaternions,
  124. * http://www.cs.ucr.edu/~vbz/resources/quatut.pdf
  125. *
  126. * @param dcm a 3x3 rotation matrix
  127. * @param quaternion a [w, x, y, z] ordered quaternion (null-rotation being 1 0 0 0)
  128. */
  129. MAVLINK_HELPER void mavlink_dcm_to_quaternion(const float dcm[3][3], float quaternion[4])
  130. {
  131. float tr = dcm[0][0] + dcm[1][1] + dcm[2][2];
  132. if (tr > 0.0f) {
  133. float s = sqrtf(tr + 1.0f);
  134. quaternion[0] = s * 0.5f;
  135. s = 0.5f / s;
  136. quaternion[1] = (dcm[2][1] - dcm[1][2]) * s;
  137. quaternion[2] = (dcm[0][2] - dcm[2][0]) * s;
  138. quaternion[3] = (dcm[1][0] - dcm[0][1]) * s;
  139. } else {
  140. /* Find maximum diagonal element in dcm
  141. * store index in dcm_i */
  142. int dcm_i = 0;
  143. int i;
  144. for (i = 1; i < 3; i++) {
  145. if (dcm[i][i] > dcm[dcm_i][dcm_i]) {
  146. dcm_i = i;
  147. }
  148. }
  149. int dcm_j = (dcm_i + 1) % 3;
  150. int dcm_k = (dcm_i + 2) % 3;
  151. float s = sqrtf((dcm[dcm_i][dcm_i] - dcm[dcm_j][dcm_j] -
  152. dcm[dcm_k][dcm_k]) + 1.0f);
  153. quaternion[dcm_i + 1] = s * 0.5f;
  154. s = 0.5f / s;
  155. quaternion[dcm_j + 1] = (dcm[dcm_i][dcm_j] + dcm[dcm_j][dcm_i]) * s;
  156. quaternion[dcm_k + 1] = (dcm[dcm_k][dcm_i] + dcm[dcm_i][dcm_k]) * s;
  157. quaternion[0] = (dcm[dcm_k][dcm_j] - dcm[dcm_j][dcm_k]) * s;
  158. }
  159. }
  160. /**
  161. * Converts euler angles to a rotation matrix
  162. *
  163. * @param roll the roll angle in radians
  164. * @param pitch the pitch angle in radians
  165. * @param yaw the yaw angle in radians
  166. * @param dcm a 3x3 rotation matrix
  167. */
  168. MAVLINK_HELPER void mavlink_euler_to_dcm(float roll, float pitch, float yaw, float dcm[3][3])
  169. {
  170. float cosPhi = cosf(roll);
  171. float sinPhi = sinf(roll);
  172. float cosThe = cosf(pitch);
  173. float sinThe = sinf(pitch);
  174. float cosPsi = cosf(yaw);
  175. float sinPsi = sinf(yaw);
  176. dcm[0][0] = cosThe * cosPsi;
  177. dcm[0][1] = -cosPhi * sinPsi + sinPhi * sinThe * cosPsi;
  178. dcm[0][2] = sinPhi * sinPsi + cosPhi * sinThe * cosPsi;
  179. dcm[1][0] = cosThe * sinPsi;
  180. dcm[1][1] = cosPhi * cosPsi + sinPhi * sinThe * sinPsi;
  181. dcm[1][2] = -sinPhi * cosPsi + cosPhi * sinThe * sinPsi;
  182. dcm[2][0] = -sinThe;
  183. dcm[2][1] = sinPhi * cosThe;
  184. dcm[2][2] = cosPhi * cosThe;
  185. }
  186. #endif // MAVLINK_NO_CONVERSION_HELPERS