From 9df8e5cfea0088e67e47cde14f7da24682897ed1 Mon Sep 17 00:00:00 2001 From: "Pawel Spychalski (DzikuVx)" Date: Wed, 28 Mar 2018 11:43:05 +0200 Subject: [PATCH] mixerMode removed --- src/main/blackbox/blackbox.c | 2 +- src/main/drivers/pwm_mapping.h | 7 +--- src/main/fc/cli.c | 42 ----------------------- src/main/fc/fc_core.c | 8 ++--- src/main/fc/fc_msp.c | 10 +++--- src/main/fc/settings.yaml | 2 +- src/main/flight/mixer.c | 1 - src/main/flight/mixer.h | 39 +++++---------------- src/main/flight/servos.c | 3 +- src/main/target/COLIBRI/config.c | 1 - src/main/target/FALCORE/config.c | 2 +- src/main/target/FF_F35_LIGHTNING/config.c | 2 +- src/main/telemetry/mavlink.c | 34 +++++++----------- 13 files changed, 34 insertions(+), 119 deletions(-) diff --git a/src/main/blackbox/blackbox.c b/src/main/blackbox/blackbox.c index a822d8f87f..8b102d1d75 100644 --- a/src/main/blackbox/blackbox.c +++ b/src/main/blackbox/blackbox.c @@ -476,7 +476,7 @@ static bool testBlackboxConditionUncached(FlightLogFieldCondition condition) return getMotorCount() >= condition - FLIGHT_LOG_FIELD_CONDITION_AT_LEAST_MOTORS_1 + 1; case FLIGHT_LOG_FIELD_CONDITION_TRICOPTER: - return mixerConfig()->mixerMode == MIXER_TRI || mixerConfig()->mixerMode == MIXER_CUSTOM_TRI; + return mixerConfig()->platformType == PLATFORM_TRICOPTER; case FLIGHT_LOG_FIELD_CONDITION_NONZERO_PID_D_0: case FLIGHT_LOG_FIELD_CONDITION_NONZERO_PID_D_1: diff --git a/src/main/drivers/pwm_mapping.h b/src/main/drivers/pwm_mapping.h index da61629cb7..e1db665ec8 100644 --- a/src/main/drivers/pwm_mapping.h +++ b/src/main/drivers/pwm_mapping.h @@ -18,6 +18,7 @@ #pragma once #include "drivers/io_types.h" +#include "flight/mixer.h" #if defined(TARGET_MOTOR_COUNT) #define MAX_PWM_MOTORS TARGET_MOTOR_COUNT @@ -43,12 +44,6 @@ typedef struct rangefinderIOConfig_s { ioTag_t echoTag; } rangefinderIOConfig_t; -typedef enum { - PLATFORM_MULTIROTOR = 0, - PLATFORM_AIRPLANE = 1, - PLATFORM_HELICOPTER = 2 -} flyingPlatformType_e; - typedef struct drv_pwm_config_s { int flyingPlatformType; diff --git a/src/main/fc/cli.c b/src/main/fc/cli.c index 098fbf0554..9abef664e4 100755 --- a/src/main/fc/cli.c +++ b/src/main/fc/cli.c @@ -1966,40 +1966,6 @@ static void cliGpsPassthrough(char *cmdline) } #endif -static void cliMixer(char *cmdline) -{ - int len; - - len = strlen(cmdline); - - if (len == 0) { - cliPrintLinef("Mixer: %s", mixerNames[mixerConfigMutable()->mixerMode - 1]); - return; - } else if (sl_strncasecmp(cmdline, "list", len) == 0) { - cliPrint("Available mixers: "); - for (uint32_t i = 0; ; i++) { - if (mixerNames[i] == NULL) - break; - cliPrintf("%s ", mixerNames[i]); - } - cliPrintLinefeed(); - return; - } - - for (uint32_t i = 0; ; i++) { - if (mixerNames[i] == NULL) { - cliPrintLine("Invalid name"); - return; - } - if (sl_strncasecmp(cmdline, mixerNames[i], len) == 0) { - mixerConfigMutable()->mixerMode = i + 1; - break; - } - } - - cliMixer(""); -} - static void cliMotor(char *cmdline) { int motor_index = 0; @@ -2529,11 +2495,6 @@ static void printConfig(const char *cmdline, bool doDiff) //printResource(dumpMask, &defaultConfig); cliPrintHashLine("mixer"); - const bool equalsDefault = mixerConfig_Copy.mixerMode == mixerConfig()->mixerMode; - const char *formatMixer = "mixer %s"; - cliDefaultPrintLinef(dumpMask, equalsDefault, formatMixer, mixerNames[mixerConfig()->mixerMode - 1]); - cliDumpPrintLinef(dumpMask, equalsDefault, formatMixer, mixerNames[mixerConfig_Copy.mixerMode - 1]); - cliDumpPrintLinef(dumpMask, customMotorMixer(0)->throttle == 0.0f, "\r\nmmix reset\r\n"); printMotorMix(dumpMask, customMotorMixer_CopyArray, customMotorMixer(0)); @@ -2696,9 +2657,6 @@ const clicmd_t cmdTable[] = { CLI_COMMAND_DEF("led", "configure leds", NULL, cliLed), #endif CLI_COMMAND_DEF("map", "configure rc channel order", "[]", cliMap), - CLI_COMMAND_DEF("mixer", "configure mixer", - "list\r\n" - "\t", cliMixer), CLI_COMMAND_DEF("mmix", "custom motor mixer", NULL, cliMotorMix), CLI_COMMAND_DEF("motor", "get/set motor", " []", cliMotor), CLI_COMMAND_DEF("name", "name of craft", NULL, cliName), diff --git a/src/main/fc/fc_core.c b/src/main/fc/fc_core.c index c4012c92c3..d867903a64 100755 --- a/src/main/fc/fc_core.c +++ b/src/main/fc/fc_core.c @@ -610,7 +610,7 @@ void processRx(timeUs_t currentTimeUs) } } - if (mixerConfig()->mixerMode == MIXER_FLYING_WING || mixerConfig()->mixerMode == MIXER_AIRPLANE || mixerConfig()->mixerMode == MIXER_CUSTOM_AIRPLANE) { + if (mixerConfig()->platformType == PLATFORM_AIRPLANE) { DISABLE_FLIGHT_MODE(HEADFREE_MODE); } @@ -754,10 +754,8 @@ void taskMainPidLoop(timeUs_t currentTimeUs) // motors do not spin up while we are trying to arm or disarm. // Allow yaw control for tricopters if the user wants the servo to move even when unarmed. if (isUsingSticksForArming() && rcData[THROTTLE] <= rxConfig()->mincheck - && !((mixerConfig()->mixerMode == MIXER_TRI || mixerConfig()->mixerMode == MIXER_CUSTOM_TRI) && servoConfig()->tri_unarmed_servo) - && mixerConfig()->mixerMode != MIXER_AIRPLANE - && mixerConfig()->mixerMode != MIXER_FLYING_WING - && mixerConfig()->mixerMode != MIXER_CUSTOM_AIRPLANE + && !((mixerConfig()->platformType == PLATFORM_TRICOPTER) && servoConfig()->tri_unarmed_servo) + && mixerConfig()->platformType != PLATFORM_AIRPLANE ) { rcCommand[YAW] = 0; } diff --git a/src/main/fc/fc_msp.c b/src/main/fc/fc_msp.c index ff2f092cb7..a65c6f06fe 100644 --- a/src/main/fc/fc_msp.c +++ b/src/main/fc/fc_msp.c @@ -345,7 +345,7 @@ static bool mspFcProcessOutCommand(uint16_t cmdMSP, sbuf_t *dst, mspPostProcessF // DEPRECATED - Use MSP_API_VERSION case MSP_IDENT: sbufWriteU8(dst, MW_VERSION); - sbufWriteU8(dst, mixerConfig()->mixerMode); + sbufWriteU8(dst, 3); //We no longer have mixerMode, just sent 3 (QuadX) as fallback sbufWriteU8(dst, MSP_PROTOCOL_VERSION); sbufWriteU32(dst, CAP_PLATFORM_32BIT | CAP_DYNBALANCE | CAP_FLAPS | CAP_NAVCAP | CAP_EXTAUX); // "capability" break; @@ -821,7 +821,7 @@ static bool mspFcProcessOutCommand(uint16_t cmdMSP, sbuf_t *dst, mspPostProcessF break; case MSP_MIXER: - sbufWriteU8(dst, mixerConfig()->mixerMode); + sbufWriteU8(dst, 3); // mixerMode no longer supported, send 3 (QuadX) as fallback break; case MSP_RX_CONFIG: @@ -867,7 +867,7 @@ static bool mspFcProcessOutCommand(uint16_t cmdMSP, sbuf_t *dst, mspPostProcessF break; case MSP_BF_CONFIG: - sbufWriteU8(dst, mixerConfig()->mixerMode); + sbufWriteU8(dst, 3); // mixerMode no longer supported, send 3 (QuadX) as fallback sbufWriteU32(dst, featureMask()); @@ -2162,7 +2162,7 @@ static mspResult_e mspFcProcessInCommand(uint16_t cmdMSP, sbuf_t *src) case MSP_SET_MIXER: if (dataSize >= 1) { - mixerConfigMutable()->mixerMode = sbufReadU8(src); + sbufReadU8(src); //This is ignored, no longer supporting mixerMode mixerUpdateStateFlags(); // Required for correct preset functionality } else return MSP_RESULT_ERROR; @@ -2227,7 +2227,7 @@ static mspResult_e mspFcProcessInCommand(uint16_t cmdMSP, sbuf_t *src) case MSP_SET_BF_CONFIG: if (dataSize >= 16) { - mixerConfigMutable()->mixerMode = sbufReadU8(src); // mixerMode + sbufReadU8(src); // mixerMode no longer supported, just swallow mixerUpdateStateFlags(); // Required for correct preset functionality featureClearAll(); diff --git a/src/main/fc/settings.yaml b/src/main/fc/settings.yaml index c2a0291f8c..8c1d46a28f 100644 --- a/src/main/fc/settings.yaml +++ b/src/main/fc/settings.yaml @@ -91,7 +91,7 @@ tables: values: ["PERCENT", "MAH", "MWH"] enum: smartportFuelUnit_e - name: platform_type - values: ["MULTIROTOR", "AIRPLANE", "HELICOPTER"] + values: ["MULTIROTOR", "AIRPLANE", "HELICOPTER", "TRICOPTER", "ROVER", "BOAT"] enum: flyingPlatformType_e groups: diff --git a/src/main/flight/mixer.c b/src/main/flight/mixer.c index a866654e54..80d4c11f1a 100755 --- a/src/main/flight/mixer.c +++ b/src/main/flight/mixer.c @@ -71,7 +71,6 @@ PG_RESET_TEMPLATE(flight3DConfig_t, flight3DConfig, PG_REGISTER_WITH_RESET_TEMPLATE(mixerConfig_t, mixerConfig, PG_MIXER_CONFIG, 1); PG_RESET_TEMPLATE(mixerConfig_t, mixerConfig, - .mixerMode = MIXER_QUADX, .yaw_motor_direction = 1, .yaw_jump_prevention_limit = 200, .platformType = PLATFORM_MULTIROTOR, diff --git a/src/main/flight/mixer.h b/src/main/flight/mixer.h index 196e932b16..0ee1b289c0 100644 --- a/src/main/flight/mixer.h +++ b/src/main/flight/mixer.h @@ -28,36 +28,14 @@ #define YAW_JUMP_PREVENTION_LIMIT_LOW 80 #define YAW_JUMP_PREVENTION_LIMIT_HIGH 500 - -// Note: this is called MultiType/MULTITYPE_* in baseflight. -typedef enum mixerMode -{ - MIXER_TRI = 1, - MIXER_QUADP = 2, - MIXER_QUADX = 3, - MIXER_BICOPTER = 4, - MIXER_GIMBAL = 5, - MIXER_Y6 = 6, - MIXER_HEX6 = 7, - MIXER_FLYING_WING = 8, - MIXER_Y4 = 9, - MIXER_HEX6X = 10, - MIXER_OCTOX8 = 11, - MIXER_OCTOFLATP = 12, - MIXER_OCTOFLATX = 13, - MIXER_AIRPLANE = 14, // airplane / singlecopter / dualcopter (not yet properly supported) - MIXER_HELI_120_CCPM = 15, - MIXER_HELI_90_DEG = 16, - MIXER_VTAIL4 = 17, - MIXER_HEX6H = 18, - MIXER_PPM_TO_SERVO = 19, // PPM -> servo relay - MIXER_DUALCOPTER = 20, - MIXER_SINGLECOPTER = 21, - MIXER_ATAIL4 = 22, - MIXER_CUSTOM = 23, - MIXER_CUSTOM_AIRPLANE = 24, - MIXER_CUSTOM_TRI = 25 -} mixerMode_e; +typedef enum { + PLATFORM_MULTIROTOR = 0, + PLATFORM_AIRPLANE = 1, + PLATFORM_HELICOPTER = 2, + PLATFORM_TRICOPTER = 3, + PLATFORM_ROVER = 4, + PLATFORM_BOAT = 5 +} flyingPlatformType_e; #define DEFAULT_MIXER MIXER_QUADX @@ -77,7 +55,6 @@ typedef struct motorMixer_s { PG_DECLARE_ARRAY(motorMixer_t, MAX_SUPPORTED_MOTORS, customMotorMixer); typedef struct mixerConfig_s { - uint8_t mixerMode; int8_t yaw_motor_direction; uint16_t yaw_jump_prevention_limit; // make limit configurable (original fixed value was 100) uint8_t platformType; diff --git a/src/main/flight/servos.c b/src/main/flight/servos.c index 09108b2dae..33befae656 100755 --- a/src/main/flight/servos.c +++ b/src/main/flight/servos.c @@ -235,8 +235,7 @@ void writeServos(void) /* * in case of tricopters, there might me a need to zero servo output when unarmed */ - const mixerMode_e currentMixerMode = mixerConfig()->mixerMode; - if ((currentMixerMode == MIXER_TRI || currentMixerMode == MIXER_CUSTOM_TRI) && !ARMING_FLAG(ARMED) && !servoConfig()->tri_unarmed_servo) { + if (mixerConfig()->platformType == PLATFORM_TRICOPTER && !ARMING_FLAG(ARMED) && !servoConfig()->tri_unarmed_servo) { zeroServoValue = true; } diff --git a/src/main/target/COLIBRI/config.c b/src/main/target/COLIBRI/config.c index f8a15a3ad6..02c9785f62 100755 --- a/src/main/target/COLIBRI/config.c +++ b/src/main/target/COLIBRI/config.c @@ -31,7 +31,6 @@ void targetConfiguration(void) { - mixerConfigMutable()->mixerMode = MIXER_HEX6X; rxConfigMutable()->serialrx_provider = SERIALRX_SBUS; rxConfigMutable()->receiverType = RX_TYPE_SERIAL; serialConfigMutable()->portConfigs[2].functionMask = FUNCTION_RX_SERIAL; diff --git a/src/main/target/FALCORE/config.c b/src/main/target/FALCORE/config.c index 85cf26bb12..2515a78c3d 100755 --- a/src/main/target/FALCORE/config.c +++ b/src/main/target/FALCORE/config.c @@ -43,7 +43,7 @@ void targetConfiguration(void) { systemConfigMutable()->asyncMode = ASYNC_MODE_NONE; - mixerConfigMutable()->mixerMode = MIXER_QUADX; + mixerConfigMutable()->platformType = PLATFORM_MULTIROTOR; featureSet(FEATURE_VBAT); featureSet(FEATURE_GPS); diff --git a/src/main/target/FF_F35_LIGHTNING/config.c b/src/main/target/FF_F35_LIGHTNING/config.c index 4edb0b6f7b..d55462b72c 100644 --- a/src/main/target/FF_F35_LIGHTNING/config.c +++ b/src/main/target/FF_F35_LIGHTNING/config.c @@ -50,5 +50,5 @@ void targetConfiguration(void) serialConfigMutable()->portConfigs[6].functionMask = FUNCTION_TELEMETRY_SMARTPORT; telemetryConfigMutable()->smartportUartUnidirectional = 1; - mixerConfigMutable()->mixerMode = MIXER_AIRPLANE; + mixerConfigMutable()->platformType = PLATFORM_AIRPLANE; } diff --git a/src/main/telemetry/mavlink.c b/src/main/telemetry/mavlink.c index 6cfabeb69c..713a46d005 100755 --- a/src/main/telemetry/mavlink.c +++ b/src/main/telemetry/mavlink.c @@ -428,34 +428,24 @@ void mavlinkSendHUDAndHeartbeat(void) mavModes |= MAV_MODE_FLAG_SAFETY_ARMED; uint8_t mavSystemType; - switch (mixerConfig()->mixerMode) + switch (mixerConfig()->platformType) { - case MIXER_TRI: - mavSystemType = MAV_TYPE_TRICOPTER; - break; - case MIXER_QUADP: - case MIXER_QUADX: - case MIXER_Y4: - case MIXER_VTAIL4: + case PLATFORM_MULTIROTOR: mavSystemType = MAV_TYPE_QUADROTOR; break; - case MIXER_Y6: - case MIXER_HEX6: - case MIXER_HEX6X: - mavSystemType = MAV_TYPE_HEXAROTOR; + case PLATFORM_TRICOPTER: + mavSystemType = MAV_TYPE_TRICOPTER; break; - case MIXER_OCTOX8: - case MIXER_OCTOFLATP: - case MIXER_OCTOFLATX: - mavSystemType = MAV_TYPE_OCTOROTOR; - break; - case MIXER_FLYING_WING: - case MIXER_AIRPLANE: - case MIXER_CUSTOM_AIRPLANE: + case PLATFORM_AIRPLANE: mavSystemType = MAV_TYPE_FIXED_WING; break; - case MIXER_HELI_120_CCPM: - case MIXER_HELI_90_DEG: + case PLATFORM_ROVER: + mavSystemType = MAV_TYPE_GROUND_ROVER; + break; + case PLATFORM_BOAT: + mavSystemType = MAV_TYPE_SURFACE_BOAT; + break; + case PLATFORM_HELICOPTER: mavSystemType = MAV_TYPE_HELICOPTER; break; default: