eulers.cpp 8.3 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232233234235236237238239240241242243244245246247248249250251252253254255256257258259260261262263264265266267268269270271272273274275276277278279280281282283284285286287288289290291292293294295296297298299300301302303304305306
  1. //
  2. // Unit tests for the AP_Math euler code
  3. //
  4. #include <AP_HAL/AP_HAL.h>
  5. #include <AP_Math/AP_Math.h>
  6. void setup();
  7. void loop();
  8. void test_matrix_rotate(void);
  9. void test_frame_transforms(void);
  10. void test_conversions(void);
  11. void test_quaternion_eulers(void);
  12. void test_matrix_eulers(void);
  13. const AP_HAL::HAL& hal = AP_HAL::get_HAL();
  14. #define SHOW_POLES_BREAKDOWN 0
  15. static float rad_diff(float rad1, float rad2)
  16. {
  17. float diff = rad1 - rad2;
  18. if (diff > M_PI) {
  19. diff -= 2 * M_PI;
  20. }
  21. if (diff < -M_PI) {
  22. diff += 2 * M_PI;
  23. }
  24. return fabsf(diff);
  25. }
  26. static void check_result(const char *msg,
  27. float roll, float pitch, float yaw,
  28. float roll2, float pitch2, float yaw2)
  29. {
  30. if (isnan(roll2) ||
  31. isnan(pitch2) ||
  32. isnan(yaw2)) {
  33. hal.console->printf("%s NAN eulers roll=%f pitch=%f yaw=%f\n",
  34. msg,
  35. (double)roll,
  36. (double)pitch,
  37. (double)yaw);
  38. }
  39. if (rad_diff(roll2,roll) > ToRad(179)) {
  40. // reverse all 3
  41. roll2 += fmodf(roll2 + M_PI, 2 * M_PI);
  42. pitch2 += fmodf(pitch2 + M_PI, 2 * M_PI);
  43. yaw2 += fmodf(yaw2 + M_PI, 2 * M_PI);
  44. }
  45. if (rad_diff(roll2,roll) > 0.01f ||
  46. rad_diff(pitch2, pitch) > 0.01f ||
  47. rad_diff(yaw2, yaw) > 0.01f) {
  48. if (pitch >= M_PI/2 ||
  49. pitch <= -M_PI/2 ||
  50. ToDeg(rad_diff(pitch, M_PI/2)) < 1 ||
  51. ToDeg(rad_diff(pitch, -M_PI/2)) < 1) {
  52. // we expect breakdown at these poles
  53. #if SHOW_POLES_BREAKDOWN
  54. hal.console->printf(
  55. "%s breakdown eulers roll=%f/%f pitch=%f/%f yaw=%f/%f\n",
  56. msg,
  57. (double)ToDeg(roll), (double)ToDeg(roll2),
  58. (double)ToDeg(pitch), (double)ToDeg(pitch2),
  59. (double)ToDeg(yaw), (double)ToDeg(yaw2));
  60. #endif
  61. } else {
  62. hal.console->printf(
  63. "%s incorrect eulers roll=%f/%f pitch=%f/%f yaw=%f/%f\n",
  64. msg,
  65. (double)ToDeg(roll), (double)ToDeg(roll2),
  66. (double)ToDeg(pitch), (double)ToDeg(pitch2),
  67. (double)ToDeg(yaw), (double)ToDeg(yaw2));
  68. }
  69. }
  70. }
  71. static void test_euler(float roll, float pitch, float yaw)
  72. {
  73. Matrix3f m;
  74. float roll2, pitch2, yaw2;
  75. m.from_euler(roll, pitch, yaw);
  76. m.to_euler(&roll2, &pitch2, &yaw2);
  77. check_result("test_euler", roll, pitch, yaw, roll2, pitch2, yaw2);
  78. }
  79. static const float angles[] = { 0, M_PI/8, M_PI/4, M_PI/2, M_PI,
  80. -M_PI/8, -M_PI/4, -M_PI/2, -M_PI};
  81. void test_matrix_eulers(void)
  82. {
  83. uint8_t N = ARRAY_SIZE(angles);
  84. hal.console->printf("rotation matrix unit tests\n\n");
  85. for (uint8_t i = 0; i < N; i++)
  86. for (uint8_t j = 0; j < N; j++)
  87. for (uint8_t k = 0; k < N; k++)
  88. test_euler(angles[i], angles[j], angles[k]);
  89. hal.console->printf("tests done\n\n");
  90. }
  91. static void test_quaternion(float roll, float pitch, float yaw)
  92. {
  93. Quaternion q;
  94. Matrix3f m;
  95. float roll2, pitch2, yaw2;
  96. q.from_euler(roll, pitch, yaw);
  97. q.to_euler(roll2, pitch2, yaw2);
  98. check_result("test_quaternion1", roll, pitch, yaw, roll2, pitch2, yaw2);
  99. m.from_euler(roll, pitch, yaw);
  100. m.to_euler(&roll2, &pitch2, &yaw2);
  101. check_result("test_quaternion2", roll, pitch, yaw, roll2, pitch2, yaw2);
  102. m.from_euler(roll, pitch, yaw);
  103. q.from_rotation_matrix(m);
  104. q.to_euler(roll2, pitch2, yaw2);
  105. check_result("test_quaternion3", roll, pitch, yaw, roll2, pitch2, yaw2);
  106. q.rotation_matrix(m);
  107. m.to_euler(&roll2, &pitch2, &yaw2);
  108. check_result("test_quaternion4", roll, pitch, yaw, roll2, pitch2, yaw2);
  109. }
  110. void test_quaternion_eulers(void)
  111. {
  112. uint8_t N = ARRAY_SIZE(angles);
  113. hal.console->printf("quaternion unit tests\n\n");
  114. test_quaternion(M_PI/4, 0, 0);
  115. test_quaternion(0, M_PI/4, 0);
  116. test_quaternion(0, 0, M_PI/4);
  117. test_quaternion(-M_PI/4, 0, 0);
  118. test_quaternion(0, -M_PI/4, 0);
  119. test_quaternion(0, 0, -M_PI/4);
  120. test_quaternion(-M_PI/4, 1, 1);
  121. test_quaternion(1, -M_PI/4, 1);
  122. test_quaternion(1, 1, -M_PI/4);
  123. test_quaternion(ToRad(89), 0, 0.1f);
  124. test_quaternion(0, ToRad(89), 0.1f);
  125. test_quaternion(0.1f, 0, ToRad(89));
  126. test_quaternion(ToRad(91), 0, 0.1f);
  127. test_quaternion(0, ToRad(91), 0.1f);
  128. test_quaternion(0.1f, 0, ToRad(91));
  129. for (uint8_t i = 0; i < N; i++)
  130. for (uint8_t j = 0; j < N; j++)
  131. for (uint8_t k = 0; k < N; k++)
  132. test_quaternion(angles[i], angles[j], angles[k]);
  133. hal.console->printf("tests done\n\n");
  134. }
  135. static void test_conversion(float roll, float pitch, float yaw)
  136. {
  137. Quaternion q;
  138. Matrix3f m, m2;
  139. float roll2, pitch2, yaw2;
  140. float roll3, pitch3, yaw3;
  141. q.from_euler(roll, pitch, yaw);
  142. q.to_euler(roll2, pitch2, yaw2);
  143. check_result("test_conversion1", roll, pitch, yaw, roll2, pitch2, yaw2);
  144. q.rotation_matrix(m);
  145. m.to_euler(&roll2, &pitch2, &yaw2);
  146. m2.from_euler(roll, pitch, yaw);
  147. m2.to_euler(&roll3, &pitch3, &yaw3);
  148. if (m.is_nan()) {
  149. hal.console->printf("NAN matrix roll=%f pitch=%f yaw=%f\n",
  150. (double)roll,
  151. (double)pitch,
  152. (double)yaw);
  153. }
  154. check_result("test_conversion2", roll, pitch, yaw, roll2, pitch2, yaw2);
  155. check_result("test_conversion3", roll, pitch, yaw, roll3, pitch3, yaw3);
  156. }
  157. void test_conversions(void)
  158. {
  159. uint8_t N = ARRAY_SIZE(angles);
  160. hal.console->printf("matrix/quaternion tests\n\n");
  161. test_conversion(1, 1.1f, 1.2f);
  162. test_conversion(1, -1.1f, 1.2f);
  163. test_conversion(1, -1.1f, -1.2f);
  164. test_conversion(-1, 1.1f, -1.2f);
  165. test_conversion(-1, 1.1f, 1.2f);
  166. for (uint8_t i = 0; i < N; i++)
  167. for (uint8_t j = 0; j < N; j++)
  168. for (uint8_t k = 0; k < N; k++)
  169. test_conversion(angles[i], angles[j], angles[k]);
  170. hal.console->printf("tests done\n\n");
  171. }
  172. void test_frame_transforms(void)
  173. {
  174. Vector3f v, v2;
  175. Quaternion q;
  176. Matrix3f m;
  177. hal.console->printf("frame transform tests\n\n");
  178. q.from_euler(ToRad(45), ToRad(45), ToRad(45));
  179. q.normalize();
  180. m.from_euler(ToRad(45), ToRad(45), ToRad(45));
  181. v2 = v = Vector3f(0.0f, 0.0f, 1.0f);
  182. q.earth_to_body(v2);
  183. hal.console->printf("%f %f %f\n", (double)v2.x, (double)v2.y, (double)v2.z);
  184. v2 = m * v;
  185. hal.console->printf("%f %f %f\n\n", (double)v2.x, (double)v2.y, (double)v2.z);
  186. v2 = v = Vector3f(0.0f, 1.0f, 0.0f);
  187. q.earth_to_body(v2);
  188. hal.console->printf("%f %f %f\n", (double)v2.x, (double)v2.y, (double)v2.z);
  189. v2 = m * v;
  190. hal.console->printf("%f %f %f\n\n", (double)v2.x, (double)v2.y, (double)v2.z);
  191. v2 = v = Vector3f(1.0f, 0.0f, 0.0f);
  192. q.earth_to_body(v2);
  193. hal.console->printf("%f %f %f\n", (double)v2.x, (double)v2.y, (double)v2.z);
  194. v2 = m * v;
  195. hal.console->printf("%f %f %f\n", (double)v2.x, (double)v2.y, (double)v2.z);
  196. }
  197. // generate a random float between -1 and 1
  198. static float rand_num(void)
  199. {
  200. return ((2.0f * get_random16()) / 0xFFFF) - 1.0f;
  201. }
  202. void test_matrix_rotate(void)
  203. {
  204. Matrix3f m1, m2, diff;
  205. Vector3f r;
  206. m1.identity();
  207. m2.identity();
  208. r.x = rand_num();
  209. r.y = rand_num();
  210. r.z = rand_num();
  211. for (uint16_t i = 0; i < 1000; i++) {
  212. // old method
  213. Matrix3f temp_matrix;
  214. temp_matrix.a.x = 0;
  215. temp_matrix.a.y = -r.z;
  216. temp_matrix.a.z = r.y;
  217. temp_matrix.b.x = r.z;
  218. temp_matrix.b.y = 0;
  219. temp_matrix.b.z = -r.x;
  220. temp_matrix.c.x = -r.y;
  221. temp_matrix.c.y = r.x;
  222. temp_matrix.c.z = 0;
  223. temp_matrix = m1 * temp_matrix;
  224. m1 += temp_matrix;
  225. // new method
  226. m2.rotate(r);
  227. // check they behave in the same way
  228. diff = m1 - m2;
  229. float err = diff.a.length() + diff.b.length() + diff.c.length();
  230. if (err > 0) {
  231. hal.console->printf("ERROR: i=%u err=%f\n", (unsigned)i, (double)err);
  232. }
  233. }
  234. }
  235. /*
  236. * euler angle tests
  237. */
  238. void setup(void)
  239. {
  240. hal.console->printf("euler unit tests\n\n");
  241. test_conversion(0, M_PI, 0);
  242. test_frame_transforms();
  243. test_conversions();
  244. test_quaternion_eulers();
  245. test_matrix_eulers();
  246. test_matrix_rotate();
  247. }
  248. void loop(void) {}
  249. AP_HAL_MAIN();