APM:Libraries
test_geodesic_grid.cpp
Go to the documentation of this file.
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 
20 #include "math_test.h"
22 
23 class TestParam {
24 public:
33  int section;
41 };
42 
43 class GeodesicGridTest : public ::testing::TestWithParam<TestParam> {
44 protected:
51  if (p.section >= 0) {
52  int expected_triangle =
54  int triangle = AP_GeodesicGrid::_triangle_index(p.v, false);
55  ASSERT_EQ(expected_triangle, triangle);
56 
57  int expected_subtriangle =
59  int subtriangle =
60  AP_GeodesicGrid::_subtriangle_index(triangle, p.v, false);
61  ASSERT_EQ(expected_subtriangle, subtriangle);
62  } else {
63  int triangle = AP_GeodesicGrid::_triangle_index(p.v, false);
64  if (triangle >= 0) {
65  int subtriangle = AP_GeodesicGrid::_subtriangle_index(triangle,
66  p.v,
67  false);
68  ASSERT_EQ(-1, subtriangle) << "triangle is " << triangle;
69  }
70  }
71  }
72 };
73 
74 static const Vector3f triangles[20][3] = {
75  {{-M_GOLDEN, 1, 0}, {-1, 0,-M_GOLDEN}, {-M_GOLDEN,-1, 0}},
76  {{-1, 0,-M_GOLDEN}, {-M_GOLDEN,-1, 0}, { 0,-M_GOLDEN,-1}},
77  {{-M_GOLDEN,-1, 0}, { 0,-M_GOLDEN,-1}, { 0,-M_GOLDEN, 1}},
78  {{-1, 0,-M_GOLDEN}, { 0,-M_GOLDEN,-1}, { 1, 0,-M_GOLDEN}},
79  {{ 0,-M_GOLDEN,-1}, { 0,-M_GOLDEN, 1}, { M_GOLDEN,-1, 0}},
80  {{ 0,-M_GOLDEN,-1}, { 1, 0,-M_GOLDEN}, { M_GOLDEN,-1, 0}},
81  {{ M_GOLDEN,-1, 0}, { 1, 0,-M_GOLDEN}, { M_GOLDEN, 1, 0}},
82  {{ 1, 0,-M_GOLDEN}, { M_GOLDEN, 1, 0}, { 0, M_GOLDEN,-1}},
83  {{ 1, 0,-M_GOLDEN}, { 0, M_GOLDEN,-1}, {-1, 0,-M_GOLDEN}},
84  {{ 0, M_GOLDEN,-1}, {-M_GOLDEN, 1, 0}, {-1, 0,-M_GOLDEN}},
85 
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  {{ M_GOLDEN, 1, 0}, { 0, M_GOLDEN, 1}, { 0, M_GOLDEN,-1}},
89  {{ 1, 0, M_GOLDEN}, { 0, M_GOLDEN, 1}, {-1, 0, M_GOLDEN}},
90  {{ 0, M_GOLDEN, 1}, { 0, M_GOLDEN,-1}, {-M_GOLDEN, 1, 0}},
91  {{ 0, M_GOLDEN, 1}, {-1, 0, M_GOLDEN}, {-M_GOLDEN, 1, 0}},
92  {{-M_GOLDEN, 1, 0}, {-1, 0, M_GOLDEN}, {-M_GOLDEN,-1, 0}},
93  {{-1, 0, M_GOLDEN}, {-M_GOLDEN,-1, 0}, { 0,-M_GOLDEN, 1}},
94  {{-1, 0, M_GOLDEN}, { 0,-M_GOLDEN, 1}, { 1, 0, M_GOLDEN}},
95  {{ 0,-M_GOLDEN, 1}, { M_GOLDEN,-1, 0}, { 1, 0, M_GOLDEN}},
96 };
97 
98 static bool section_triangle(unsigned int section_index,
99  Vector3f &a,
100  Vector3f &b,
101  Vector3f &c) {
102  if (section_index >= 80) {
103  return false;
104  }
105 
106  unsigned int i = section_index / 4;
107  unsigned int j = section_index % 4;
108  auto &t = triangles[i];
109  Vector3f mt[3]{(t[0] + t[1]) / 2, (t[1] + t[2]) / 2, (t[2] + t[0]) / 2};
110 
111  switch (j) {
112  case 0:
113  a = mt[0];
114  b = mt[1];
115  c = mt[2];
116  break;
117  case 1:
118  a = t[0];
119  b = mt[0];
120  c = mt[2];
121  break;
122  case 2:
123  a = mt[0];
124  b = t[1];
125  c = mt[1];
126  break;
127  case 3:
128  a = mt[2];
129  b = mt[1];
130  c = t[2];
131  break;
132  }
133 
134  return true;
135 }
136 
138 
140 {
141  auto p = GetParam();
142 
143  test_triangles_indexes(p);
144  EXPECT_EQ(p.section, AP_GeodesicGrid::section(p.v));
145 
146  if (p.section < 0) {
147  int s = AP_GeodesicGrid::section(p.v, true);
148  int i;
149  for (i = 0; p.inclusive_sections[i] > 0; i++) {
150  assert(i < 7);
151  if (s == p.inclusive_sections[i]) {
152  break;
153  }
154  }
155  if (p.inclusive_sections[i] < 0) {
156  ADD_FAILURE() << "section " << s << " with inclusive=true not found in inclusive_sections";
157  }
158  }
159 }
160 
162  {{ M_GOLDEN, 1.0f, 0.0f}, -1, {27, 30, 43, 46, 49, -1}},
163  {{ M_GOLDEN, -1.0f, 0.0f}, -1, {19, 23, 25, 41, 78, -1}},
164  {{-M_GOLDEN, 1.0f, 0.0f}, -1, { 1, 38, 59, 63, 65, -1}},
165  {{-M_GOLDEN, -1.0f, 0.0f}, -1, { 3, 6, 9, 67, 70, -1}},
166  {{ 1.0f, 0.0f, M_GOLDEN}, -1, {42, 45, 53, 75, 79, -1}},
167  {{-1.0f, 0.0f, M_GOLDEN}, -1, {55, 62, 66, 69, 73, -1}},
168  {{ 1.0f, 0.0f, -M_GOLDEN}, -1, {15, 22, 26, 29, 33, -1}},
169  {{-1.0f, 0.0f, -M_GOLDEN}, -1, { 2, 5, 13, 35, 39, -1}},
170  {{0.0f, M_GOLDEN, 1.0f}, -1, {47, 50, 54, 57, 61, -1}},
171  {{0.0f, M_GOLDEN, -1.0f}, -1, {31, 34, 37, 51, 58, -1}},
172  {{0.0f, -M_GOLDEN, 1.0f}, -1, {11, 18, 71, 74, 77, -1}},
173  {{0.0f, -M_GOLDEN, -1.0f}, -1, { 7, 10, 14, 17, 21, -1}},
174 };
175 INSTANTIATE_TEST_CASE_P(IcosahedronVertices,
177  ::testing::ValuesIn(icosahedron_vertices));
178 
179 /* Generate vectors for each triangle */
180 static std::vector<TestParam> general_vectors = []()
181 {
182  std::vector<TestParam> params;
183  for (int i = 0; i < 20 * AP_GeodesicGrid::NUM_SUBTRIANGLES; i++) {
184  Vector3f a, b, c;
185  TestParam p;
186  section_triangle(i, a, b, c);
187  p.section = i;
188 
189  /* Vector that crosses the centroid */
190  p.v = a + b + c;
191  params.push_back(p);
192 
193  /* Vectors that cross the triangle close to the edges */
194  p.v = a + b + c * 0.001f;
195  params.push_back(p);
196  p.v = a + b * 0.001f + c;
197  params.push_back(p);
198  p.v = a * 0.001f + b + c;
199  params.push_back(p);
200 
201  /* Vectors that cross the triangle close to the vertices */
202  p.v = a + b * 0.001 + c * 0.001f;
203  params.push_back(p);
204  p.v = a * 0.001f + b + c * 0.001f;
205  params.push_back(p);
206  p.v = a * 0.001f + b * 0.001f + c;
207  params.push_back(p);
208  }
209  return params;
210 }();
211 INSTANTIATE_TEST_CASE_P(GeneralVectors,
213  ::testing::ValuesIn(general_vectors));
214 
215 /* Other hardcoded vectors, so we don't rely just on the centroid vectors
216  * (which are dependent on how the triangles are *defined by the
217  * implementation*)
218  *
219  * See AP_GeodesicGrid.h for the notation on the comments below.
220  */
222  /* a + 2 * m_a + .5 * m_c for T_4 */
223  {{.25f * M_GOLDEN, -.25f * (13.0f * M_GOLDEN + 1.0f), - 1.25f}, 17},
224  /* 3 * m_a + 2 * m_b 0 * m_c for T_4 */
225  {{M_GOLDEN, -4.0f * M_GOLDEN -1.0f, 1.0f}, -1, {16, 18, -1}},
226  /* 2 * m_c + (1 / 3) * m_b + .1 * c for T_13 */
227  {{-.2667f, .1667f * M_GOLDEN, 2.2667f * M_GOLDEN + .1667f}, 55},
228  /* .25 * m_a + 5 * b + 2 * m_b for T_8 */
229  {{-.875f, 6.125f * M_GOLDEN, -1.125f * M_GOLDEN - 6.125f}, 34},
230 };
231 INSTANTIATE_TEST_CASE_P(HardcodedVectors,
233  ::testing::ValuesIn(hardcoded_vectors));
234 
235 AP_GTEST_MAIN()
void test_triangles_indexes(const TestParam &p)
#define M_GOLDEN
Definition: definitions.h:17
static std::vector< TestParam > general_vectors
static const Vector3f triangles[20][3]
INSTANTIATE_TEST_CASE_P(IcosahedronVertices, GeodesicGridTest, ::testing::ValuesIn(icosahedron_vertices))
static TestParam hardcoded_vectors[]
static int _triangle_index(const Vector3f &v, bool inclusive)
#define f(i)
static TestParam icosahedron_vertices[]
TEST_P(GeodesicGridTest, Sections)
AP_GTEST_PRINTATBLE_PARAM_MEMBER(TestParam, v)
static const int NUM_SUBTRIANGLES
static int section(const Vector3f &v, bool inclusive=false)
static int _subtriangle_index(const unsigned int triangle_index, const Vector3f &v, bool inclusive)
static bool section_triangle(unsigned int section_index, Vector3f &a, Vector3f &b, Vector3f &c)
int inclusive_sections[7]