Add Mixer quad1234
This commit is contained in:
parent
f269f653f5
commit
10809ba6b6
|
@ -206,6 +206,13 @@ static const motorMixer_t mixerSingleProp[] = {
|
||||||
{ 1.0f, 0.0f, 0.0f, 0.0f },
|
{ 1.0f, 0.0f, 0.0f, 0.0f },
|
||||||
};
|
};
|
||||||
|
|
||||||
|
static const motorMixer_t mixerQuadX1234[] = {
|
||||||
|
{ 1.0f, 1.0f, -1.0f, -1.0f }, // FRONT_L
|
||||||
|
{ 1.0f, -1.0f, -1.0f, 1.0f }, // FRONT_R
|
||||||
|
{ 1.0f, -1.0f, 1.0f, -1.0f }, // REAR_R
|
||||||
|
{ 1.0f, 1.0f, 1.0f, 1.0f }, // REAR_L
|
||||||
|
};
|
||||||
|
|
||||||
// Keep synced with mixerMode_e
|
// Keep synced with mixerMode_e
|
||||||
const mixer_t mixers[] = {
|
const mixer_t mixers[] = {
|
||||||
// motors, use servo, motor mixer
|
// motors, use servo, motor mixer
|
||||||
|
@ -235,6 +242,7 @@ 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 },
|
||||||
};
|
};
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
@ -318,6 +326,7 @@ const mixerRules_t servoMixers[] = {
|
||||||
{ 0, NULL }, // MULTITYPE_CUSTOM
|
{ 0, NULL }, // MULTITYPE_CUSTOM
|
||||||
{ 0, NULL }, // MULTITYPE_CUSTOM_PLANE
|
{ 0, NULL }, // MULTITYPE_CUSTOM_PLANE
|
||||||
{ 0, NULL }, // MULTITYPE_CUSTOM_TRI
|
{ 0, NULL }, // MULTITYPE_CUSTOM_TRI
|
||||||
|
{ 0, NULL },
|
||||||
};
|
};
|
||||||
|
|
||||||
static servoMixer_t *customServoMixers;
|
static servoMixer_t *customServoMixers;
|
||||||
|
|
|
@ -50,7 +50,8 @@ typedef enum mixerMode
|
||||||
MIXER_ATAIL4 = 22,
|
MIXER_ATAIL4 = 22,
|
||||||
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
|
||||||
} mixerMode_e;
|
} mixerMode_e;
|
||||||
|
|
||||||
// Custom mixer data per motor
|
// Custom mixer data per motor
|
||||||
|
|
|
@ -164,7 +164,7 @@ static const char * const mixerNames[] = {
|
||||||
"FLYING_WING", "Y4", "HEX6X", "OCTOX8", "OCTOFLATP", "OCTOFLATX",
|
"FLYING_WING", "Y4", "HEX6X", "OCTOX8", "OCTOFLATP", "OCTOFLATX",
|
||||||
"AIRPLANE", "HELI_120_CCPM", "HELI_90_DEG", "VTAIL4",
|
"AIRPLANE", "HELI_120_CCPM", "HELI_90_DEG", "VTAIL4",
|
||||||
"HEX6H", "PPM_TO_SERVO", "DUALCOPTER", "SINGLECOPTER",
|
"HEX6H", "PPM_TO_SERVO", "DUALCOPTER", "SINGLECOPTER",
|
||||||
"ATAIL4", "CUSTOM", "CUSTOMAIRPLANE", "CUSTOMTRI", NULL
|
"ATAIL4", "CUSTOM", "CUSTOMAIRPLANE", "CUSTOMTRI", "QUADX1234", NULL
|
||||||
};
|
};
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
|
Loading…
Reference in New Issue