diff --git a/src/main/config/config.c b/src/main/config/config.c index 02c9a389a7..826fd88b56 100755 --- a/src/main/config/config.c +++ b/src/main/config/config.c @@ -134,7 +134,7 @@ static uint32_t activeFeaturesLatch = 0; static uint8_t currentControlRateProfileIndex = 0; controlRateConfig_t *currentControlRateProfile; -static const uint8_t EEPROM_CONF_VERSION = 127; +static const uint8_t EEPROM_CONF_VERSION = 128; static void resetAccelerometerTrims(flightDynamicsTrims_t *accelerometerTrims) { @@ -485,7 +485,6 @@ static void resetConf(void) masterConfig.motor_pwm_rate = BRUSHLESS_MOTORS_PWM_RATE; #endif masterConfig.servo_pwm_rate = 50; - masterConfig.force_motor_pwm_rate = 0; masterConfig.use_oneshot42 = 0; #ifdef CC3D masterConfig.use_buzzer_p6 = 0; diff --git a/src/main/config/config_master.h b/src/main/config/config_master.h index e9931b6ee6..a0bd3467df 100644 --- a/src/main/config/config_master.h +++ b/src/main/config/config_master.h @@ -36,7 +36,6 @@ typedef struct master_t { uint16_t motor_pwm_rate; // The update rate of motor outputs (50-498Hz) uint16_t servo_pwm_rate; // The update rate of servo outputs (50-498Hz) - uint8_t force_motor_pwm_rate; // Use fixed motor update even when oneshot enabled uint8_t use_oneshot42; // Oneshot42 uint8_t use_multiShot; // multishot diff --git a/src/main/drivers/pwm_mapping.c b/src/main/drivers/pwm_mapping.c index 8a3be70fae..c7d4a24801 100755 --- a/src/main/drivers/pwm_mapping.c +++ b/src/main/drivers/pwm_mapping.c @@ -31,7 +31,6 @@ void pwmBrushedMotorConfig(const timerHardware_t *timerHardware, uint8_t motorIndex, uint16_t motorPwmRate, uint16_t idlePulse); void pwmBrushlessMotorConfig(const timerHardware_t *timerHardware, uint8_t motorIndex, uint16_t motorPwmRate, uint16_t idlePulse); -void pwmFixedMotorConfig(const timerHardware_t *timerHardware, uint8_t motorIndex, uint16_t motorPwmRate, uint16_t idlePulse, uint8_t useOneshot42, uint8_t useMultiShot); void pwmOneshotMotorConfig(const timerHardware_t *timerHardware, uint8_t motorIndex, uint8_t useOneshot42); void pwmMultiShotMotorConfig(const timerHardware_t *timerHardware, uint8_t motorIndex); void pwmServoConfig(const timerHardware_t *timerHardware, uint8_t servoIndex, uint16_t servoPwmRate, uint16_t servoCenterPulse); @@ -805,9 +804,7 @@ if (init->useBuzzerP6) { } #endif if (init->useOneshot) { - if (init->useFixedPWM) { - pwmFixedMotorConfig(timerHardwarePtr, pwmOutputConfiguration.motorCount, init->motorPwmRate, init->idlePulse, init->useOneshot42, init->useMultiShot); - } else if (init->useMultiShot) { + if (init->useMultiShot) { pwmMultiShotMotorConfig(timerHardwarePtr, pwmOutputConfiguration.motorCount); } else { pwmOneshotMotorConfig(timerHardwarePtr, pwmOutputConfiguration.motorCount, init->useOneshot42); diff --git a/src/main/drivers/pwm_mapping.h b/src/main/drivers/pwm_mapping.h index 86e070a359..9d8377f17c 100644 --- a/src/main/drivers/pwm_mapping.h +++ b/src/main/drivers/pwm_mapping.h @@ -60,7 +60,6 @@ typedef struct drv_pwm_config_s { #endif bool useVbat; bool useOneshot; - bool useFixedPWM; bool useOneshot42; bool useMultiShot; bool useSoftSerial; diff --git a/src/main/drivers/pwm_output.c b/src/main/drivers/pwm_output.c index 1a69377f46..25d51892ee 100644 --- a/src/main/drivers/pwm_output.c +++ b/src/main/drivers/pwm_output.c @@ -205,26 +205,6 @@ void pwmBrushlessMotorConfig(const timerHardware_t *timerHardware, uint8_t motor motors[motorIndex]->pwmWritePtr = pwmWriteStandard; } -void pwmFixedMotorConfig(const timerHardware_t *timerHardware, uint8_t motorIndex, uint16_t motorPwmRate, uint16_t idlePulse, uint8_t useOneshot42, uint8_t useMultiShot) -{ - uint32_t hz; - if (useMultiShot) { - hz = MULTISHOT_TIMER_MHZ * 1000000; - motors[motorIndex] = pwmOutConfig(timerHardware, MULTISHOT_TIMER_MHZ, hz / motorPwmRate, idlePulse); - } else { - hz = ONESHOT_TIMER_MHZ * 1000000; - motors[motorIndex] = pwmOutConfig(timerHardware, ONESHOT_TIMER_MHZ, hz / motorPwmRate, idlePulse); - } - - if (useOneshot42) { - motors[motorIndex]->pwmWritePtr = pwmWriteOneshot42; - } else if (useMultiShot) { - motors[motorIndex]->pwmWritePtr = pwmWriteMultiShot; - } else { - motors[motorIndex]->pwmWritePtr = pwmWriteOneshot125; - } -} - void pwmOneshotMotorConfig(const timerHardware_t *timerHardware, uint8_t motorIndex, uint8_t useOneshot42) { motors[motorIndex] = pwmOutConfig(timerHardware, ONESHOT_TIMER_MHZ, 0xFFFF, 0); diff --git a/src/main/flight/mixer.c b/src/main/flight/mixer.c index 4b8873b232..ba2dd5c666 100755 --- a/src/main/flight/mixer.c +++ b/src/main/flight/mixer.c @@ -633,7 +633,7 @@ void writeServos(void) } #endif -void writeMotors(uint8_t useMotorPwmRate) +void writeMotors(void) { uint8_t i; @@ -641,7 +641,7 @@ void writeMotors(uint8_t useMotorPwmRate) pwmWriteMotor(i, motor[i]); - if (feature(FEATURE_ONESHOT125) && useMotorPwmRate) { + if (feature(FEATURE_ONESHOT125)) { pwmCompleteOneshotMotorUpdate(motorCount); } } @@ -653,7 +653,7 @@ void writeAllMotors(int16_t mc) // Sends commands to all motors for (i = 0; i < motorCount; i++) motor[i] = mc; - writeMotors(0); + writeMotors(); } void stopMotors(void) diff --git a/src/main/flight/mixer.h b/src/main/flight/mixer.h index 12aec2ed05..eb324c6768 100644 --- a/src/main/flight/mixer.h +++ b/src/main/flight/mixer.h @@ -218,6 +218,6 @@ int servoDirection(int servoIndex, int fromChannel); #endif void mixerResetDisarmedMotors(void); void mixTable(void); -void writeMotors(uint8_t useMotorPwmRate); +void writeMotors(void); void stopMotors(void); void StopPwmAllMotors(void); diff --git a/src/main/io/serial_cli.c b/src/main/io/serial_cli.c index 2e14ee9bae..685c092726 100644 --- a/src/main/io/serial_cli.c +++ b/src/main/io/serial_cli.c @@ -550,7 +550,6 @@ const clivalue_t valueTable[] = { { "3d_neutral", VAR_UINT16 | MASTER_VALUE, &masterConfig.flight3DConfig.neutral3d, .config.minmax = { PWM_RANGE_ZERO, PWM_RANGE_MAX } }, { "3d_deadband_throttle", VAR_UINT16 | MASTER_VALUE, &masterConfig.flight3DConfig.deadband3d_throttle, .config.minmax = { PWM_RANGE_ZERO, PWM_RANGE_MAX } }, - { "force_motor_pwm_rate", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, &masterConfig.force_motor_pwm_rate, .config.lookup = { TABLE_OFF_ON } }, { "use_oneshot42", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, &masterConfig.use_oneshot42, .config.lookup = { TABLE_OFF_ON } }, { "use_multishot", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, &masterConfig.use_multiShot, .config.lookup = { TABLE_OFF_ON } }, #ifdef CC3D diff --git a/src/main/io/serial_msp.c b/src/main/io/serial_msp.c index 18eed33b30..b353f79a4f 100644 --- a/src/main/io/serial_msp.c +++ b/src/main/io/serial_msp.c @@ -164,13 +164,8 @@ void setGyroSamplingSpeed(uint16_t looptime) { #endif masterConfig.gyro_sync_denom = constrain(looptime / gyroSampleRate, 1, maxDivider); - if (looptime < 1000) { - masterConfig.force_motor_pwm_rate = 1; - masterConfig.motor_pwm_rate = lrintf(1.0f / (gyroSampleRate * masterConfig.gyro_sync_denom * masterConfig.pid_process_denom * 0.000001f)) + 100; - if (!(masterConfig.use_multiShot || masterConfig.use_oneshot42)) masterConfig.motor_pwm_rate = constrain(masterConfig.motor_pwm_rate, 1000, 3800); - } else { - masterConfig.force_motor_pwm_rate = 0; - } + masterConfig.motor_pwm_rate = lrintf(1.0f / (gyroSampleRate * masterConfig.gyro_sync_denom * masterConfig.pid_process_denom * 0.000001f)); + if (!(masterConfig.use_multiShot || masterConfig.use_oneshot42)) masterConfig.motor_pwm_rate = constrain(masterConfig.motor_pwm_rate, 1000, 3800); } } diff --git a/src/main/main.c b/src/main/main.c index 6024e64674..a1cac7835f 100644 --- a/src/main/main.c +++ b/src/main/main.c @@ -19,6 +19,7 @@ #include #include #include +#include #include "platform.h" #include "scheduler.h" @@ -310,7 +311,6 @@ void init(void) #endif pwm_params.useOneshot = feature(FEATURE_ONESHOT125); - pwm_params.useFixedPWM = masterConfig.force_motor_pwm_rate ? true : false; if (masterConfig.use_oneshot42) { pwm_params.useOneshot42 = masterConfig.use_oneshot42 ? true : false; masterConfig.use_multiShot = false; @@ -321,7 +321,7 @@ void init(void) pwm_params.idlePulse = masterConfig.escAndServoConfig.mincommand; if (feature(FEATURE_3D)) pwm_params.idlePulse = masterConfig.flight3DConfig.neutral3d; - if (pwm_params.motorPwmRate > 500 && !masterConfig.force_motor_pwm_rate) + if (pwm_params.motorPwmRate > 500) pwm_params.idlePulse = 0; // brushed motors #ifdef CC3D pwm_params.useBuzzerP6 = masterConfig.use_buzzer_p6 ? true : false; @@ -666,6 +666,8 @@ int main(void) { rescheduleTask(TASK_GYROPID, targetLooptime - INTERRUPT_WAIT_TIME); setTaskEnabled(TASK_GYROPID, true); + setTaskEnabled(TASK_MOTOR, true); + rescheduleTask(TASK_MOTOR, lrintf((1.0f / masterConfig.motor_pwm_rate) * 1000000)); if(sensors(SENSOR_ACC)) { setTaskEnabled(TASK_ACCEL, true); switch(targetLooptime) { // Switch statement kept in place to change acc rates in the future diff --git a/src/main/mw.c b/src/main/mw.c index dd5e8b7226..39adeb8d88 100644 --- a/src/main/mw.c +++ b/src/main/mw.c @@ -723,6 +723,20 @@ void subTasksMainPidLoop(void) { #endif } +void taskMotorUpdate(void) { + if (motorControlEnable) { + if (debugMode == DEBUG_CYCLETIME) { + static uint32_t previousMotorUpdateTime; + uint32_t currentDeltaTime = getTaskDeltaTime(TASK_SELF); + debug[2] = currentDeltaTime; + debug[3] = currentDeltaTime - previousMotorUpdateTime; + previousMotorUpdateTime = currentDeltaTime; + } + + writeMotors(); + } +} + // Function for loop trigger void taskMainPidLoopCheck(void) { static uint32_t previousTime; @@ -737,18 +751,6 @@ void taskMainPidLoopCheck(void) { debug[1] = averageSystemLoadPercent; } - if (motorControlEnable && realTimeCycle) { - if (debugMode == DEBUG_CYCLETIME) { - static uint32_t previousMotorUpdateTime, motorCycleTime; - motorCycleTime = micros() - previousMotorUpdateTime; - previousMotorUpdateTime = micros(); - debug[2] = motorCycleTime; - debug[3] = motorCycleTime - targetPidLooptime; - } - - writeMotors(masterConfig.force_motor_pwm_rate); - } - while (true) { if (gyroSyncCheckUpdate() || ((currentDeltaTime + (micros() - previousTime)) >= (targetLooptime + GYRO_WATCHDOG_DELAY))) { static uint8_t pidUpdateCountdown; @@ -765,7 +767,7 @@ void taskMainPidLoopCheck(void) { } else { pidUpdateCountdown = masterConfig.pid_process_denom - 1; taskMainPidLoop(); - realTimeCycle = true; + //realTimeCycle = true; } break; diff --git a/src/main/scheduler.c b/src/main/scheduler.c index 14703243cf..9d26edfbf4 100755 --- a/src/main/scheduler.c +++ b/src/main/scheduler.c @@ -66,6 +66,7 @@ typedef struct { } cfTask_t; void taskMainPidLoopCheck(void); +void taskMotorUpdate(void); void taskUpdateAccelerometer(void); void taskHandleSerial(void); void taskUpdateBeeper(void); @@ -103,6 +104,13 @@ static cfTask_t cfTasks[TASK_COUNT] = { .staticPriority = TASK_PRIORITY_REALTIME, }, + [TASK_MOTOR] = { + .taskName = "MOTOR", + .taskFunc = taskMotorUpdate, + .desiredPeriod = 1000, + .staticPriority = TASK_PRIORITY_HIGH, + }, + [TASK_ACCEL] = { .taskName = "ACCEL", .taskFunc = taskUpdateAccelerometer, diff --git a/src/main/scheduler.h b/src/main/scheduler.h index 9b8ce3801c..bd462d3f64 100755 --- a/src/main/scheduler.h +++ b/src/main/scheduler.h @@ -43,6 +43,7 @@ typedef enum { /* Actual tasks */ TASK_SYSTEM = 0, TASK_GYROPID, + TASK_MOTOR, TASK_ACCEL, TASK_SERIAL, TASK_BEEPER,