polygon.cpp 3.7 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113
  1. //
  2. // Unit tests for the AP_Math polygon 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. /*
  10. * this is the boundary of the 2010 outback challenge
  11. * Note that the last point must be the same as the first for the
  12. * Polygon_outside() algorithm
  13. */
  14. static const Vector2l OBC_boundary[] = {
  15. Vector2l(-265695640, 1518373730),
  16. Vector2l(-265699560, 1518394050),
  17. Vector2l(-265768230, 1518411420),
  18. Vector2l(-265773080, 1518403440),
  19. Vector2l(-265815110, 1518419500),
  20. Vector2l(-265784860, 1518474690),
  21. Vector2l(-265994890, 1518528860),
  22. Vector2l(-266092110, 1518747420),
  23. Vector2l(-266454780, 1518820530),
  24. Vector2l(-266435720, 1518303500),
  25. Vector2l(-265875990, 1518344050),
  26. Vector2l(-265695640, 1518373730)
  27. };
  28. static const struct {
  29. Vector2l point;
  30. bool outside;
  31. } test_points[] = {
  32. { Vector2l(-266398870, 1518220000), true },
  33. { Vector2l(-266418700, 1518709260), false },
  34. { Vector2l(-350000000, 1490000000), true },
  35. { Vector2l(0, 0), true },
  36. { Vector2l(-265768150, 1518408250), false },
  37. { Vector2l(-265774060, 1518405860), true },
  38. { Vector2l(-266435630, 1518303440), true },
  39. { Vector2l(-266435650, 1518313540), false },
  40. { Vector2l(-266435690, 1518303530), false },
  41. { Vector2l(-266435690, 1518303490), true },
  42. { Vector2l(-265875990, 1518344049), true },
  43. { Vector2l(-265875990, 1518344051), false },
  44. { Vector2l(-266454781, 1518820530), true },
  45. { Vector2l(-266454779, 1518820530), true },
  46. { Vector2l(-266092109, 1518747420), true },
  47. { Vector2l(-266092111, 1518747420), false },
  48. { Vector2l(-266092110, 1518747421), true },
  49. { Vector2l(-266092110, 1518747419), false },
  50. { Vector2l(-266092111, 1518747421), true },
  51. { Vector2l(-266092109, 1518747421), true },
  52. { Vector2l(-266092111, 1518747419), false },
  53. };
  54. /*
  55. * polygon tests
  56. */
  57. void setup(void)
  58. {
  59. uint32_t count;
  60. bool all_passed = true;
  61. uint32_t start_time;
  62. hal.console->printf("polygon unit tests\n\n");
  63. if (!Polygon_complete(OBC_boundary, ARRAY_SIZE(OBC_boundary))) {
  64. hal.console->printf("OBC boundary is not complete!\n");
  65. all_passed = false;
  66. }
  67. if (Polygon_complete(OBC_boundary, ARRAY_SIZE(OBC_boundary)-1)) {
  68. hal.console->printf("Polygon_complete test failed\n");
  69. all_passed = false;
  70. }
  71. for (uint32_t i = 0; i < ARRAY_SIZE(test_points); i++) {
  72. bool result = Polygon_outside(test_points[i].point,
  73. OBC_boundary, ARRAY_SIZE(OBC_boundary));
  74. hal.console->printf("%10f,%10f %s %s\n",
  75. (double)(1.0e-7f * test_points[i].point.x),
  76. (double)(1.0e-7f * test_points[i].point.y),
  77. result ? "OUTSIDE" : "INSIDE ",
  78. result == test_points[i].outside ? "PASS" : "FAIL");
  79. if (result != test_points[i].outside) {
  80. all_passed = false;
  81. }
  82. }
  83. hal.console->printf("%s\n", all_passed ? "TEST PASSED" : "TEST FAILED");
  84. hal.console->printf("Speed test:\n");
  85. start_time = AP_HAL::micros();
  86. for (count = 0; count < 1000; count++) {
  87. for (uint32_t i = 0; i < ARRAY_SIZE(test_points); i++) {
  88. bool result = Polygon_outside(test_points[i].point,
  89. OBC_boundary, ARRAY_SIZE(OBC_boundary));
  90. if (result != test_points[i].outside) {
  91. all_passed = false;
  92. }
  93. }
  94. }
  95. hal.console->printf("%u usec/call\n", (unsigned)((AP_HAL::micros()
  96. - start_time)/(count * ARRAY_SIZE(test_points))));
  97. hal.console->printf("%s\n", all_passed ? "ALL TESTS PASSED" : "TEST FAILED");
  98. }
  99. void loop(void){}
  100. AP_HAL_MAIN();