mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-30 20:48:33 -04:00
AP_Math: AP_GeodesicGrid: remove section_triangle() function
That function was only being used by the unit tests and the benchmark. In order to remove memory usage, the triangles will be removed, since we don't actually need to keep them in real situations. Thus, this patch removes that function and copy those triangles to the test and benchmark.
This commit is contained in:
parent
c7eb46fae2
commit
8e8ab3af96
@ -148,46 +148,6 @@ int AP_GeodesicGrid::section(const Vector3f& v,
|
||||
return 4 * i + j;
|
||||
}
|
||||
|
||||
bool AP_GeodesicGrid::section_triangle(unsigned int section_index,
|
||||
Vector3f& a,
|
||||
Vector3f& b,
|
||||
Vector3f& c) const
|
||||
{
|
||||
if (section_index >= 20 * NUM_SUBTRIANGLES) {
|
||||
return false;
|
||||
}
|
||||
|
||||
unsigned int i = section_index / NUM_SUBTRIANGLES;
|
||||
unsigned int j = section_index % NUM_SUBTRIANGLES;
|
||||
auto& t = _triangles[i];
|
||||
auto& mt = _mid_triangles[i];
|
||||
|
||||
switch (j) {
|
||||
case 0:
|
||||
a = mt[0];
|
||||
b = mt[1];
|
||||
c = mt[2];
|
||||
break;
|
||||
case 1:
|
||||
a = t[0];
|
||||
b = mt[0];
|
||||
c = mt[2];
|
||||
break;
|
||||
case 2:
|
||||
a = mt[0];
|
||||
b = t[1];
|
||||
c = mt[1];
|
||||
break;
|
||||
case 3:
|
||||
a = mt[2];
|
||||
b = mt[1];
|
||||
c = t[2];
|
||||
break;
|
||||
}
|
||||
|
||||
return true;
|
||||
}
|
||||
|
||||
void AP_GeodesicGrid::_init_opposite_triangles()
|
||||
{
|
||||
for (int i = 0, j = 10; i < 10; i++, j++) {
|
||||
|
@ -127,25 +127,6 @@ public:
|
||||
*/
|
||||
int section(const Vector3f& v, const bool inclusive = false) const;
|
||||
|
||||
/**
|
||||
* Get the triangle that defines the section at index \p section_index.
|
||||
*
|
||||
* @param section_index[in] The section index.
|
||||
*
|
||||
* @param a[out] The triangle's first vertex.
|
||||
* @param b[out] The triangle's second vertex.
|
||||
* @param c[out] The triangle's third vertex.
|
||||
*
|
||||
* @return If \p section_index is valid, true is returned and the triangle
|
||||
* vertices are assigned to \p a, \p b and \p c, in that order. Otherwise,
|
||||
* false is returned and the values of the vertices parameters are left
|
||||
* unmodified.
|
||||
*/
|
||||
bool section_triangle(unsigned int section_index,
|
||||
Vector3f& a,
|
||||
Vector3f& b,
|
||||
Vector3f& c) const;
|
||||
|
||||
private:
|
||||
/*
|
||||
* The following are concepts used in the description of the private
|
||||
|
@ -20,12 +20,75 @@
|
||||
|
||||
static AP_GeodesicGrid grid;
|
||||
|
||||
static const Vector3f triangles[20][3] = {
|
||||
{{-M_GOLDEN, 1, 0}, {-1, 0,-M_GOLDEN}, {-M_GOLDEN,-1, 0}},
|
||||
{{-1, 0,-M_GOLDEN}, {-M_GOLDEN,-1, 0}, { 0,-M_GOLDEN,-1}},
|
||||
{{-M_GOLDEN,-1, 0}, { 0,-M_GOLDEN,-1}, { 0,-M_GOLDEN, 1}},
|
||||
{{-1, 0,-M_GOLDEN}, { 0,-M_GOLDEN,-1}, { 1, 0,-M_GOLDEN}},
|
||||
{{ 0,-M_GOLDEN,-1}, { 0,-M_GOLDEN, 1}, { M_GOLDEN,-1, 0}},
|
||||
{{ 0,-M_GOLDEN,-1}, { 1, 0,-M_GOLDEN}, { M_GOLDEN,-1, 0}},
|
||||
{{ M_GOLDEN,-1, 0}, { 1, 0,-M_GOLDEN}, { M_GOLDEN, 1, 0}},
|
||||
{{ 1, 0,-M_GOLDEN}, { M_GOLDEN, 1, 0}, { 0, M_GOLDEN,-1}},
|
||||
{{ 1, 0,-M_GOLDEN}, { 0, M_GOLDEN,-1}, {-1, 0,-M_GOLDEN}},
|
||||
{{ 0, M_GOLDEN,-1}, {-M_GOLDEN, 1, 0}, {-1, 0,-M_GOLDEN}},
|
||||
|
||||
{{ M_GOLDEN,-1, 0}, { 1, 0, M_GOLDEN}, { M_GOLDEN, 1, 0}},
|
||||
{{ 1, 0, M_GOLDEN}, { M_GOLDEN, 1, 0}, { 0, M_GOLDEN, 1}},
|
||||
{{ M_GOLDEN, 1, 0}, { 0, M_GOLDEN, 1}, { 0, M_GOLDEN,-1}},
|
||||
{{ 1, 0, M_GOLDEN}, { 0, M_GOLDEN, 1}, {-1, 0, M_GOLDEN}},
|
||||
{{ 0, M_GOLDEN, 1}, { 0, M_GOLDEN,-1}, {-M_GOLDEN, 1, 0}},
|
||||
{{ 0, M_GOLDEN, 1}, {-1, 0, M_GOLDEN}, {-M_GOLDEN, 1, 0}},
|
||||
{{-M_GOLDEN, 1, 0}, {-1, 0, M_GOLDEN}, {-M_GOLDEN,-1, 0}},
|
||||
{{-1, 0, M_GOLDEN}, {-M_GOLDEN,-1, 0}, { 0,-M_GOLDEN, 1}},
|
||||
{{-1, 0, M_GOLDEN}, { 0,-M_GOLDEN, 1}, { 1, 0, M_GOLDEN}},
|
||||
{{ 0,-M_GOLDEN, 1}, { M_GOLDEN,-1, 0}, { 1, 0, M_GOLDEN}},
|
||||
};
|
||||
|
||||
static bool section_triangle(unsigned int section_index,
|
||||
Vector3f& a,
|
||||
Vector3f& b,
|
||||
Vector3f& c) {
|
||||
if (section_index >= 80) {
|
||||
return false;
|
||||
}
|
||||
|
||||
unsigned int i = section_index / 4;
|
||||
unsigned int j = section_index % 4;
|
||||
auto& t = triangles[i];
|
||||
Vector3f mt[3]{(t[0] + t[1]) / 2, (t[1] + t[2]) / 2, (t[2] + t[0]) / 2};
|
||||
|
||||
switch (j) {
|
||||
case 0:
|
||||
a = mt[0];
|
||||
b = mt[1];
|
||||
c = mt[2];
|
||||
break;
|
||||
case 1:
|
||||
a = t[0];
|
||||
b = mt[0];
|
||||
c = mt[2];
|
||||
break;
|
||||
case 2:
|
||||
a = mt[0];
|
||||
b = t[1];
|
||||
c = mt[1];
|
||||
break;
|
||||
case 3:
|
||||
a = mt[2];
|
||||
b = mt[1];
|
||||
c = t[2];
|
||||
break;
|
||||
}
|
||||
|
||||
return true;
|
||||
}
|
||||
|
||||
static void BM_GeodesicGridSections(benchmark::State& state)
|
||||
{
|
||||
Vector3f v, a, b, c;
|
||||
int section = state.range_x();
|
||||
|
||||
grid.section_triangle(section, a, b, c);
|
||||
section_triangle(section, a, b, c);
|
||||
v = (a + b + c) / 3.0f;
|
||||
|
||||
while (state.KeepRunning()) {
|
||||
|
@ -70,6 +70,69 @@ protected:
|
||||
|
||||
AP_GeodesicGrid GeodesicGridTest::grid;
|
||||
|
||||
static const Vector3f triangles[20][3] = {
|
||||
{{-M_GOLDEN, 1, 0}, {-1, 0,-M_GOLDEN}, {-M_GOLDEN,-1, 0}},
|
||||
{{-1, 0,-M_GOLDEN}, {-M_GOLDEN,-1, 0}, { 0,-M_GOLDEN,-1}},
|
||||
{{-M_GOLDEN,-1, 0}, { 0,-M_GOLDEN,-1}, { 0,-M_GOLDEN, 1}},
|
||||
{{-1, 0,-M_GOLDEN}, { 0,-M_GOLDEN,-1}, { 1, 0,-M_GOLDEN}},
|
||||
{{ 0,-M_GOLDEN,-1}, { 0,-M_GOLDEN, 1}, { M_GOLDEN,-1, 0}},
|
||||
{{ 0,-M_GOLDEN,-1}, { 1, 0,-M_GOLDEN}, { M_GOLDEN,-1, 0}},
|
||||
{{ M_GOLDEN,-1, 0}, { 1, 0,-M_GOLDEN}, { M_GOLDEN, 1, 0}},
|
||||
{{ 1, 0,-M_GOLDEN}, { M_GOLDEN, 1, 0}, { 0, M_GOLDEN,-1}},
|
||||
{{ 1, 0,-M_GOLDEN}, { 0, M_GOLDEN,-1}, {-1, 0,-M_GOLDEN}},
|
||||
{{ 0, M_GOLDEN,-1}, {-M_GOLDEN, 1, 0}, {-1, 0,-M_GOLDEN}},
|
||||
|
||||
{{ M_GOLDEN,-1, 0}, { 1, 0, M_GOLDEN}, { M_GOLDEN, 1, 0}},
|
||||
{{ 1, 0, M_GOLDEN}, { M_GOLDEN, 1, 0}, { 0, M_GOLDEN, 1}},
|
||||
{{ M_GOLDEN, 1, 0}, { 0, M_GOLDEN, 1}, { 0, M_GOLDEN,-1}},
|
||||
{{ 1, 0, M_GOLDEN}, { 0, M_GOLDEN, 1}, {-1, 0, M_GOLDEN}},
|
||||
{{ 0, M_GOLDEN, 1}, { 0, M_GOLDEN,-1}, {-M_GOLDEN, 1, 0}},
|
||||
{{ 0, M_GOLDEN, 1}, {-1, 0, M_GOLDEN}, {-M_GOLDEN, 1, 0}},
|
||||
{{-M_GOLDEN, 1, 0}, {-1, 0, M_GOLDEN}, {-M_GOLDEN,-1, 0}},
|
||||
{{-1, 0, M_GOLDEN}, {-M_GOLDEN,-1, 0}, { 0,-M_GOLDEN, 1}},
|
||||
{{-1, 0, M_GOLDEN}, { 0,-M_GOLDEN, 1}, { 1, 0, M_GOLDEN}},
|
||||
{{ 0,-M_GOLDEN, 1}, { M_GOLDEN,-1, 0}, { 1, 0, M_GOLDEN}},
|
||||
};
|
||||
|
||||
static bool section_triangle(unsigned int section_index,
|
||||
Vector3f& a,
|
||||
Vector3f& b,
|
||||
Vector3f& c) {
|
||||
if (section_index >= 80) {
|
||||
return false;
|
||||
}
|
||||
|
||||
unsigned int i = section_index / 4;
|
||||
unsigned int j = section_index % 4;
|
||||
auto& t = triangles[i];
|
||||
Vector3f mt[3]{(t[0] + t[1]) / 2, (t[1] + t[2]) / 2, (t[2] + t[0]) / 2};
|
||||
|
||||
switch (j) {
|
||||
case 0:
|
||||
a = mt[0];
|
||||
b = mt[1];
|
||||
c = mt[2];
|
||||
break;
|
||||
case 1:
|
||||
a = t[0];
|
||||
b = mt[0];
|
||||
c = mt[2];
|
||||
break;
|
||||
case 2:
|
||||
a = mt[0];
|
||||
b = t[1];
|
||||
c = mt[1];
|
||||
break;
|
||||
case 3:
|
||||
a = mt[2];
|
||||
b = mt[1];
|
||||
c = t[2];
|
||||
break;
|
||||
}
|
||||
|
||||
return true;
|
||||
}
|
||||
|
||||
AP_GTEST_PRINTATBLE_PARAM_MEMBER(TestParam, v);
|
||||
|
||||
TEST_P(GeodesicGridTest, Sections)
|
||||
@ -116,11 +179,10 @@ INSTANTIATE_TEST_CASE_P(IcosahedronVertices,
|
||||
static std::vector<TestParam> centroid_vectors = []()
|
||||
{
|
||||
std::vector<TestParam> params;
|
||||
AP_GeodesicGrid grid;
|
||||
for (int i = 0; i < 20 * AP_GeodesicGrid::NUM_SUBTRIANGLES; i++) {
|
||||
Vector3f a, b, c;
|
||||
TestParam p;
|
||||
grid.section_triangle(i, a, b, c);
|
||||
section_triangle(i, a, b, c);
|
||||
p.section = i;
|
||||
p.v = (a + b + c) / 3;
|
||||
params.push_back(p);
|
||||
|
Loading…
Reference in New Issue
Block a user