rotations.cpp 9.2 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232233234235236237238239240241242243244245246247248249250251252253254255256257258259260261262263264265266267268269270271272273274275276277278279280281282283284285286287288289290291292293294295296297
  1. //
  2. // Unit tests for the AP_Math rotations code
  3. //
  4. #include <AP_HAL/AP_HAL.h>
  5. #include <AP_Math/AP_Math.h>
  6. void setup();
  7. void loop();
  8. const AP_HAL::HAL& hal = AP_HAL::get_HAL();
  9. static void print_vector(Vector3f &v)
  10. {
  11. hal.console->printf("[%.4f %.4f %.4f]\n",
  12. (double)v.x,
  13. (double)v.y,
  14. (double)v.z);
  15. }
  16. // test rotation method accuracy
  17. static void test_rotation_accuracy(void)
  18. {
  19. Matrix3f attitude;
  20. Vector3f small_rotation;
  21. float roll, pitch, yaw;
  22. float rot_angle;
  23. hal.console->printf("\nRotation method accuracy:\n");
  24. // test roll
  25. for(int16_t i = 0; i < 90; i++ ) {
  26. // reset initial attitude
  27. attitude.from_euler(0.0f, 0.0f, 0.0f);
  28. // calculate small rotation vector
  29. rot_angle = ToRad(i);
  30. small_rotation = Vector3f(rot_angle, 0.0f, 0.0f);
  31. // apply small rotation
  32. attitude.rotate(small_rotation);
  33. // get resulting attitude's euler angles
  34. attitude.to_euler(&roll, &pitch, &yaw);
  35. // now try via from_axis_angle
  36. Matrix3f r2;
  37. r2.from_axis_angle(Vector3f(1.0f, 0.0f, 0.0f), rot_angle);
  38. attitude.from_euler(0.0f, 0.0f, 0.0f);
  39. attitude = r2 * attitude;
  40. float roll2, pitch2, yaw2;
  41. attitude.to_euler(&roll2, &pitch2, &yaw2);
  42. // display results
  43. hal.console->printf("actual angle: %d angle1:%4.2f angle2:%4.2f\n",
  44. (int)i,
  45. (double)ToDeg(roll),
  46. (double)ToDeg(roll2));
  47. }
  48. // test pitch
  49. for(int16_t i = 0; i < 90; i++ ) {
  50. // reset initial attitude
  51. attitude.from_euler(0.0f, 0.0f, 0.0f);
  52. // calculate small rotation vector
  53. rot_angle = ToRad(i);
  54. small_rotation = Vector3f(0.0f ,rot_angle, 0.0f);
  55. // apply small rotation
  56. attitude.rotate(small_rotation);
  57. // get resulting attitude's euler angles
  58. attitude.to_euler(&roll, &pitch, &yaw);
  59. // now try via from_axis_angle
  60. Matrix3f r2;
  61. r2.from_axis_angle(Vector3f(0.0f ,1.0f, 0.0f), rot_angle);
  62. attitude.from_euler(0.0f, 0.0f, 0.0f);
  63. attitude = r2 * attitude;
  64. float roll2, pitch2, yaw2;
  65. attitude.to_euler(&roll2, &pitch2, &yaw2);
  66. // display results
  67. hal.console->printf("actual angle: %d angle1:%4.2f angle2:%4.2f\n",
  68. (int)i,
  69. (double)ToDeg(pitch),
  70. (double)ToDeg(pitch2));
  71. }
  72. // test yaw
  73. for(int16_t i = 0; i < 90; i++ ) {
  74. // reset initial attitude
  75. attitude.from_euler(0.0f, 0.0f, 0.0f);
  76. // calculate small rotation vector
  77. rot_angle = ToRad(i);
  78. small_rotation = Vector3f(0.0f, 0.0f, rot_angle);
  79. // apply small rotation
  80. attitude.rotate(small_rotation);
  81. // get resulting attitude's euler angles
  82. attitude.to_euler(&roll, &pitch, &yaw);
  83. // now try via from_axis_angle
  84. Matrix3f r2;
  85. r2.from_axis_angle(Vector3f(0.0f, 0.0f, 1.0f), rot_angle);
  86. attitude.from_euler(0.0f, 0.0f, 0.0f);
  87. attitude = r2 * attitude;
  88. float roll2, pitch2, yaw2;
  89. attitude.to_euler(&roll2, &pitch2, &yaw2);
  90. // display results
  91. hal.console->printf("actual angle: %d angle1:%4.2f angle2:%4.2f\n",
  92. (int)i,
  93. (double)ToDeg(yaw),
  94. (double)ToDeg(yaw2));
  95. }
  96. }
  97. static void test_euler(enum Rotation rotation, float roll, float pitch, float yaw)
  98. {
  99. Vector3f v, v1, v2, diff;
  100. Matrix3f rotmat;
  101. const float accuracy = 1.0e-6f;
  102. v.x = 1;
  103. v.y = 2;
  104. v.z = 3;
  105. v1 = v;
  106. v1.rotate(rotation);
  107. rotmat.from_euler(radians(roll), radians(pitch), radians(yaw));
  108. v2 = v;
  109. v2 = rotmat * v2;
  110. diff = (v2 - v1);
  111. if (diff.length() > accuracy) {
  112. hal.console->printf("euler test %u failed : yaw:%d roll:%d pitch:%d\n",
  113. (unsigned)rotation,
  114. (int)yaw,
  115. (int)roll,
  116. (int)pitch);
  117. hal.console->printf("fast rotated: ");
  118. print_vector(v1);
  119. hal.console->printf("slow rotated: ");
  120. print_vector(v2);
  121. hal.console->printf("\n");
  122. }
  123. }
  124. static void test_rotate_inverse(void)
  125. {
  126. hal.console->printf("\nrotate inverse test(Vector (1,1,1)):\n");
  127. Vector3f vec(1.0f,1.0f,1.0f), cmp_vec(1.0f, 1.0f, 1.0f);
  128. for (enum Rotation r = ROTATION_NONE;
  129. r < ROTATION_MAX;
  130. r = (enum Rotation)((uint8_t)r+1)) {
  131. hal.console->printf("\nROTATION(%d) ", r);
  132. vec.rotate(r);
  133. print_vector(vec);
  134. hal.console->printf("INV_ROTATION(%d)", r);
  135. vec.rotate_inverse(r);
  136. print_vector(vec);
  137. if ((vec - cmp_vec).length() > 1e-5) {
  138. hal.console->printf("Rotation Test Failed!!! %.8f\n", (double)(vec - cmp_vec).length());
  139. return;
  140. }
  141. }
  142. }
  143. static void test_eulers(void)
  144. {
  145. hal.console->printf("euler tests\n");
  146. test_euler(ROTATION_NONE, 0, 0, 0);
  147. test_euler(ROTATION_YAW_45, 0, 0, 45);
  148. test_euler(ROTATION_YAW_90, 0, 0, 90);
  149. test_euler(ROTATION_YAW_135, 0, 0, 135);
  150. test_euler(ROTATION_YAW_180, 0, 0, 180);
  151. test_euler(ROTATION_YAW_225, 0, 0, 225);
  152. test_euler(ROTATION_YAW_270, 0, 0, 270);
  153. test_euler(ROTATION_YAW_315, 0, 0, 315);
  154. test_euler(ROTATION_ROLL_180, 180, 0, 0);
  155. test_euler(ROTATION_ROLL_180_YAW_45, 180, 0, 45);
  156. test_euler(ROTATION_ROLL_180_YAW_90, 180, 0, 90);
  157. test_euler(ROTATION_ROLL_180_YAW_135, 180, 0, 135);
  158. test_euler(ROTATION_PITCH_180, 0, 180, 0);
  159. test_euler(ROTATION_ROLL_180_YAW_225, 180, 0, 225);
  160. test_euler(ROTATION_ROLL_180_YAW_270, 180, 0, 270);
  161. test_euler(ROTATION_ROLL_180_YAW_315, 180, 0, 315);
  162. test_euler(ROTATION_ROLL_90, 90, 0, 0);
  163. test_euler(ROTATION_ROLL_90_YAW_45, 90, 0, 45);
  164. test_euler(ROTATION_ROLL_90_YAW_90, 90, 0, 90);
  165. test_euler(ROTATION_ROLL_90_YAW_135, 90, 0, 135);
  166. test_euler(ROTATION_ROLL_270, 270, 0, 0);
  167. test_euler(ROTATION_ROLL_270_YAW_45, 270, 0, 45);
  168. test_euler(ROTATION_ROLL_270_YAW_90, 270, 0, 90);
  169. test_euler(ROTATION_ROLL_270_YAW_135, 270, 0, 135);
  170. test_euler(ROTATION_PITCH_90, 0, 90, 0);
  171. test_euler(ROTATION_PITCH_270, 0, 270, 0);
  172. test_euler(ROTATION_PITCH_180_YAW_90, 0, 180, 90);
  173. test_euler(ROTATION_PITCH_180_YAW_270, 0, 180, 270);
  174. test_euler(ROTATION_ROLL_90_PITCH_90, 90, 90, 0);
  175. test_euler(ROTATION_ROLL_180_PITCH_90,180, 90, 0);
  176. test_euler(ROTATION_ROLL_270_PITCH_90,270, 90, 0);
  177. test_euler(ROTATION_ROLL_90_PITCH_180, 90, 180, 0);
  178. test_euler(ROTATION_ROLL_270_PITCH_180,270,180, 0);
  179. test_euler(ROTATION_ROLL_90_PITCH_270, 90, 270, 0);
  180. test_euler(ROTATION_ROLL_180_PITCH_270,180,270, 0);
  181. test_euler(ROTATION_ROLL_270_PITCH_270,270,270, 0);
  182. test_euler(ROTATION_ROLL_90_PITCH_180_YAW_90, 90, 180, 90);
  183. test_euler(ROTATION_ROLL_90_YAW_270, 90, 0, 270);
  184. test_euler(ROTATION_ROLL_90_PITCH_68_YAW_293,90,68.8,293.3);
  185. test_euler(ROTATION_PITCH_7, 0, 7, 0);
  186. }
  187. static bool have_rotation(const Matrix3f &m)
  188. {
  189. Matrix3f mt = m.transposed();
  190. for (enum Rotation r = ROTATION_NONE;
  191. r < ROTATION_MAX;
  192. r = (enum Rotation)((uint8_t)(r + 1))) {
  193. Vector3f v(1.0f, 2.0f, 3.0f);
  194. Vector3f v2 = v;
  195. v2.rotate(r);
  196. v2 = mt * v2;
  197. if ((v2 - v).length() < 0.01f) {
  198. return true;
  199. }
  200. }
  201. return false;
  202. }
  203. static void missing_rotations(void)
  204. {
  205. hal.console->printf("testing for missing rotations\n");
  206. for (uint16_t yaw = 0; yaw < 360; yaw += 90)
  207. for (uint16_t pitch = 0; pitch < 360; pitch += 90)
  208. for (uint16_t roll = 0; roll < 360; roll += 90) {
  209. Matrix3f m;
  210. m.from_euler(ToRad(roll), ToRad(pitch), ToRad(yaw));
  211. if (!have_rotation(m)) {
  212. hal.console->printf("Missing rotation (%u, %u, %u)\n", roll, pitch, yaw);
  213. }
  214. }
  215. }
  216. static void test_rotate_matrix(void)
  217. {
  218. for (enum Rotation r = ROTATION_NONE;
  219. r < ROTATION_MAX;
  220. r = (enum Rotation)((uint8_t)r+1)) {
  221. //hal.console->printf("\nROTATION(%d)\n", r);
  222. Vector3f vec(1,2,3);
  223. Vector3f vec2 = vec;
  224. vec.rotate(r);
  225. Matrix3f m;
  226. m.from_rotation(r);
  227. vec2 = m * vec2;
  228. //print_vector(vec);
  229. //print_vector(vec2);
  230. if ((vec - vec2).length() > 1e-5) {
  231. hal.console->printf("Rotation Test Failed!!! %.8f\n", (double)(vec - vec2).length());
  232. return;
  233. }
  234. }
  235. hal.console->printf("test_rotate_matrix passed\n");
  236. }
  237. /*
  238. * rotation tests
  239. */
  240. void setup(void)
  241. {
  242. hal.console->begin(115200);
  243. hal.console->printf("rotation unit tests\n\n");
  244. test_rotation_accuracy();
  245. test_eulers();
  246. missing_rotations();
  247. test_rotate_inverse();
  248. test_rotate_matrix();
  249. hal.console->printf("rotation unit tests done\n\n");
  250. }
  251. void loop(void) {}
  252. AP_HAL_MAIN();