From 7dedaa425491ce13ee995b7ccc4871c5f2960fa6 Mon Sep 17 00:00:00 2001 From: QuadMcFly Date: Sat, 28 Jan 2023 20:19:47 -0500 Subject: [PATCH] Add Octo X8 + to mixer defaults (#12175) --- src/main/flight/mixer.h | 3 ++- src/main/flight/mixer_init.c | 15 ++++++++++++++- src/main/telemetry/mavlink.c | 1 + 3 files changed, 17 insertions(+), 2 deletions(-) diff --git a/src/main/flight/mixer.h b/src/main/flight/mixer.h index 9e7ea6712c..11a6befad8 100644 --- a/src/main/flight/mixer.h +++ b/src/main/flight/mixer.h @@ -57,7 +57,8 @@ typedef enum mixerMode MIXER_CUSTOM = 23, MIXER_CUSTOM_AIRPLANE = 24, MIXER_CUSTOM_TRI = 25, - MIXER_QUADX_1234 = 26 + MIXER_QUADX_1234 = 26, + MIXER_OCTOX8P = 27 } mixerMode_e; typedef enum mixerType diff --git a/src/main/flight/mixer_init.c b/src/main/flight/mixer_init.c index 41cc172d87..4449acd87b 100644 --- a/src/main/flight/mixer_init.c +++ b/src/main/flight/mixer_init.c @@ -152,6 +152,17 @@ static const motorMixer_t mixerOctoX8[] = { { 1.0f, 1.0f, -1.0f, 1.0f }, // UNDER_FRONT_L }; +static const motorMixer_t mixerOctoX8P[] = { + { 1.0f, 0.0f, 1.0f, -1.0f }, // REAR + { 1.0f, -1.0f, 0.0f, 1.0f }, // RIGHT + { 1.0f, 1.0f, 0.0f, 1.0f }, // LEFT + { 1.0f, 0.0f, -1.0f, -1.0f }, // FRONT + { 1.0f, 0.0f, 1.0f, 1.0f }, // UNDER_REAR + { 1.0f, -1.0f, 0.0f, -1.0f }, // UNDER_RIGHT + { 1.0f, 1.0f, 0.0f, -1.0f }, // UNDER_LEFT + { 1.0f, 0.0f, -1.0f, 1.0f }, // UNDER_FRONT +}; + static const motorMixer_t mixerOctoFlatP[] = { { 1.0f, 0.707107f, -0.707107f, 1.0f }, // FRONT_L { 1.0f, -0.707107f, -0.707107f, 1.0f }, // FRONT_R @@ -175,6 +186,7 @@ static const motorMixer_t mixerOctoFlatX[] = { }; #else #define mixerOctoX8 NULL +#define mixerOctoX8P NULL #define mixerOctoFlatP NULL #define mixerOctoFlatX NULL #endif @@ -244,7 +256,8 @@ const mixer_t mixers[] = { { 0, false, NULL }, // MIXER_CUSTOM { 2, true, NULL }, // MIXER_CUSTOM_AIRPLANE { 3, true, NULL }, // MIXER_CUSTOM_TRI - { 4, false, mixerQuadX1234 }, + { 4, false, mixerQuadX1234 }, // MIXER_QUADX_1234 + { 8, false, mixerOctoX8P }, // MIXER_OCTOX8P }; #endif // !USE_QUAD_MIXER_ONLY diff --git a/src/main/telemetry/mavlink.c b/src/main/telemetry/mavlink.c index 7961147352..cbd6d2be24 100644 --- a/src/main/telemetry/mavlink.c +++ b/src/main/telemetry/mavlink.c @@ -456,6 +456,7 @@ void mavlinkSendHUDAndHeartbeat(void) mavSystemType = MAV_TYPE_HEXAROTOR; break; case MIXER_OCTOX8: + case MIXER_OCTOX8P: case MIXER_OCTOFLATP: case MIXER_OCTOFLATX: mavSystemType = MAV_TYPE_OCTOROTOR;