Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Add Octo X8 + to mixer defaults #12175

Merged
merged 1 commit into from
Jan 29, 2023
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Jump to
Jump to file
Failed to load files.
Diff view
Diff view
3 changes: 2 additions & 1 deletion src/main/flight/mixer.h
Original file line number Diff line number Diff line change
Expand Up @@ -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
Expand Down
15 changes: 14 additions & 1 deletion src/main/flight/mixer_init.c
Original file line number Diff line number Diff line change
Expand Up @@ -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
Expand All @@ -175,6 +186,7 @@ static const motorMixer_t mixerOctoFlatX[] = {
};
#else
#define mixerOctoX8 NULL
#define mixerOctoX8P NULL
#define mixerOctoFlatP NULL
#define mixerOctoFlatX NULL
#endif
Expand Down Expand Up @@ -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

Expand Down
1 change: 1 addition & 0 deletions src/main/telemetry/mavlink.c
Original file line number Diff line number Diff line change
Expand Up @@ -455,6 +455,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;
Expand Down