test_polygon.cpp 12 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232233234235236237238239240241242243244245246247248249250251252253254255256257258259260261262263264265266267268269270271272273274275276277278279280281282283284285286287288289290291292293294295296297298299300301302303304305306307308309310311312313314315316317318319320321322323324325326327328329330331332333334335336337338339340341342343344345346347348349350351352353354355356357358359360361362
  1. #include <AP_gtest.h>
  2. #include <AP_Common/AP_Common.h>
  3. #include <AP_Math/AP_Math.h>
  4. struct PB {
  5. Vector2f point;
  6. Vector2f boundary[3];
  7. bool outside;
  8. };
  9. static const PB points_boundaries[] = {
  10. { {0.1f,0.1f}, {{0.0f,0.0f}, {0.0f,1.0f}, {1.0f,0.0f}}, false },
  11. // test for winding order issues:
  12. { {0.9f,0.9f}, {{0.0f,0.0f}, {1.0f,0.0f}, {0.0f,1.0f}}, true },
  13. { {0.9f,0.9f}, {{0.0f,1.0f}, {0.0f,0.0f}, {1.0f,0.0f}}, true },
  14. { {0.9f,0.9f}, {{1.0f,0.0f}, {0.0f,1.0f}, {0.0f,0.0f}}, true },
  15. { {0.9f,0.9f}, {{0.0f,1.0f}, {1.0f,0.0f}, {0.0f,0.0f}}, true },
  16. { {0.1f,0.1f}, {{0.0f,0.0f}, {1.0f,0.0f}, {0.0f,1.0f}}, false },
  17. { {0.1f,0.1f}, {{0.0f,1.0f}, {0.0f,0.0f}, {1.0f,0.0f}}, false },
  18. { {0.1f,0.1f}, {{1.0f,0.0f}, {0.0f,1.0f}, {0.0f,0.0f}}, false },
  19. { {0.1f,0.1f}, {{0.0f,1.0f}, {1.0f,0.0f}, {0.0f,0.0f}}, false },
  20. { {0.99f-10.0f,0.99f-10.0f}, {{0.0f-10.0f,1.0f-10.0f}, {1.0f-10.0f,0.0f-10.0f}, {0.0f-10.0f,0.0f-10.0f}}, true },
  21. { {99.0f,99.0f}, {{0.0f,100.0f}, {100.0f,0.0f}, {0.0f,0.0f}}, true },
  22. { {0.1f,0.0f}, {{0.0f,0.0f}, {0.0f,1.0f}, {1.0f,0.0f}}, false },
  23. { {0.0f,0.99f}, {{0.0f,0.0f}, {0.0f,1.0f}, {1.0f,0.0f}}, false },
  24. { {0.99f,0.0f}, {{0.0f,0.0f}, {0.0f,1.0f}, {1.0f,0.0f}}, false },
  25. { {1.01f,0.0f}, {{0.0f,0.0f}, {0.0f,1.0f}, {1.0f,0.0f}}, true },
  26. { {0.0f,1.01f}, {{0.0f,0.0f}, {0.0f,1.0f}, {1.0f,0.0f}}, true },
  27. { {2.0f,2.0f}, {{0.0f,0.0f}, {0.0f,1.0f}, {1.0f,0.0f}}, true },
  28. { {-2.0f,-2.0f}, {{0.0f,0.0f}, {0.0f,1.0f}, {1.0f,0.0f}}, true },
  29. { {-0.05f,0.0f}, {{0.0f,0.0f}, {0.0f,1.0f}, {1.0f,0.0f}}, true },
  30. { {0.0f,-0.05f}, {{0.0f,0.0f}, {0.0f,1.0f}, {1.0f,0.0f}}, true },
  31. };
  32. TEST(Polygon, outside)
  33. {
  34. // uint8_t count = 0;
  35. for (const struct PB &pb : points_boundaries) {
  36. // ::fprintf(stderr, "count=%u\n", count++);
  37. Vector2f v[4];
  38. memcpy(v, pb.boundary, sizeof(pb.boundary));
  39. v[3] = v[0]; // close it
  40. EXPECT_EQ(pb.outside, Polygon_outside(pb.point, v, 4));
  41. }
  42. }
  43. struct SquareBoundary {
  44. Vector2f point;
  45. Vector2f boundary[4];
  46. bool outside;
  47. };
  48. static const SquareBoundary square_boundaries[] = {
  49. { {1.0f,1.0f}, {{0.0f,0.0f}, {0.0f,10.0f}, {10.0, 10.0}, {10.0f,0.0f}}, false },
  50. { {9.0f,9.0f}, {{0.0f,0.0f}, {0.0f,10.0f}, {10.0, 10.0}, {10.0f,0.0f}}, false },
  51. { {1.0f,9.0f}, {{0.0f,0.0f}, {0.0f,10.0f}, {10.0, 10.0}, {10.0f,0.0f}}, false },
  52. { {9.0f,1.0f}, {{0.0f,0.0f}, {0.0f,10.0f}, {10.0, 10.0}, {10.0f,0.0f}}, false },
  53. };
  54. TEST(Polygon, square_boundaries)
  55. {
  56. // uint8_t count = 0;
  57. for (const auto &pb : square_boundaries) {
  58. // ::fprintf(stderr, "count=%u\n", count++);
  59. Vector2f v[5];
  60. memcpy(v, pb.boundary, sizeof(pb.boundary));
  61. v[4] = v[0]; // close it
  62. EXPECT_EQ(pb.outside, Polygon_outside(pb.point, v, 5));
  63. EXPECT_EQ(Polygon_outside(pb.point, v, 4),
  64. Polygon_outside(pb.point, v, 5));
  65. }
  66. }
  67. TEST(Polygon, circle_outside_triangle)
  68. {
  69. const Vector2f triangle[] = {{0.0f,0.0f}, {1.0f,0.0f}, {0.0f,1.0f}};
  70. Vector2f triangle_closed[4];
  71. memcpy(triangle_closed, triangle, sizeof(triangle));
  72. triangle_closed[3] = triangle_closed[0];
  73. const float radius = 0.8f;
  74. for (uint16_t i=0; i<360; i++) {
  75. const float x = radius * sin(radians(i)) + 0.5f;
  76. const float y = radius * cos(radians(i)) + 0.5f;
  77. EXPECT_EQ(true, Polygon_outside(Vector2f{x,y}, triangle_closed, 4));
  78. EXPECT_EQ(Polygon_outside(Vector2f{x,y}, triangle_closed, 3),
  79. Polygon_outside(Vector2f{x,y}, triangle_closed, 4));
  80. }
  81. }
  82. TEST(Polygon, circle_inside_triangle)
  83. {
  84. const Vector2f triangle[] = {{0.0f,0.0f}, {1.0f,0.0f}, {0.0f,1.0f}};
  85. Vector2f triangle_closed[4];
  86. memcpy(triangle_closed, triangle, sizeof(triangle));
  87. triangle_closed[3] = triangle_closed[0];
  88. const float radius = 0.2f;
  89. for (uint16_t i=0; i<360; i++) {
  90. const float x = radius * sin(radians(i)) + 0.2f;
  91. const float y = radius * cos(radians(i)) + 0.2f;
  92. EXPECT_EQ(false, Polygon_outside(Vector2f{x,y}, triangle_closed, 4));
  93. EXPECT_EQ(Polygon_outside(Vector2f{x,y}, triangle_closed, 3),
  94. Polygon_outside(Vector2f{x,y}, triangle_closed, 4));
  95. }
  96. }
  97. TEST(Polygon, complex)
  98. {
  99. const Vector2f poly[] = {
  100. {0.0f,0.0f},
  101. {0.0f,10.0f},
  102. {5.0, 10.0f},
  103. {5.0f,5.0f},
  104. {3.0f,5.0f},
  105. {3.0f,6.0f},
  106. {4.0f,6.0f},
  107. {4.0f,9.0f},
  108. {4.0f,9.0f},
  109. {1.0f,9.0f},
  110. {1.0f,6.0f},
  111. {2.0f,6.0f},
  112. {2.0f,5.0f},
  113. {1.0f,5.0f},
  114. {1.0f,0.0f},
  115. };
  116. const Vector2f inside_points[] = {
  117. {0.1f, 0.1f},
  118. {4.5f, 9.5f},
  119. {0.5f, 9.5f},
  120. };
  121. const Vector2f outside_points[] = {
  122. {3.0f, 8.0f},
  123. {5.5f, 10.0f},
  124. {2.0f, 2.0f},
  125. {2.5f, 5.5f},
  126. {1.5f, 6.5f},
  127. };
  128. Vector2f closed_poly[sizeof(poly) + sizeof(Vector2f)];
  129. memcpy(closed_poly, poly, sizeof(poly));
  130. const uint16_t n = ARRAY_SIZE(closed_poly);
  131. closed_poly[n-1] = closed_poly[0];
  132. for (const auto &point : inside_points) {
  133. EXPECT_EQ(false, Polygon_outside(point, closed_poly, n));
  134. EXPECT_EQ(Polygon_outside(point, closed_poly, n-1),
  135. Polygon_outside(point, closed_poly, n));
  136. }
  137. for (const auto &point : outside_points) {
  138. EXPECT_EQ(true, Polygon_outside(point, closed_poly, n));
  139. EXPECT_EQ(Polygon_outside(point, closed_poly, n-1),
  140. Polygon_outside(point, closed_poly, n));
  141. }
  142. }
  143. TEST(Polygon, circle_outside_square)
  144. {
  145. const Vector2f square[] = {{0.0f,0.0f}, {0.0f,10.0f}, {10.0, 10.0}, {10.0f,0.0f}};
  146. Vector2f square_closed[5];
  147. memcpy(square_closed, square, sizeof(square));
  148. square_closed[4] = square_closed[0];
  149. const float radius = 8.0f;
  150. for (uint16_t i=0; i<360; i++) {
  151. const float x = radius * sin(radians(i)) + 5.0f;
  152. const float y = radius * cos(radians(i)) + 5.0f;
  153. EXPECT_EQ(true, Polygon_outside(Vector2f{x,y}, square_closed, 4));
  154. EXPECT_EQ(Polygon_outside(Vector2f{x,y}, square_closed, 3),
  155. Polygon_outside(Vector2f{x,y}, square_closed, 4));
  156. }
  157. }
  158. struct PB_long {
  159. Vector2l point;
  160. Vector2l boundary[3];
  161. bool outside;
  162. };
  163. static const PB_long points_boundaries_long[] = {
  164. { {1000000,1000000}, {{0,0}, {0,10000000}, {10000000,0}}, false },
  165. // test for winding order issues:
  166. { {9000000,9000000}, {{0,0}, {10000000,0}, {0,10000000}}, true },
  167. { {9000000,9000000}, {{0,10000000}, {0,0}, {10000000,0}}, true },
  168. { {9000000,9000000}, {{10000000,0}, {0,10000000}, {0,0}}, true },
  169. { {9000000,9000000}, {{0,10000000}, {10000000,0}, {0,0}}, true },
  170. { {1000000,1000000}, {{0,0}, {10000000,0}, {0,10000000}}, false },
  171. { {1000000,1000000}, {{0,10000000}, {0,0}, {10000000,0}}, false },
  172. { {1000000,1000000}, {{10000000,0}, {0,10000000}, {0,0}}, false },
  173. { {1000000,1000000}, {{0,10000000}, {10000000,0}, {0,0}}, false },
  174. { {9900000-10,9900000-10}, {{0-10,10000000-10}, {10000000-10,0-10}, {0-10,0-10}}, true },
  175. { {990000000,990000000}, {{0,100}, {100,0}, {0,0}}, true },
  176. { {1000000,0}, {{0,0}, {0,10000000}, {10000000,0}}, false },
  177. { {0,9900000}, {{0,0}, {0,10000000}, {10000000,0}}, false },
  178. { {9900000,0}, {{0,0}, {0,10000000}, {10000000,0}}, false },
  179. { {10100000,0}, {{0,0}, {0,10000000}, {10000000,0}}, true },
  180. { {0,10100000}, {{0,0}, {0,10000000}, {10000000,0}}, true },
  181. { {20000000,20000000}, {{0,0}, {0,10000000}, {10000000,0}}, true },
  182. { {-20000000,-20000000}, {{0,0}, {0,10000000}, {10000000,0}}, true },
  183. { {-500000,0}, {{0,0}, {0,10000000}, {10000000,0}}, true },
  184. { {0,-500000}, {{0,0}, {0,10000000}, {10000000,0}}, true },
  185. };
  186. TEST(Polygon, outside_long)
  187. {
  188. // uint8_t count = 0;
  189. for (const struct PB_long &pb : points_boundaries_long) {
  190. // ::fprintf(stderr, "count=%u\n", count++);
  191. Vector2l v[4];
  192. memcpy(v, pb.boundary, sizeof(pb.boundary));
  193. v[3] = v[0]; // close it
  194. EXPECT_EQ(pb.outside, Polygon_outside(pb.point, v, 4));
  195. }
  196. }
  197. TEST(Polygon, outside_long_closed_equal_to_unclosed)
  198. {
  199. // uint8_t count = 0;
  200. for (const struct PB_long &pb : points_boundaries_long) {
  201. // ::fprintf(stderr, "count=%u\n", count++);
  202. Vector2l v[4];
  203. memcpy(v, pb.boundary, sizeof(pb.boundary));
  204. v[3] = v[0]; // close it
  205. EXPECT_EQ(Polygon_outside(pb.point, v, 3),
  206. Polygon_outside(pb.point, v, 4));
  207. }
  208. }
  209. #define TEST_POLYGON_POINTS(POLYGON, TEST_POINTS) \
  210. do { \
  211. for (uint32_t i = 0; i < ARRAY_SIZE(TEST_POINTS); i++) { \
  212. EXPECT_EQ(TEST_POINTS[i].outside, \
  213. Polygon_outside(TEST_POINTS[i].point, \
  214. POLYGON, ARRAY_SIZE(POLYGON))); \
  215. } \
  216. } while(0)
  217. // this OBC polygon test stolen from the polygon Math example
  218. /*
  219. * this is the boundary of the 2010 outback challenge
  220. * Note that the last point must be the same as the first for the
  221. * Polygon_outside() algorithm
  222. */
  223. static const Vector2l OBC_boundary[] = {
  224. Vector2l(-265695640, 1518373730),
  225. Vector2l(-265699560, 1518394050),
  226. Vector2l(-265768230, 1518411420),
  227. Vector2l(-265773080, 1518403440),
  228. Vector2l(-265815110, 1518419500),
  229. Vector2l(-265784860, 1518474690),
  230. Vector2l(-265994890, 1518528860),
  231. Vector2l(-266092110, 1518747420),
  232. Vector2l(-266454780, 1518820530),
  233. Vector2l(-266435720, 1518303500),
  234. Vector2l(-265875990, 1518344050),
  235. Vector2l(-265695640, 1518373730)
  236. };
  237. static const struct {
  238. Vector2l point;
  239. bool outside;
  240. } OBC_test_points[] = {
  241. { Vector2l(-266398870, 1518220000), true },
  242. { Vector2l(-266418700, 1518709260), false },
  243. { Vector2l(-350000000, 1490000000), true },
  244. { Vector2l(0, 0), true },
  245. { Vector2l(-265768150, 1518408250), false },
  246. { Vector2l(-265774060, 1518405860), true },
  247. { Vector2l(-266435630, 1518303440), true },
  248. { Vector2l(-266435650, 1518313540), false },
  249. { Vector2l(-266435690, 1518303530), false },
  250. { Vector2l(-266435690, 1518303490), true },
  251. { Vector2l(-265875990, 1518344049), true },
  252. { Vector2l(-265875990, 1518344051), false },
  253. { Vector2l(-266454781, 1518820530), true },
  254. { Vector2l(-266454779, 1518820530), true },
  255. { Vector2l(-266092109, 1518747420), true },
  256. { Vector2l(-266092111, 1518747420), false },
  257. { Vector2l(-266092110, 1518747421), true },
  258. { Vector2l(-266092110, 1518747419), false },
  259. { Vector2l(-266092111, 1518747421), true },
  260. { Vector2l(-266092109, 1518747421), true },
  261. { Vector2l(-266092111, 1518747419), false },
  262. };
  263. TEST(Polygon, obc)
  264. {
  265. TEST_POLYGON_POINTS(OBC_boundary, OBC_test_points);
  266. }
  267. static const Vector2f PROX_boundary[] = {
  268. Vector2f{938.315063f,388.662872f},
  269. Vector2f{545.622803f,1317.25f},
  270. Vector2f{-833.382812f,2011.96423f},
  271. Vector2f{-2011.96411f,833.382996f},
  272. Vector2f{-875.159241f,-362.502838f},
  273. Vector2f{-153.222916f,-369.912689f},
  274. Vector2f{153.222931f,-369.912689f},
  275. Vector2f{369.91272f,-153.222855f},
  276. // closing point so we can call Polygon_outside(...):
  277. Vector2f{938.315063f,388.662872f},
  278. };
  279. static const struct {
  280. Vector2f point;
  281. bool outside;
  282. } PROX_test_points[] = {
  283. { Vector2f{0.0f,0.0f}, false },
  284. };
  285. TEST(Polygon, prox)
  286. {
  287. TEST_POLYGON_POINTS(PROX_boundary, PROX_test_points);
  288. }
  289. static const Vector2f SIMPLE_boundary[] = {
  290. Vector2f{-1,2},
  291. Vector2f{1,2},
  292. Vector2f{1,-3},
  293. Vector2f{-1,-3},
  294. // closing point so we can call Polygon_outside(...):
  295. Vector2f{-1,2},
  296. };
  297. static const struct {
  298. Vector2f point;
  299. bool outside;
  300. } SIMPLE_test_points[] = {
  301. { Vector2f{0.0f,0.0f}, false },
  302. { Vector2f{0.5f,1.5f}, false },
  303. { Vector2f{-0.5f,1.5f}, false },
  304. { Vector2f{-0.5f,-2.5}, false },
  305. };
  306. TEST(Polygon, simple)
  307. {
  308. TEST_POLYGON_POINTS(SIMPLE_boundary, SIMPLE_test_points);
  309. }
  310. AP_GTEST_MAIN()
  311. int hal = 0; // bizarrely, this fixes an undefined-symbol error but doesn't raise a type exception. Yay.