Skip to content

Commit

Permalink
mixprofile development
Browse files Browse the repository at this point in the history
  • Loading branch information
haoxiang.qiu committed Nov 14, 2022
1 parent cbbef19 commit 67390e1
Show file tree
Hide file tree
Showing 12 changed files with 119 additions and 156 deletions.
19 changes: 8 additions & 11 deletions src/main/drivers/pwm_mapping.c
Original file line number Diff line number Diff line change
Expand Up @@ -47,6 +47,13 @@ enum {
MAP_TO_SERVO_OUTPUT,
};

typedef struct {
int maxTimMotorCount;
int maxTimServoCount;
const timerHardware_t * timMotors[MAX_PWM_OUTPUT_PORTS];
const timerHardware_t * timServos[MAX_PWM_OUTPUT_PORTS];
} timMotorServoHardware_t;

static pwmInitError_e pwmInitError = PWM_INIT_ERROR_NONE;

static const char * pwmInitErrorMsg[] = {
Expand Down Expand Up @@ -220,12 +227,10 @@ static void timerHardwareOverride(timerHardware_t * timer) {

void pwmBuildTimerOutputList(timMotorServoHardware_t * timOutputs, bool isMixerUsingServos)
{
LOG_INFO(PWM, "pwmBuildTimerOutputList");
timOutputs->maxTimMotorCount = 0;
timOutputs->maxTimServoCount = 0;

uint8_t motorCount = getMotorCount();
LOG_INFO(PWM, "motorCount %d", motorCount);
uint8_t motorIdx = 0;

for (int idx = 0; idx < timerHardwareCount; idx++) {
Expand Down Expand Up @@ -387,19 +392,11 @@ bool pwmMotorAndServoInit(void)

// Build temporary timer mappings for motor and servo
pwmBuildTimerOutputList(&timOutputs, isMixerUsingServos());

// At this point we have built tables of timers suitable for motor and servo mappings
// Now we can actually initialize them according to motor/servo count from mixer
pwmInitMotors(&timOutputs);
pwmInitServos(&timOutputs);

return (pwmInitError == PWM_INIT_ERROR_NONE);
}

// bool pwmMotorAndServoHotInit(timMotorServoHardware_t* timOutputs)
// {
// resetAllocatedOutputPortCount();
// pwmInitMotors(timOutputs);
// pwmInitServos(timOutputs);

// return (pwmInitError == PWM_INIT_ERROR_NONE);
// }
10 changes: 0 additions & 10 deletions src/main/drivers/pwm_mapping.h
Original file line number Diff line number Diff line change
Expand Up @@ -18,7 +18,6 @@
#pragma once

#include "drivers/io_types.h"
#include "drivers/timer.h"
#include "flight/mixer_profile.h"
#include "flight/servos.h"

Expand Down Expand Up @@ -62,13 +61,6 @@ typedef enum {
PWM_INIT_ERROR_TIMER_INIT_FAILED,
} pwmInitError_e;

typedef struct {
int maxTimMotorCount;
int maxTimServoCount;
const timerHardware_t * timMotors[MAX_PWM_OUTPUT_PORTS];
const timerHardware_t * timServos[MAX_PWM_OUTPUT_PORTS];
} timMotorServoHardware_t;

typedef struct rangefinderIOConfig_s {
ioTag_t triggerTag;
ioTag_t echoTag;
Expand All @@ -79,9 +71,7 @@ typedef struct {
bool isDSHOT;
} motorProtocolProperties_t;

void pwmBuildTimerOutputList(timMotorServoHardware_t * timOutputs, bool isMixerUsingServos);
bool pwmMotorAndServoInit(void);
// bool pwmMotorAndServoHotInit(timMotorServoHardware_t* timOutputs);
const motorProtocolProperties_t * getMotorProtocolProperties(motorPwmProtocolTypes_e proto);
pwmInitError_e getPwmInitError(void);
const char * getPwmInitErrorMessage(void);
4 changes: 0 additions & 4 deletions src/main/drivers/pwm_output.c
Original file line number Diff line number Diff line change
Expand Up @@ -113,10 +113,6 @@ static uint8_t commandsBuff[DHSOT_COMMAND_QUEUE_SIZE];
static currentExecutingCommand_t currentExecutingCommand;
#endif

void resetAllocatedOutputPortCount(void){
allocatedOutputPortCount = 0;
}

static void pwmOutConfigTimer(pwmOutputPort_t * p, TCH_t * tch, uint32_t hz, uint16_t period, uint16_t value)
{
p->tch = tch;
Expand Down
1 change: 0 additions & 1 deletion src/main/drivers/pwm_output.h
Original file line number Diff line number Diff line change
Expand Up @@ -34,7 +34,6 @@ void pwmRequestMotorTelemetry(int motorIndex);

ioTag_t pwmGetMotorPinTag(int motorIndex);

void resetAllocatedOutputPortCount(void);
void pwmWriteMotor(uint8_t index, uint16_t value);
void pwmShutdownPulsesForAllMotors(uint8_t motorCount);
void pwmCompleteMotorUpdate(void);
Expand Down
33 changes: 10 additions & 23 deletions src/main/fc/cli.c
Original file line number Diff line number Diff line change
Expand Up @@ -81,7 +81,6 @@ bool cliMode = false;

#include "flight/failsafe.h"
#include "flight/imu.h"
// #include "flight/mixer.h"
#include "flight/mixer_profile.h"
#include "flight/pid.h"
#include "flight/servos.h"
Expand Down Expand Up @@ -283,7 +282,6 @@ typedef enum {
DUMP_MASTER = (1 << 0),
DUMP_PROFILE = (1 << 1),
DUMP_BATTERY_PROFILE = (1 << 2),
// DUMP_RATES = (1 << 3),
DUMP_MIXER_PROFILE = (1 << 3),
DUMP_ALL = (1 << 4),
DO_DIFF = (1 << 5),
Expand Down Expand Up @@ -1864,7 +1862,6 @@ static void cliServoMix(char *cmdline)
printServoMix(DUMP_MASTER, customServoMixers(0), NULL);
} else if (sl_strncasecmp(cmdline, "reset", 5) == 0) {
// erase custom mixer
// pgResetCopy(customServoMixersMutable(0), PG_SERVO_MIXER);
Reset_servoMixers(customServoMixersMutable(0));
} else {
enum {RULE = 0, TARGET, INPUT, RATE, SPEED, CONDITION, ARGS_COUNT};
Expand Down Expand Up @@ -3626,17 +3623,6 @@ static void printConfig(const char *cmdline, bool doDiff)
}

cliPrintHashLine("resources");
// printResource(dumpMask, &defaultConfig);

// cliPrintHashLine("mixer");
// cliDumpPrintLinef(dumpMask, primaryMotorMixer_CopyArray[0].throttle == 0.0f, "\r\nmmix reset\r\n");

// printMotorMix(dumpMask, primaryMotorMixer_CopyArray, primaryMotorMixer(0));

// print custom servo mixer if exists
// cliPrintHashLine("servo mixer");
// cliDumpPrintLinef(dumpMask, customServoMixers_CopyArray[0].rate == 0, "smix reset\r\n");
// printServoMix(dumpMask, customServoMixers_CopyArray, customServoMixers(0));

// print servo parameters
cliPrintHashLine("servo");
Expand Down Expand Up @@ -3720,34 +3706,39 @@ static void printConfig(const char *cmdline, bool doDiff)
const int currentProfileIndexSave = getConfigProfile();
const int currentBatteryProfileIndexSave = getConfigBatteryProfile();
const int currentMixerProfileIndexSave = getConfigMixerProfile();
for (int ii = 0; ii < MAX_MIXER_PROFILE_COUNT; ++ii) {
cliDumpMixerProfile(ii, dumpMask);
}
for (int ii = 0; ii < MAX_PROFILE_COUNT; ++ii) {
cliDumpProfile(ii, dumpMask);
}
for (int ii = 0; ii < MAX_BATTERY_PROFILE_COUNT; ++ii) {
cliDumpBatteryProfile(ii, dumpMask);
}
for (int ii = 0; ii < MAX_MIXER_PROFILE_COUNT; ++ii) {
cliDumpMixerProfile(ii, dumpMask);
}
setConfigProfile(currentProfileIndexSave);
setConfigBatteryProfile(currentBatteryProfileIndexSave);
setConfigMixerProfile(currentMixerProfileIndexSave);

cliPrintHashLine("restore original profile selection");
cliPrintLinef("profile %d", currentProfileIndexSave + 1);
cliPrintLinef("mixer_profile %d", currentMixerProfileIndexSave + 1);
cliPrintLinef("profile %d", currentProfileIndexSave + 1);
cliPrintLinef("battery_profile %d", currentBatteryProfileIndexSave + 1);

#ifdef USE_CLI_BATCH
batchModeEnabled = false;
#endif
} else {
// dump just the current profiles
cliDumpMixerProfile(getConfigMixerProfile(), dumpMask);
cliDumpProfile(getConfigProfile(), dumpMask);
cliDumpBatteryProfile(getConfigBatteryProfile(), dumpMask);
cliDumpMixerProfile(getConfigMixerProfile(), dumpMask);
}
}

if (dumpMask & DUMP_MIXER_PROFILE) {
cliDumpMixerProfile(getConfigMixerProfile(), dumpMask);
}

if (dumpMask & DUMP_PROFILE) {
cliDumpProfile(getConfigProfile(), dumpMask);
}
Expand All @@ -3756,10 +3747,6 @@ static void printConfig(const char *cmdline, bool doDiff)
cliDumpBatteryProfile(getConfigBatteryProfile(), dumpMask);
}

if (dumpMask & DUMP_MIXER_PROFILE) {
cliDumpMixerProfile(getConfigMixerProfile(), dumpMask);
}

if ((dumpMask & DUMP_MASTER) || (dumpMask & DUMP_ALL)) {
cliPrintHashLine("save configuration\r\nsave");
}
Expand Down
1 change: 0 additions & 1 deletion src/main/fc/fc_msp.c
Original file line number Diff line number Diff line change
Expand Up @@ -3132,7 +3132,6 @@ static bool mspSettingInfoCommand(sbuf_t *dst, sbuf_t *src)
sbufWriteU8(dst, MAX_MIXER_PROFILE_COUNT);
break;
}


// If the setting uses a table, send each possible string (null terminated)
if (SETTING_MODE(setting) == MODE_LOOKUP) {
Expand Down
29 changes: 1 addition & 28 deletions src/main/flight/mixer.c
Original file line number Diff line number Diff line change
Expand Up @@ -83,34 +83,6 @@ PG_RESET_TEMPLATE(reversibleMotorsConfig_t, reversibleMotorsConfig,
.deadband_high = SETTING_3D_DEADBAND_HIGH_DEFAULT,
.neutral = SETTING_3D_NEUTRAL_DEFAULT
);
// PG_REGISTER_ARRAY_WITH_RESET_FN(mixerProfile_t, MAX_MIXER_PROFILE_COUNT, mixerProfiles, PG_MIXER_PROFILE, 1);

// void pgResetFn_mixerProfiles(mixerProfile_t *instance)
// {
// for (int i = 0; i < MAX_MIXER_PROFILE_COUNT; i++) {
// RESET_CONFIG(mixerProfile_t, &instance[i],
// .motorDirectionInverted = SETTING_MOTOR_DIRECTION_INVERTED_DEFAULT,
// .platformType = SETTING_PLATFORM_TYPE_DEFAULT,
// .hasFlaps = SETTING_HAS_FLAPS_DEFAULT,
// .appliedMixerPreset = SETTING_MODEL_PREVIEW_TYPE_DEFAULT, //This flag is not available in CLI and used by Configurator only
// .outputMode = SETTING_OUTPUT_MODE_DEFAULT,
// );
// motorMixer_t tmp_mixer = {.throttle=0,.roll=0,.pitch=0,.yaw=0};
// for (int j = 0; j < MAX_SUPPORTED_MOTORS; j++) {
// instance->MotorMixer[j] = tmp_mixer;
// }
// }
// }

// PG_REGISTER_WITH_RESET_TEMPLATE(mixerConfig_t, mixerConfig, PG_MIXER_PROFILE, 5);

// PG_RESET_TEMPLATE(mixerConfig_t, mixerConfig,
// .motorDirectionInverted = SETTING_MOTOR_DIRECTION_INVERTED_DEFAULT,
// .platformType = SETTING_PLATFORM_TYPE_DEFAULT,
// .hasFlaps = SETTING_HAS_FLAPS_DEFAULT,
// .appliedMixerPreset = SETTING_MODEL_PREVIEW_TYPE_DEFAULT, //This flag is not available in CLI and used by Configurator only
// .outputMode = SETTING_OUTPUT_MODE_DEFAULT,
// );

PG_REGISTER_WITH_RESET_TEMPLATE(motorConfig_t, motorConfig, PG_MOTOR_CONFIG, 9);

Expand Down Expand Up @@ -436,6 +408,7 @@ void FAST_CODE writeMotors(void)
// We don't define USE_DSHOT
motorValue = motor[i];
#endif

pwmWriteMotor(i, motorValue);
}
}
Expand Down
22 changes: 1 addition & 21 deletions src/main/flight/mixer.h
Original file line number Diff line number Diff line change
Expand Up @@ -25,7 +25,6 @@
#define MAX_SUPPORTED_MOTORS 12
#endif


// Digital protocol has fixed values
#define DSHOT_DISARM_COMMAND 0
#define DSHOT_MIN_THROTTLE 48
Expand Down Expand Up @@ -63,8 +62,6 @@ typedef struct motorMixer_s {
float yaw;
} motorMixer_t;

// PG_DECLARE_ARRAY(motorMixer_t, MAX_SUPPORTED_MOTORS, primaryMotorMixer);

typedef struct mixerConfig_s {
int8_t motorDirectionInverted;
uint8_t platformType;
Expand All @@ -73,22 +70,6 @@ typedef struct mixerConfig_s {
uint8_t outputMode;
} mixerConfig_t;

// typedef struct mixerProfile_s {
// int8_t motorDirectionInverted;
// uint8_t platformType;
// bool hasFlaps;
// int16_t appliedMixerPreset;
// uint8_t outputMode;
// motorMixer_t MotorMixer[MAX_SUPPORTED_MOTORS];
// } mixerProfile_t;

// PG_DECLARE_ARRAY(mixerProfile_t, MAX_MIXER_PROFILE_COUNT, mixerProfiles);
// #define mixerConfig() mixerProfiles(systemConfig()->current_mixer_profile_index)
// #define mixerConfigMutable() ((mixerProfile_t *)mixerConfig())
// #define primaryMotorMixer(_index) (&((mixerConfig()->MotorMixer)[_index]))
// #define primaryMotorMixerMutable(_index) ((motorMixer_t *)primaryMotorMixer(_index))
// extern motorMixer_t primaryMotorMixer_CopyArray[12];

typedef struct reversibleMotorsConfig_s {
uint16_t deadband_low; // min 3d value
uint16_t deadband_high; // max 3d value
Expand Down Expand Up @@ -142,8 +123,7 @@ void processServoAutotrim(const float dT);
void processServoAutotrimMode(void);
void processContinuousServoAutotrim(const float dT);
void stopMotors(void);
void stopAndDisableMotors(void);
void stopPwmAllMotors(void);

void loadPrimaryMotorMixer(void);
bool areMotorsRunning(void);
bool areMotorsRunning(void);
Loading

0 comments on commit 67390e1

Please sign in to comment.