test_geodesic_grid.cpp 8.1 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232233234235
  1. /*
  2. * Copyright (C) 2015-2016 Intel Corporation. All rights reserved.
  3. *
  4. * This file is free software: you can redistribute it and/or modify it
  5. * under the terms of the GNU General Public License as published by the
  6. * Free Software Foundation, either version 3 of the License, or
  7. * (at your option) any later version.
  8. *
  9. * This file is distributed in the hope that it will be useful, but
  10. * WITHOUT ANY WARRANTY; without even the implied warranty of
  11. * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.
  12. * See the GNU General Public License for more details.
  13. *
  14. * You should have received a copy of the GNU General Public License along
  15. * with this program. If not, see <http://www.gnu.org/licenses/>.
  16. */
  17. #include <cassert>
  18. #include <vector>
  19. #include "math_test.h"
  20. #include <AP_Math/AP_GeodesicGrid.h>
  21. class TestParam {
  22. public:
  23. /**
  24. * Vector to be tested.
  25. */
  26. Vector3f v;
  27. /**
  28. * Expected section if when AP_GeodesicGrid::section() is called with
  29. * inclusive set as false.
  30. */
  31. int section;
  32. /**
  33. * Array terminated with -1. This doesn't have to be touched if #section
  34. * isn't negative. If #section is -1, then calling
  35. * AP_GeodesicGrid::section() with inclusive set as true expects a return
  36. * value as one of the values in #inclusive_sections.
  37. */
  38. int inclusive_sections[7];
  39. };
  40. class GeodesicGridTest : public ::testing::TestWithParam<TestParam> {
  41. protected:
  42. /**
  43. * Test the functions for triangles indexes.
  44. *
  45. * @param p[in] The test parameter.
  46. */
  47. void test_triangles_indexes(const TestParam &p) {
  48. if (p.section >= 0) {
  49. int expected_triangle =
  50. p.section / AP_GeodesicGrid::NUM_SUBTRIANGLES;
  51. int triangle = AP_GeodesicGrid::_triangle_index(p.v, false);
  52. ASSERT_EQ(expected_triangle, triangle);
  53. int expected_subtriangle =
  54. p.section % AP_GeodesicGrid::NUM_SUBTRIANGLES;
  55. int subtriangle =
  56. AP_GeodesicGrid::_subtriangle_index(triangle, p.v, false);
  57. ASSERT_EQ(expected_subtriangle, subtriangle);
  58. } else {
  59. int triangle = AP_GeodesicGrid::_triangle_index(p.v, false);
  60. if (triangle >= 0) {
  61. int subtriangle = AP_GeodesicGrid::_subtriangle_index(triangle,
  62. p.v,
  63. false);
  64. ASSERT_EQ(-1, subtriangle) << "triangle is " << triangle;
  65. }
  66. }
  67. }
  68. };
  69. static const Vector3f triangles[20][3] = {
  70. {{-M_GOLDEN, 1, 0}, {-1, 0,-M_GOLDEN}, {-M_GOLDEN,-1, 0}},
  71. {{-1, 0,-M_GOLDEN}, {-M_GOLDEN,-1, 0}, { 0,-M_GOLDEN,-1}},
  72. {{-M_GOLDEN,-1, 0}, { 0,-M_GOLDEN,-1}, { 0,-M_GOLDEN, 1}},
  73. {{-1, 0,-M_GOLDEN}, { 0,-M_GOLDEN,-1}, { 1, 0,-M_GOLDEN}},
  74. {{ 0,-M_GOLDEN,-1}, { 0,-M_GOLDEN, 1}, { M_GOLDEN,-1, 0}},
  75. {{ 0,-M_GOLDEN,-1}, { 1, 0,-M_GOLDEN}, { M_GOLDEN,-1, 0}},
  76. {{ M_GOLDEN,-1, 0}, { 1, 0,-M_GOLDEN}, { M_GOLDEN, 1, 0}},
  77. {{ 1, 0,-M_GOLDEN}, { M_GOLDEN, 1, 0}, { 0, M_GOLDEN,-1}},
  78. {{ 1, 0,-M_GOLDEN}, { 0, M_GOLDEN,-1}, {-1, 0,-M_GOLDEN}},
  79. {{ 0, M_GOLDEN,-1}, {-M_GOLDEN, 1, 0}, {-1, 0,-M_GOLDEN}},
  80. {{ M_GOLDEN,-1, 0}, { 1, 0, M_GOLDEN}, { M_GOLDEN, 1, 0}},
  81. {{ 1, 0, M_GOLDEN}, { M_GOLDEN, 1, 0}, { 0, M_GOLDEN, 1}},
  82. {{ M_GOLDEN, 1, 0}, { 0, M_GOLDEN, 1}, { 0, M_GOLDEN,-1}},
  83. {{ 1, 0, M_GOLDEN}, { 0, M_GOLDEN, 1}, {-1, 0, M_GOLDEN}},
  84. {{ 0, M_GOLDEN, 1}, { 0, M_GOLDEN,-1}, {-M_GOLDEN, 1, 0}},
  85. {{ 0, M_GOLDEN, 1}, {-1, 0, M_GOLDEN}, {-M_GOLDEN, 1, 0}},
  86. {{-M_GOLDEN, 1, 0}, {-1, 0, M_GOLDEN}, {-M_GOLDEN,-1, 0}},
  87. {{-1, 0, M_GOLDEN}, {-M_GOLDEN,-1, 0}, { 0,-M_GOLDEN, 1}},
  88. {{-1, 0, M_GOLDEN}, { 0,-M_GOLDEN, 1}, { 1, 0, M_GOLDEN}},
  89. {{ 0,-M_GOLDEN, 1}, { M_GOLDEN,-1, 0}, { 1, 0, M_GOLDEN}},
  90. };
  91. static bool section_triangle(unsigned int section_index,
  92. Vector3f &a,
  93. Vector3f &b,
  94. Vector3f &c) {
  95. if (section_index >= 80) {
  96. return false;
  97. }
  98. unsigned int i = section_index / 4;
  99. unsigned int j = section_index % 4;
  100. auto &t = triangles[i];
  101. Vector3f mt[3]{(t[0] + t[1]) / 2, (t[1] + t[2]) / 2, (t[2] + t[0]) / 2};
  102. switch (j) {
  103. case 0:
  104. a = mt[0];
  105. b = mt[1];
  106. c = mt[2];
  107. break;
  108. case 1:
  109. a = t[0];
  110. b = mt[0];
  111. c = mt[2];
  112. break;
  113. case 2:
  114. a = mt[0];
  115. b = t[1];
  116. c = mt[1];
  117. break;
  118. case 3:
  119. a = mt[2];
  120. b = mt[1];
  121. c = t[2];
  122. break;
  123. }
  124. return true;
  125. }
  126. AP_GTEST_PRINTATBLE_PARAM_MEMBER(TestParam, v);
  127. TEST_P(GeodesicGridTest, Sections)
  128. {
  129. auto p = GetParam();
  130. test_triangles_indexes(p);
  131. EXPECT_EQ(p.section, AP_GeodesicGrid::section(p.v));
  132. if (p.section < 0) {
  133. int s = AP_GeodesicGrid::section(p.v, true);
  134. int i;
  135. for (i = 0; p.inclusive_sections[i] > 0; i++) {
  136. assert(i < 7);
  137. if (s == p.inclusive_sections[i]) {
  138. break;
  139. }
  140. }
  141. if (p.inclusive_sections[i] < 0) {
  142. ADD_FAILURE() << "section " << s << " with inclusive=true not found in inclusive_sections";
  143. }
  144. }
  145. }
  146. static TestParam icosahedron_vertices[] = {
  147. {{ M_GOLDEN, 1.0f, 0.0f}, -1, {27, 30, 43, 46, 49, -1}},
  148. {{ M_GOLDEN, -1.0f, 0.0f}, -1, {19, 23, 25, 41, 78, -1}},
  149. {{-M_GOLDEN, 1.0f, 0.0f}, -1, { 1, 38, 59, 63, 65, -1}},
  150. {{-M_GOLDEN, -1.0f, 0.0f}, -1, { 3, 6, 9, 67, 70, -1}},
  151. {{ 1.0f, 0.0f, M_GOLDEN}, -1, {42, 45, 53, 75, 79, -1}},
  152. {{-1.0f, 0.0f, M_GOLDEN}, -1, {55, 62, 66, 69, 73, -1}},
  153. {{ 1.0f, 0.0f, -M_GOLDEN}, -1, {15, 22, 26, 29, 33, -1}},
  154. {{-1.0f, 0.0f, -M_GOLDEN}, -1, { 2, 5, 13, 35, 39, -1}},
  155. {{0.0f, M_GOLDEN, 1.0f}, -1, {47, 50, 54, 57, 61, -1}},
  156. {{0.0f, M_GOLDEN, -1.0f}, -1, {31, 34, 37, 51, 58, -1}},
  157. {{0.0f, -M_GOLDEN, 1.0f}, -1, {11, 18, 71, 74, 77, -1}},
  158. {{0.0f, -M_GOLDEN, -1.0f}, -1, { 7, 10, 14, 17, 21, -1}},
  159. };
  160. INSTANTIATE_TEST_CASE_P(IcosahedronVertices,
  161. GeodesicGridTest,
  162. ::testing::ValuesIn(icosahedron_vertices));
  163. /* Generate vectors for each triangle */
  164. static std::vector<TestParam> general_vectors = []()
  165. {
  166. std::vector<TestParam> params;
  167. for (int i = 0; i < 20 * AP_GeodesicGrid::NUM_SUBTRIANGLES; i++) {
  168. Vector3f a, b, c;
  169. TestParam p;
  170. section_triangle(i, a, b, c);
  171. p.section = i;
  172. /* Vector that crosses the centroid */
  173. p.v = a + b + c;
  174. params.push_back(p);
  175. /* Vectors that cross the triangle close to the edges */
  176. p.v = a + b + c * 0.001f;
  177. params.push_back(p);
  178. p.v = a + b * 0.001f + c;
  179. params.push_back(p);
  180. p.v = a * 0.001f + b + c;
  181. params.push_back(p);
  182. /* Vectors that cross the triangle close to the vertices */
  183. p.v = a + b * 0.001 + c * 0.001f;
  184. params.push_back(p);
  185. p.v = a * 0.001f + b + c * 0.001f;
  186. params.push_back(p);
  187. p.v = a * 0.001f + b * 0.001f + c;
  188. params.push_back(p);
  189. }
  190. return params;
  191. }();
  192. INSTANTIATE_TEST_CASE_P(GeneralVectors,
  193. GeodesicGridTest,
  194. ::testing::ValuesIn(general_vectors));
  195. /* Other hardcoded vectors, so we don't rely just on the centroid vectors
  196. * (which are dependent on how the triangles are *defined by the
  197. * implementation*)
  198. *
  199. * See AP_GeodesicGrid.h for the notation on the comments below.
  200. */
  201. static TestParam hardcoded_vectors[] = {
  202. /* a + 2 * m_a + .5 * m_c for T_4 */
  203. {{.25f * M_GOLDEN, -.25f * (13.0f * M_GOLDEN + 1.0f), - 1.25f}, 17},
  204. /* 3 * m_a + 2 * m_b 0 * m_c for T_4 */
  205. {{M_GOLDEN, -4.0f * M_GOLDEN -1.0f, 1.0f}, -1, {16, 18, -1}},
  206. /* 2 * m_c + (1 / 3) * m_b + .1 * c for T_13 */
  207. {{-.2667f, .1667f * M_GOLDEN, 2.2667f * M_GOLDEN + .1667f}, 55},
  208. /* .25 * m_a + 5 * b + 2 * m_b for T_8 */
  209. {{-.875f, 6.125f * M_GOLDEN, -1.125f * M_GOLDEN - 6.125f}, 34},
  210. };
  211. INSTANTIATE_TEST_CASE_P(HardcodedVectors,
  212. GeodesicGridTest,
  213. ::testing::ValuesIn(hardcoded_vectors));
  214. AP_GTEST_MAIN()