mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-01 13:38:38 -04:00
AP_Math: AP_GeodesicGrid: change order of triangles
- Change the order of the icosahedron triangles so that there's a uniform way of finding the opposite triangle. The order visually still makes sense. - Change test to accommodate the order change.
This commit is contained in:
parent
ea412ad629
commit
4398e1e49b
@ -115,18 +115,9 @@ AP_GeodesicGrid::AP_GeodesicGrid()
|
||||
{{ 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}},
|
||||
{{-1, 0, M_GOLDEN}, { 0,-M_GOLDEN, 1}, { 1, 0, M_GOLDEN}},
|
||||
{{ 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}},
|
||||
{{ 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}, {-M_GOLDEN, 1, 0}, {-1, 0, M_GOLDEN}}
|
||||
}
|
||||
{
|
||||
_init_opposite_triangles();
|
||||
_init_mid_triangles();
|
||||
_init_all_inverses();
|
||||
}
|
||||
@ -187,6 +178,15 @@ bool AP_GeodesicGrid::section_triangle(unsigned int section_index,
|
||||
return true;
|
||||
}
|
||||
|
||||
void AP_GeodesicGrid::_init_opposite_triangles()
|
||||
{
|
||||
for (int i = 0, j = 10; i < 10; i++, j++) {
|
||||
_triangles[j][0] = -_triangles[i][0];
|
||||
_triangles[j][1] = -_triangles[i][1];
|
||||
_triangles[j][2] = -_triangles[i][2];
|
||||
}
|
||||
}
|
||||
|
||||
void AP_GeodesicGrid::_init_mid_triangles()
|
||||
{
|
||||
for (int i = 0; i < 20; i++) {
|
||||
|
@ -54,18 +54,22 @@
|
||||
* (( 1, 0,-g), ( g, 1, 0), ( 0, g,-1)),
|
||||
* (( 1, 0,-g), ( 0, g,-1), (-1, 0,-g)),
|
||||
* (( 0, g,-1), (-g, 1, 0), (-1, 0,-g)),
|
||||
* ((-g, 1, 0), (-1, 0, g), (-g,-1, 0)),
|
||||
* ((-1, 0, g), (-g,-1, 0), ( 0,-g, 1)),
|
||||
* ((-1, 0, g), ( 0,-g, 1), ( 1, 0, g)),
|
||||
* (( 0,-g, 1), ( 1, 0, g), ( g,-1, 0)),
|
||||
* (( g,-1, 0), ( 1, 0, g), ( g, 1, 0)),
|
||||
* (( 1, 0, g), ( g, 1, 0), ( 0, g, 1)),
|
||||
* (( g, 1, 0), ( 0, g, 1), ( 0, g,-1)),
|
||||
* (( 1, 0, g), ( 0, g, 1), (-1, 0, g)),
|
||||
* (( 0, g, 1), ( 0, g,-1), (-g, 1, 0)),
|
||||
* (( 0, g, 1), (-g, 1, 0), (-1, 0, g))
|
||||
* -T_0,
|
||||
* -T_1,
|
||||
* -T_2,
|
||||
* -T_3,
|
||||
* -T_4,
|
||||
* -T_5,
|
||||
* -T_6,
|
||||
* -T_7,
|
||||
* -T_8,
|
||||
* -T_9,
|
||||
* )
|
||||
*
|
||||
* Where for a given T_i = (a, b, c), -T_i = (-a, -b, -c). We call -T_i the
|
||||
* opposite triangle of T_i in this specification. For any i in [0,20), T_j is
|
||||
* the opposite of T_i iff j = (i + 10) % 20.
|
||||
*
|
||||
* Let an icosahedron triangle T be defined as T = (a, b, c). The "middle
|
||||
* triangle" M is defined as the triangle formed by the points that bisect the
|
||||
* edges of T. M is defined by:
|
||||
@ -143,7 +147,7 @@ private:
|
||||
/**
|
||||
* The icosahedron's triangles. The item `_triangles[i]` represents T_i.
|
||||
*/
|
||||
const Vector3f _triangles[20][3];
|
||||
Vector3f _triangles[20][3];
|
||||
|
||||
/**
|
||||
* The inverses of the change-of-basis matrices for the icosahedron
|
||||
@ -168,6 +172,11 @@ private:
|
||||
*/
|
||||
Matrix3f _mid_inverses[20];
|
||||
|
||||
/**
|
||||
* Initialize the opposite of the first 10 icosahedron triangles.
|
||||
*/
|
||||
void _init_opposite_triangles();
|
||||
|
||||
/**
|
||||
* Initialize the vertices of the middle triangles as specified by
|
||||
* #_mid_triangles.
|
||||
|
@ -70,17 +70,17 @@ TEST_P(GeodesicGridTest, Sections)
|
||||
}
|
||||
|
||||
static TestParam icosahedron_vertices[] = {
|
||||
{{ M_GOLDEN, 1.0f, 0.0f}, -1, {27, 30, 59, 62, 65, -1}},
|
||||
{{ M_GOLDEN, -1.0f, 0.0f}, -1, {19, 23, 25, 55, 57, -1}},
|
||||
{{-M_GOLDEN, 1.0f, 0.0f}, -1, { 1, 38, 41, 75, 78, -1}},
|
||||
{{-M_GOLDEN, -1.0f, 0.0f}, -1, { 3, 6, 9, 43, 46, -1}},
|
||||
{{ 1.0f, 0.0f, M_GOLDEN}, -1, {51, 54, 58, 61, 69, -1}},
|
||||
{{-1.0f, 0.0f, M_GOLDEN}, -1, {42, 45, 49, 71, 79, -1}},
|
||||
{{ M_GOLDEN, 1.0f, 0.0f}, -1, {27, 30, 43, 46, 49, -1}},
|
||||
{{ M_GOLDEN, -1.0f, 0.0f}, -1, {19, 23, 25, 41, 78, -1}},
|
||||
{{-M_GOLDEN, 1.0f, 0.0f}, -1, { 1, 38, 59, 63, 65, -1}},
|
||||
{{-M_GOLDEN, -1.0f, 0.0f}, -1, { 3, 6, 9, 67, 70, -1}},
|
||||
{{ 1.0f, 0.0f, M_GOLDEN}, -1, {42, 45, 53, 75, 79, -1}},
|
||||
{{-1.0f, 0.0f, M_GOLDEN}, -1, {55, 62, 66, 69, 73, -1}},
|
||||
{{ 1.0f, 0.0f, -M_GOLDEN}, -1, {15, 22, 26, 29, 33, -1}},
|
||||
{{-1.0f, 0.0f, -M_GOLDEN}, -1, { 2, 5, 13, 35, 39, -1}},
|
||||
{{0.0f, M_GOLDEN, 1.0f}, -1, {63, 66, 70, 73, 77, -1}},
|
||||
{{0.0f, M_GOLDEN, -1.0f}, -1, {31, 34, 37, 67, 74, -1}},
|
||||
{{0.0f, -M_GOLDEN, 1.0f}, -1, {11, 18, 47, 50, 53, -1}},
|
||||
{{0.0f, M_GOLDEN, 1.0f}, -1, {47, 50, 54, 57, 61, -1}},
|
||||
{{0.0f, M_GOLDEN, -1.0f}, -1, {31, 34, 37, 51, 58, -1}},
|
||||
{{0.0f, -M_GOLDEN, 1.0f}, -1, {11, 18, 71, 74, 77, -1}},
|
||||
{{0.0f, -M_GOLDEN, -1.0f}, -1, { 7, 10, 14, 17, 21, -1}},
|
||||
};
|
||||
INSTANTIATE_TEST_CASE_P(IcosahedronVertices,
|
||||
@ -117,8 +117,8 @@ static TestParam hardcoded_vectors[] = {
|
||||
{{.25f * M_GOLDEN, -.25f * (13.0f * M_GOLDEN + 1.0f), - 1.25f}, 17},
|
||||
/* 3 * m_a + 2 * m_b 0 * m_c for T_4 */
|
||||
{{M_GOLDEN, -4.0f * M_GOLDEN -1.0f, 1.0f}, -1, {16, 18, -1}},
|
||||
/* 2 * m_c + (1 / 3) * m_b + .1 * c for T_17 */
|
||||
{{-.2667f, .1667f * M_GOLDEN, 2.2667f * M_GOLDEN + .1667f}, 71},
|
||||
/* 2 * m_c + (1 / 3) * m_b + .1 * c for T_13 */
|
||||
{{-.2667f, .1667f * M_GOLDEN, 2.2667f * M_GOLDEN + .1667f}, 55},
|
||||
/* .25 * m_a + 5 * b + 2 * m_b for T_8 */
|
||||
{{-.875f, 6.125f * M_GOLDEN, -1.125f * M_GOLDEN - 6.125f}, 34},
|
||||
};
|
||||
|
Loading…
Reference in New Issue
Block a user