mirror of
https://github.com/betaflight/betaflight.git
synced 2025-07-24 16:55:36 +03:00
Add Octo X8 + to mixer defaults (#12175)
This commit is contained in:
parent
ecdbba2ce2
commit
7dedaa4254
3 changed files with 17 additions and 2 deletions
|
@ -57,7 +57,8 @@ typedef enum mixerMode
|
||||||
MIXER_CUSTOM = 23,
|
MIXER_CUSTOM = 23,
|
||||||
MIXER_CUSTOM_AIRPLANE = 24,
|
MIXER_CUSTOM_AIRPLANE = 24,
|
||||||
MIXER_CUSTOM_TRI = 25,
|
MIXER_CUSTOM_TRI = 25,
|
||||||
MIXER_QUADX_1234 = 26
|
MIXER_QUADX_1234 = 26,
|
||||||
|
MIXER_OCTOX8P = 27
|
||||||
} mixerMode_e;
|
} mixerMode_e;
|
||||||
|
|
||||||
typedef enum mixerType
|
typedef enum mixerType
|
||||||
|
|
|
@ -152,6 +152,17 @@ static const motorMixer_t mixerOctoX8[] = {
|
||||||
{ 1.0f, 1.0f, -1.0f, 1.0f }, // UNDER_FRONT_L
|
{ 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[] = {
|
static const motorMixer_t mixerOctoFlatP[] = {
|
||||||
{ 1.0f, 0.707107f, -0.707107f, 1.0f }, // FRONT_L
|
{ 1.0f, 0.707107f, -0.707107f, 1.0f }, // FRONT_L
|
||||||
{ 1.0f, -0.707107f, -0.707107f, 1.0f }, // FRONT_R
|
{ 1.0f, -0.707107f, -0.707107f, 1.0f }, // FRONT_R
|
||||||
|
@ -175,6 +186,7 @@ static const motorMixer_t mixerOctoFlatX[] = {
|
||||||
};
|
};
|
||||||
#else
|
#else
|
||||||
#define mixerOctoX8 NULL
|
#define mixerOctoX8 NULL
|
||||||
|
#define mixerOctoX8P NULL
|
||||||
#define mixerOctoFlatP NULL
|
#define mixerOctoFlatP NULL
|
||||||
#define mixerOctoFlatX NULL
|
#define mixerOctoFlatX NULL
|
||||||
#endif
|
#endif
|
||||||
|
@ -244,7 +256,8 @@ const mixer_t mixers[] = {
|
||||||
{ 0, false, NULL }, // MIXER_CUSTOM
|
{ 0, false, NULL }, // MIXER_CUSTOM
|
||||||
{ 2, true, NULL }, // MIXER_CUSTOM_AIRPLANE
|
{ 2, true, NULL }, // MIXER_CUSTOM_AIRPLANE
|
||||||
{ 3, true, NULL }, // MIXER_CUSTOM_TRI
|
{ 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
|
#endif // !USE_QUAD_MIXER_ONLY
|
||||||
|
|
||||||
|
|
|
@ -456,6 +456,7 @@ void mavlinkSendHUDAndHeartbeat(void)
|
||||||
mavSystemType = MAV_TYPE_HEXAROTOR;
|
mavSystemType = MAV_TYPE_HEXAROTOR;
|
||||||
break;
|
break;
|
||||||
case MIXER_OCTOX8:
|
case MIXER_OCTOX8:
|
||||||
|
case MIXER_OCTOX8P:
|
||||||
case MIXER_OCTOFLATP:
|
case MIXER_OCTOFLATP:
|
||||||
case MIXER_OCTOFLATX:
|
case MIXER_OCTOFLATX:
|
||||||
mavSystemType = MAV_TYPE_OCTOROTOR;
|
mavSystemType = MAV_TYPE_OCTOROTOR;
|
||||||
|
|
Loading…
Add table
Add a link
Reference in a new issue