location.cpp 11 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232233234235236237238239240241242243244245246247248249250251252253254255256257258259260261262263264265266267268269270271272273274275276277278279280281282283284285286287288289290291292293294295296297298299300301302303304305306307308309310311312313314315316317318319320321322323324325326327328329330331332333334335336337338339340341342343
  1. //
  2. // Unit tests for the AP_Math polygon code
  3. //
  4. #define ALLOW_DOUBLE_MATH_FUNCTIONS
  5. #include <AP_HAL/AP_HAL.h>
  6. #include <AP_Math/AP_Math.h>
  7. #include <AP_Common/Location.h>
  8. void setup();
  9. void loop();
  10. const AP_HAL::HAL& hal = AP_HAL::get_HAL();
  11. static const struct {
  12. Vector2f wp1, wp2, location;
  13. bool passed;
  14. } test_points[] = {
  15. { Vector2f(-35.3647759314918f, 149.16265692810987f),
  16. Vector2f(-35.36279922658029f, 149.16352169591426f),
  17. Vector2f(-35.36214956969903f, 149.16461410046492f), true },
  18. { Vector2f(-35.36438601157189f, 149.16613916088568f),
  19. Vector2f(-35.364432558610254f, 149.16287313113048f),
  20. Vector2f(-35.36491510034746f, 149.16365837225004f), false },
  21. { Vector2f(0.0f, 0.0f),
  22. Vector2f(0.0f, 1.0f),
  23. Vector2f(0.0f, 2.0f), true },
  24. { Vector2f(0.0f, 0.0f),
  25. Vector2f(0.0f, 2.0f),
  26. Vector2f(0.0f, 1.0f), false },
  27. { Vector2f(0.0f, 0.0f),
  28. Vector2f(1.0f, 0.0f),
  29. Vector2f(2.0f, 0.0f), true },
  30. { Vector2f(0.0f, 0.0f),
  31. Vector2f(2.0f, 0.0f),
  32. Vector2f(1.0f, 0.0f), false },
  33. { Vector2f(0.0f, 0.0f),
  34. Vector2f(-1.0f, 1.0f),
  35. Vector2f(-2.0f, 2.0f), true },
  36. };
  37. static struct Location location_from_point(Vector2f pt)
  38. {
  39. struct Location loc = {};
  40. loc.lat = pt.x * 1.0e7f;
  41. loc.lng = pt.y * 1.0e7f;
  42. return loc;
  43. }
  44. static void test_passed_waypoint(void)
  45. {
  46. hal.console->printf("waypoint tests starting\n");
  47. for (uint8_t i = 0; i < ARRAY_SIZE(test_points); i++) {
  48. struct Location loc = location_from_point(test_points[i].location);
  49. struct Location wp1 = location_from_point(test_points[i].wp1);
  50. struct Location wp2 = location_from_point(test_points[i].wp2);
  51. if (loc.past_interval_finish_line(wp1, wp2) != test_points[i].passed) {
  52. hal.console->printf("Failed waypoint test %u\n", (unsigned)i);
  53. return;
  54. }
  55. }
  56. hal.console->printf("waypoint tests OK\n");
  57. }
  58. static void test_one_offset(const struct Location &loc,
  59. float ofs_north, float ofs_east,
  60. float dist, float bearing)
  61. {
  62. struct Location loc2;
  63. float dist2, bearing2;
  64. loc2 = loc;
  65. uint32_t t1 = AP_HAL::micros();
  66. loc2.offset(ofs_north, ofs_east);
  67. hal.console->printf("location_offset took %u usec\n",
  68. (unsigned)(AP_HAL::micros() - t1));
  69. dist2 = loc.get_distance(loc2);
  70. bearing2 = loc.get_bearing_to(loc2) * 0.01f;
  71. float brg_error = bearing2-bearing;
  72. if (brg_error > 180) {
  73. brg_error -= 360;
  74. } else if (brg_error < -180) {
  75. brg_error += 360;
  76. }
  77. if (fabsf(dist - dist2) > 1.0f ||
  78. brg_error > 1.0f) {
  79. hal.console->printf("Failed offset test brg_error=%f dist_error=%f\n",
  80. (double)brg_error, (double)(dist - dist2));
  81. }
  82. }
  83. static const struct {
  84. float ofs_north, ofs_east, distance, bearing;
  85. } test_offsets[] = {
  86. { 1000.0f, 1000.0f, sqrtf(2.0f) * 1000.0f, 45.0f },
  87. { 1000.0f, -1000.0f, sqrtf(2.0f) * 1000.0f, -45.0f },
  88. { 1000.0f, 0.0f, 1000.0f, 0.0f },
  89. { 0.0f, 1000.0f, 1000.0f, 90.0f },
  90. };
  91. static void test_offset(void)
  92. {
  93. struct Location loc {};
  94. loc.lat = -35 * 1.0e7f;
  95. loc.lng = 149 * 1.0e7f;
  96. for (uint8_t i = 0; i < ARRAY_SIZE(test_offsets); i++) {
  97. test_one_offset(loc,
  98. test_offsets[i].ofs_north,
  99. test_offsets[i].ofs_east,
  100. test_offsets[i].distance,
  101. test_offsets[i].bearing);
  102. }
  103. }
  104. /*
  105. test position accuracy for floating point versus integer positions
  106. */
  107. static void test_accuracy(void)
  108. {
  109. struct Location loc {};
  110. loc.lat = 0.0e7f;
  111. loc.lng = -120.0e7f;
  112. struct Location loc2 = loc;
  113. Vector2f v((loc.lat * 1.0e-7f), (loc.lng* 1.0e-7f));
  114. Vector2f v2;
  115. loc2 = loc;
  116. loc2.lat += 10000000;
  117. v2 = Vector2f(loc2.lat * 1.0e-7f, loc2.lng * 1.0e-7f);
  118. hal.console->printf("1 degree lat dist=%.4f\n", (double)loc.get_distance(loc2));
  119. loc2 = loc;
  120. loc2.lng += 10000000;
  121. v2 = Vector2f(loc2.lat * 1.0e-7f, loc2.lng * 1.0e-7f);
  122. hal.console->printf("1 degree lng dist=%.4f\n", (double)loc.get_distance(loc2));
  123. for (int32_t i = 0; i < 100; i++) {
  124. loc2 = loc;
  125. loc2.lat += i;
  126. v2 = Vector2f((loc.lat + i) * 1.0e-7f, loc.lng * 1.0e-7f);
  127. if (v2 != v) {
  128. hal.console->printf("lat v2 != v at i=%d dist=%.4f\n", (int)i, (double)loc.get_distance(loc2));
  129. break;
  130. }
  131. }
  132. for (int32_t i = 0; i < 100; i++) {
  133. loc2 = loc;
  134. loc2.lng += i;
  135. v2 = Vector2f(loc.lat * 1.0e-7f, (loc.lng + i) * 1.0e-7f);
  136. if (v2 != v) {
  137. hal.console->printf("lng v2 != v at i=%d dist=%.4f\n", (int)i, (double)loc.get_distance(loc2));
  138. break;
  139. }
  140. }
  141. for (int32_t i = 0; i < 100; i++) {
  142. loc2 = loc;
  143. loc2.lat -= i;
  144. v2 = Vector2f((loc.lat - i) * 1.0e-7f, loc.lng * 1.0e-7f);
  145. if (v2 != v) {
  146. hal.console->printf("-lat v2 != v at i=%d dist=%.4f\n", (int)i, (double)loc.get_distance(loc2));
  147. break;
  148. }
  149. }
  150. for (int32_t i = 0; i < 100; i++) {
  151. loc2 = loc;
  152. loc2.lng -= i;
  153. v2 = Vector2f(loc.lat * 1.0e-7f, (loc.lng - i) * 1.0e-7f);
  154. if (v2 != v) {
  155. hal.console->printf("-lng v2 != v at i=%d dist=%.4f\n", (int)i, (double)loc.get_distance(loc2));
  156. break;
  157. }
  158. }
  159. }
  160. static const struct {
  161. int32_t v, wv;
  162. } wrap_180_tests[] = {
  163. { 32000, -4000 },
  164. { 1500 + 100*36000, 1500 },
  165. { -1500 - 100*36000, -1500 },
  166. };
  167. static const struct {
  168. int32_t v, wv;
  169. } wrap_360_tests[] = {
  170. { 32000, 32000 },
  171. { 1500 + 100*36000, 1500 },
  172. { -1500 - 100*36000, 34500 },
  173. };
  174. static const struct {
  175. float v, wv;
  176. } wrap_PI_tests[] = {
  177. { 0.2f*M_PI, 0.2f*M_PI },
  178. { 0.2f*M_PI + 100*M_PI, 0.2f*M_PI },
  179. { -0.2f*M_PI - 100*M_PI, -0.2f*M_PI },
  180. };
  181. static void test_wrap_cd(void)
  182. {
  183. for (uint8_t i = 0; i < ARRAY_SIZE(wrap_180_tests); i++) {
  184. int32_t r = wrap_180_cd(wrap_180_tests[i].v);
  185. if (r != wrap_180_tests[i].wv) {
  186. hal.console->printf("wrap_180: v=%ld wv=%ld r=%ld\n",
  187. (long)wrap_180_tests[i].v,
  188. (long)wrap_180_tests[i].wv,
  189. (long)r);
  190. }
  191. }
  192. for (uint8_t i = 0; i < ARRAY_SIZE(wrap_360_tests); i++) {
  193. int32_t r = wrap_360_cd(wrap_360_tests[i].v);
  194. if (r != wrap_360_tests[i].wv) {
  195. hal.console->printf("wrap_360: v=%ld wv=%ld r=%ld\n",
  196. (long)wrap_360_tests[i].v,
  197. (long)wrap_360_tests[i].wv,
  198. (long)r);
  199. }
  200. }
  201. for (uint8_t i = 0; i < ARRAY_SIZE(wrap_PI_tests); i++) {
  202. float r = wrap_PI(wrap_PI_tests[i].v);
  203. if (fabsf(r - wrap_PI_tests[i].wv) > 0.001f) {
  204. hal.console->printf("wrap_PI: v=%f wv=%f r=%f\n",
  205. (double)wrap_PI_tests[i].v,
  206. (double)wrap_PI_tests[i].wv,
  207. (double)r);
  208. }
  209. }
  210. hal.console->printf("wrap_cd tests done\n");
  211. }
  212. static void test_wgs_conversion_functions(void)
  213. {
  214. #define D2R DEG_TO_RAD_DOUBLE
  215. /* Maximum allowable error in quantities with units of length (in meters). */
  216. static const double MAX_DIST_ERROR_M = 1e-6;
  217. /* Maximum allowable error in quantities with units of angle (in sec of arc).
  218. * 1 second of arc on the equator is ~31 meters. */
  219. static const double MAX_ANGLE_ERROR_SEC = 1e-7;
  220. static const double MAX_ANGLE_ERROR_RAD = (MAX_ANGLE_ERROR_SEC * (D2R / (double)3600.0));
  221. /* Semi-major axis. */
  222. static const double EARTH_A = 6378137.0;
  223. /* Semi-minor axis. */
  224. static const double EARTH_B = 6356752.31424517929553985595703125;
  225. #define NUM_COORDS 10
  226. Vector3d llhs[NUM_COORDS];
  227. llhs[0] = Vector3d(0, 0, 0); /* On the Equator and Prime Meridian. */
  228. llhs[1] = Vector3d(0, 180*D2R, 0); /* On the Equator. */
  229. llhs[2] = Vector3d(0, 90*D2R, 0); /* On the Equator. */
  230. llhs[3] = Vector3d(0, -90*D2R, 0); /* On the Equator. */
  231. llhs[4] = Vector3d(90*D2R, 0, 0); /* North pole. */
  232. llhs[5] = Vector3d(-90*D2R, 0, 0); /* South pole. */
  233. llhs[6] = Vector3d(90*D2R, 0, 22); /* 22m above the north pole. */
  234. llhs[7] = Vector3d(-90*D2R, 0, 22); /* 22m above the south pole. */
  235. llhs[8] = Vector3d(0, 0, 22); /* 22m above the Equator and Prime Meridian. */
  236. llhs[9] = Vector3d(0, 180*D2R, 22); /* 22m above the Equator. */
  237. Vector3d ecefs[NUM_COORDS];
  238. ecefs[0] = Vector3d(EARTH_A, 0, 0);
  239. ecefs[1] = Vector3d(-EARTH_A, 0, 0);
  240. ecefs[2] = Vector3d(0, EARTH_A, 0);
  241. ecefs[3] = Vector3d(0, -EARTH_A, 0);
  242. ecefs[4] = Vector3d(0, 0, EARTH_B);
  243. ecefs[5] = Vector3d(0, 0, -EARTH_B);
  244. ecefs[6] = Vector3d(0, 0, (EARTH_B+22));
  245. ecefs[7] = Vector3d(0, 0, -(EARTH_B+22));
  246. ecefs[8] = Vector3d((22+EARTH_A), 0, 0);
  247. ecefs[9] = Vector3d(-(22+EARTH_A), 0, 0);
  248. hal.console->printf("TESTING wgsllh2ecef\n");
  249. for (int i = 0; i < NUM_COORDS; i++) {
  250. Vector3d ecef;
  251. wgsllh2ecef(llhs[i], ecef);
  252. double x_err = fabs(ecef[0] - ecefs[i][0]);
  253. double y_err = fabs(ecef[1] - ecefs[i][1]);
  254. double z_err = fabs(ecef[2] - ecefs[i][2]);
  255. if ((x_err < MAX_DIST_ERROR_M) &&
  256. (y_err < MAX_DIST_ERROR_M) &&
  257. (z_err < MAX_DIST_ERROR_M)) {
  258. hal.console->printf("passing llh to ecef test %d\n", i);
  259. } else {
  260. hal.console->printf("failed llh to ecef test %d: ", i);
  261. hal.console->printf("(%f - %f) (%f - %f) (%f - %f) => %.10f %.10f %.10f\n",
  262. ecef[0], ecefs[i][0], ecef[1], ecefs[i][1], ecef[2], ecefs[i][2], x_err, y_err, z_err);
  263. }
  264. }
  265. hal.console->printf("TESTING wgsecef2llh\n");
  266. for (int i = 0; i < NUM_COORDS; i++) {
  267. Vector3d llh;
  268. wgsecef2llh(ecefs[i], llh);
  269. double lat_err = fabs(llh[0] - llhs[i][0]);
  270. double lon_err = fabs(llh[1] - llhs[i][1]);
  271. double hgt_err = fabs(llh[2] - llhs[i][2]);
  272. if ((lat_err < MAX_ANGLE_ERROR_RAD) &&
  273. (lon_err < MAX_ANGLE_ERROR_RAD) &&
  274. (hgt_err < MAX_DIST_ERROR_M)) {
  275. hal.console->printf("passing exef to llh test %d\n", i);
  276. } else {
  277. hal.console->printf("failed ecef to llh test %d: ", i);
  278. hal.console->printf("%.10f %.10f %.10f\n", lat_err, lon_err, hgt_err);
  279. }
  280. }
  281. }
  282. /*
  283. * polygon tests
  284. */
  285. void setup(void)
  286. {
  287. test_passed_waypoint();
  288. test_offset();
  289. test_accuracy();
  290. test_wrap_cd();
  291. test_wgs_conversion_functions();
  292. hal.console->printf("ALL TESTS DONE\n");
  293. }
  294. void loop(void){}
  295. AP_HAL_MAIN();