mirror of https://github.com/ArduPilot/ardupilot
AP_Math: AP_GeodesicGrid: make all methods static
Since all members are.
This commit is contained in:
parent
3b05ec1157
commit
9d34b3b996
|
@ -179,7 +179,7 @@ const Matrix3f AP_GeodesicGrid::_mid_inverses[10]{
|
|||
};
|
||||
|
||||
int AP_GeodesicGrid::section(const Vector3f& v,
|
||||
const bool inclusive) const
|
||||
const bool inclusive)
|
||||
{
|
||||
int i = _triangle_index(v, inclusive);
|
||||
if (i < 0) {
|
||||
|
@ -195,7 +195,7 @@ int AP_GeodesicGrid::section(const Vector3f& v,
|
|||
}
|
||||
|
||||
int AP_GeodesicGrid::_neighbor_umbrella_component(int idx,
|
||||
int comp_idx) const
|
||||
int comp_idx)
|
||||
{
|
||||
if (idx < 3) {
|
||||
return _neighbor_umbrellas[idx].components[comp_idx];
|
||||
|
@ -206,7 +206,7 @@ int AP_GeodesicGrid::_neighbor_umbrella_component(int idx,
|
|||
int AP_GeodesicGrid::_from_neighbor_umbrella(int idx,
|
||||
const Vector3f& v,
|
||||
const Vector3f& u,
|
||||
bool inclusive) const
|
||||
bool inclusive)
|
||||
{
|
||||
/* The following comparisons between the umbrella's first and second
|
||||
* vertices' coefficients work for this algorithm because all vertices'
|
||||
|
@ -301,7 +301,7 @@ int AP_GeodesicGrid::_from_neighbor_umbrella(int idx,
|
|||
}
|
||||
|
||||
int AP_GeodesicGrid::_triangle_index(const Vector3f& v,
|
||||
const bool inclusive) const
|
||||
const bool inclusive)
|
||||
{
|
||||
/* w holds the coordinates of v with respect to the basis comprised by the
|
||||
* vectors of T_i */
|
||||
|
@ -436,7 +436,7 @@ int AP_GeodesicGrid::_triangle_index(const Vector3f& v,
|
|||
|
||||
int AP_GeodesicGrid::_subtriangle_index(const unsigned int triangle_index,
|
||||
const Vector3f& v,
|
||||
const bool inclusive) const
|
||||
const bool inclusive)
|
||||
{
|
||||
/* w holds the coordinates of v with respect to the basis comprised by the
|
||||
* vectors of the middle triangle of T_i where i is triangle_index */
|
||||
|
|
|
@ -123,7 +123,7 @@ public:
|
|||
* the null vector or the section isn't found, which might happen when \p
|
||||
* inclusive is false.
|
||||
*/
|
||||
int section(const Vector3f& v, const bool inclusive = false) const;
|
||||
static int section(const Vector3f& v, const bool inclusive = false);
|
||||
|
||||
private:
|
||||
/*
|
||||
|
@ -235,8 +235,8 @@ private:
|
|||
*
|
||||
* @return The icosahedron triangle's index of the component.
|
||||
*/
|
||||
int _neighbor_umbrella_component(int umbrella_index,
|
||||
int component_index) const;
|
||||
static int _neighbor_umbrella_component(int umbrella_index,
|
||||
int component_index);
|
||||
/**
|
||||
* Find the icosahedron triangle index of the component of
|
||||
* #_neighbor_umbrellas[umbrella_index] that is crossed by \p v.
|
||||
|
@ -256,10 +256,10 @@ private:
|
|||
* if \p v is the null vector or the triangle isn't found, which might
|
||||
* happen when \p inclusive is false.
|
||||
*/
|
||||
int _from_neighbor_umbrella(int umbrella_index,
|
||||
const Vector3f& v,
|
||||
const Vector3f& u,
|
||||
bool inclusive) const;
|
||||
static int _from_neighbor_umbrella(int umbrella_index,
|
||||
const Vector3f& v,
|
||||
const Vector3f& u,
|
||||
bool inclusive);
|
||||
|
||||
/**
|
||||
* Find which icosahedron's triangle is crossed by \p v.
|
||||
|
@ -272,7 +272,7 @@ private:
|
|||
* @return The index of the triangle. The value -1 is returned if the
|
||||
* triangle isn't found, which might happen when \p inclusive is false.
|
||||
*/
|
||||
int _triangle_index(const Vector3f& v, const bool inclusive) const;
|
||||
static int _triangle_index(const Vector3f& v, const bool inclusive);
|
||||
|
||||
/**
|
||||
* Find which sub-triangle of the icosahedron's triangle pointed by \p
|
||||
|
@ -292,7 +292,7 @@ private:
|
|||
* @return The index of the sub-triangle. The value -1 is returned if the
|
||||
* triangle isn't found, which might happen when \p inclusive is false.
|
||||
*/
|
||||
int _subtriangle_index(const unsigned int triangle_index,
|
||||
const Vector3f& v,
|
||||
const bool inclusive) const;
|
||||
static int _subtriangle_index(const unsigned int triangle_index,
|
||||
const Vector3f& v,
|
||||
const bool inclusive);
|
||||
};
|
||||
|
|
|
@ -18,8 +18,6 @@
|
|||
|
||||
#include <AP_Math/AP_GeodesicGrid.h>
|
||||
|
||||
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}},
|
||||
|
@ -92,7 +90,7 @@ static void BM_GeodesicGridSections(benchmark::State& state)
|
|||
v = (a + b + c) / 3.0f;
|
||||
|
||||
while (state.KeepRunning()) {
|
||||
int s = grid.section(v);
|
||||
int s = AP_GeodesicGrid::section(v);
|
||||
gbenchmark_escape(&s);
|
||||
}
|
||||
}
|
||||
|
|
|
@ -42,8 +42,6 @@ public:
|
|||
|
||||
class GeodesicGridTest : public ::testing::TestWithParam<TestParam> {
|
||||
protected:
|
||||
static AP_GeodesicGrid grid;
|
||||
|
||||
/**
|
||||
* Test the functions for triangles indexes.
|
||||
*
|
||||
|
@ -51,25 +49,28 @@ protected:
|
|||
*/
|
||||
void test_triangles_indexes(const TestParam& p) {
|
||||
if (p.section >= 0) {
|
||||
int expected_triangle = p.section / grid.NUM_SUBTRIANGLES;
|
||||
int triangle = grid._triangle_index(p.v, false);
|
||||
int expected_triangle =
|
||||
p.section / AP_GeodesicGrid::NUM_SUBTRIANGLES;
|
||||
int triangle = AP_GeodesicGrid::_triangle_index(p.v, false);
|
||||
ASSERT_EQ(expected_triangle, triangle);
|
||||
|
||||
int expected_subtriangle = p.section % grid.NUM_SUBTRIANGLES;
|
||||
int subtriangle = grid._subtriangle_index(triangle, p.v, false);
|
||||
int expected_subtriangle =
|
||||
p.section % AP_GeodesicGrid::NUM_SUBTRIANGLES;
|
||||
int subtriangle =
|
||||
AP_GeodesicGrid::_subtriangle_index(triangle, p.v, false);
|
||||
ASSERT_EQ(expected_subtriangle, subtriangle);
|
||||
} else {
|
||||
int triangle = grid._triangle_index(p.v, false);
|
||||
int triangle = AP_GeodesicGrid::_triangle_index(p.v, false);
|
||||
if (triangle >= 0) {
|
||||
int subtriangle = grid._subtriangle_index(triangle, p.v, false);
|
||||
int subtriangle = AP_GeodesicGrid::_subtriangle_index(triangle,
|
||||
p.v,
|
||||
false);
|
||||
ASSERT_EQ(-1, subtriangle) << "triangle is " << triangle;
|
||||
}
|
||||
}
|
||||
}
|
||||
};
|
||||
|
||||
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}},
|
||||
|
@ -140,10 +141,10 @@ TEST_P(GeodesicGridTest, Sections)
|
|||
auto p = GetParam();
|
||||
|
||||
test_triangles_indexes(p);
|
||||
EXPECT_EQ(p.section, grid.section(p.v));
|
||||
EXPECT_EQ(p.section, AP_GeodesicGrid::section(p.v));
|
||||
|
||||
if (p.section < 0) {
|
||||
int s = grid.section(p.v, true);
|
||||
int s = AP_GeodesicGrid::section(p.v, true);
|
||||
int i;
|
||||
for (i = 0; p.inclusive_sections[i] > 0; i++) {
|
||||
assert(i < 7);
|
||||
|
|
Loading…
Reference in New Issue