1
0
Fork 0
mirror of https://github.com/iNavFlight/inav.git synced 2025-07-26 09:45:33 +03:00

Refactor PWM rate and make it configurable only for brushed protocols

This commit is contained in:
Pawel Spychalski (DzikuVx) 2022-06-07 13:04:01 +02:00
parent 3914c4f02e
commit 283ebd22c7
7 changed files with 43 additions and 44 deletions

View file

@ -45,6 +45,7 @@
#include "drivers/compass/compass.h" #include "drivers/compass/compass.h"
#include "drivers/sensor.h" #include "drivers/sensor.h"
#include "drivers/time.h" #include "drivers/time.h"
#include "drivers/pwm_output.h"
#include "fc/config.h" #include "fc/config.h"
#include "fc/controlrate_profile.h" #include "fc/controlrate_profile.h"
@ -1811,7 +1812,7 @@ static bool blackboxWriteSysinfo(void)
#endif #endif
BLACKBOX_PRINT_HEADER_LINE("serialrx_provider", "%d", rxConfig()->serialrx_provider); BLACKBOX_PRINT_HEADER_LINE("serialrx_provider", "%d", rxConfig()->serialrx_provider);
BLACKBOX_PRINT_HEADER_LINE("motor_pwm_protocol", "%d", motorConfig()->motorPwmProtocol); BLACKBOX_PRINT_HEADER_LINE("motor_pwm_protocol", "%d", motorConfig()->motorPwmProtocol);
BLACKBOX_PRINT_HEADER_LINE("motor_pwm_rate", "%d", motorConfig()->motorPwmRate); BLACKBOX_PRINT_HEADER_LINE("motor_pwm_rate", "%d", getEscUpdateFrequency());
BLACKBOX_PRINT_HEADER_LINE("debug_mode", "%d", systemConfig()->debug_mode); BLACKBOX_PRINT_HEADER_LINE("debug_mode", "%d", systemConfig()->debug_mode);
BLACKBOX_PRINT_HEADER_LINE("features", "%d", featureConfig()->enabledFeatures); BLACKBOX_PRINT_HEADER_LINE("features", "%d", featureConfig()->enabledFeatures);
BLACKBOX_PRINT_HEADER_LINE("waypoints", "%d,%d", getWaypointCount(),isWaypointListValid()); BLACKBOX_PRINT_HEADER_LINE("waypoints", "%d,%d", getWaypointCount(),isWaypointListValid());

View file

@ -464,26 +464,56 @@ void pwmMotorPreconfigure(void)
case PWM_TYPE_DSHOT600: case PWM_TYPE_DSHOT600:
case PWM_TYPE_DSHOT300: case PWM_TYPE_DSHOT300:
case PWM_TYPE_DSHOT150: case PWM_TYPE_DSHOT150:
motorConfigDigitalUpdateInterval(motorConfig()->motorPwmRate); motorConfigDigitalUpdateInterval(getEscUpdateFrequency());
motorWritePtr = pwmWriteDigital; motorWritePtr = pwmWriteDigital;
break; break;
#endif #endif
} }
} }
/**
* This function return the PWM frequency based on ESC protocol. We allow customer rates only for Brushed motors
*/
uint32_t getEscUpdateFrequency(void) {
switch (initMotorProtocol) {
case PWM_TYPE_BRUSHED:
return motorConfig()->motorPwmRate;
case PWM_TYPE_STANDARD:
return 400;
case PWM_TYPE_MULTISHOT:
return 2000;
case PWM_TYPE_DSHOT150:
return 4000;
case PWM_TYPE_DSHOT300:
return 8000;
case PWM_TYPE_DSHOT600:
return 16000;
case PWM_TYPE_ONESHOT125:
default:
return 1000;
}
}
bool pwmMotorConfig(const timerHardware_t *timerHardware, uint8_t motorIndex, bool enableOutput) bool pwmMotorConfig(const timerHardware_t *timerHardware, uint8_t motorIndex, bool enableOutput)
{ {
switch (initMotorProtocol) { switch (initMotorProtocol) {
case PWM_TYPE_BRUSHED: case PWM_TYPE_BRUSHED:
motors[motorIndex].pwmPort = motorConfigPwm(timerHardware, 0.0f, 0.0f, motorConfig()->motorPwmRate, enableOutput); motors[motorIndex].pwmPort = motorConfigPwm(timerHardware, 0.0f, 0.0f, getEscUpdateFrequency(), enableOutput);
break; break;
case PWM_TYPE_ONESHOT125: case PWM_TYPE_ONESHOT125:
motors[motorIndex].pwmPort = motorConfigPwm(timerHardware, 125e-6f, 125e-6f, motorConfig()->motorPwmRate, enableOutput); motors[motorIndex].pwmPort = motorConfigPwm(timerHardware, 125e-6f, 125e-6f, getEscUpdateFrequency(), enableOutput);
break; break;
case PWM_TYPE_MULTISHOT: case PWM_TYPE_MULTISHOT:
motors[motorIndex].pwmPort = motorConfigPwm(timerHardware, 5e-6f, 20e-6f, motorConfig()->motorPwmRate, enableOutput); motors[motorIndex].pwmPort = motorConfigPwm(timerHardware, 5e-6f, 20e-6f, getEscUpdateFrequency(), enableOutput);
break; break;
#ifdef USE_DSHOT #ifdef USE_DSHOT
@ -495,7 +525,7 @@ bool pwmMotorConfig(const timerHardware_t *timerHardware, uint8_t motorIndex, bo
#endif #endif
case PWM_TYPE_STANDARD: case PWM_TYPE_STANDARD:
motors[motorIndex].pwmPort = motorConfigPwm(timerHardware, 1e-3f, 1e-3f, motorConfig()->motorPwmRate, enableOutput); motors[motorIndex].pwmPort = motorConfigPwm(timerHardware, 1e-3f, 1e-3f, getEscUpdateFrequency(), enableOutput);
break; break;
default: default:

View file

@ -55,4 +55,6 @@ void pwmWriteBeeper(bool onoffBeep);
void beeperPwmInit(ioTag_t tag, uint16_t frequency); void beeperPwmInit(ioTag_t tag, uint16_t frequency);
void sendDShotCommand(dshotCommands_e cmd); void sendDShotCommand(dshotCommands_e cmd);
void initDShotCommands(void); void initDShotCommands(void);
uint32_t getEscUpdateFrequency(void);

View file

@ -237,40 +237,8 @@ void validateAndFixConfig(void)
} }
#endif #endif
#ifdef BRUSHED_MOTORS
motorConfigMutable()->motorPwmRate = constrain(motorConfig()->motorPwmRate, 500, 32000); motorConfigMutable()->motorPwmRate = constrain(motorConfig()->motorPwmRate, 500, 32000);
#else
switch (motorConfig()->motorPwmProtocol) {
default:
case PWM_TYPE_STANDARD: // Limited to 490 Hz
motorConfigMutable()->motorPwmRate = MIN(motorConfig()->motorPwmRate, 490);
break;
case PWM_TYPE_ONESHOT125: // Limited to 3900 Hz
motorConfigMutable()->motorPwmRate = MIN(motorConfig()->motorPwmRate, 3900);
break;
case PWM_TYPE_MULTISHOT: // 2-16 kHz
motorConfigMutable()->motorPwmRate = constrain(motorConfig()->motorPwmRate, 2000, 16000);
break;
case PWM_TYPE_BRUSHED: // 500Hz - 32kHz
motorConfigMutable()->motorPwmRate = constrain(motorConfig()->motorPwmRate, 500, 32000);
break;
#ifdef USE_DSHOT
// One DSHOT packet takes 16 bits x 19 ticks + 2uS = 304 timer ticks + 2uS
case PWM_TYPE_DSHOT150:
motorConfigMutable()->motorPwmRate = MIN(motorConfig()->motorPwmRate, 4000);
break;
case PWM_TYPE_DSHOT300:
motorConfigMutable()->motorPwmRate = MIN(motorConfig()->motorPwmRate, 8000);
break;
// Although DSHOT 600+ support >16kHz update rate it's not practical because of increased CPU load
// It's more reasonable to use slower-speed DSHOT at higher rate for better reliability
case PWM_TYPE_DSHOT600:
motorConfigMutable()->motorPwmRate = MIN(motorConfig()->motorPwmRate, 16000);
break;
#endif
}
#endif
// Call target-specific validation function // Call target-specific validation function
validateAndFixTargetConfig(); validateAndFixTargetConfig();

View file

@ -846,8 +846,8 @@ groups:
min: 0 min: 0
max: PWM_RANGE_MAX max: PWM_RANGE_MAX
- name: motor_pwm_rate - name: motor_pwm_rate
description: "Output frequency (in Hz) for motor pins. Default is 400Hz for motor with motor_pwm_protocol set to STANDARD. For *SHOT (e.g. ONESHOT125) values of 1000 and 2000 have been tested by the development team and are supported. It may be possible to use higher values. For BRUSHED values of 8000 and above should be used. Setting to 8000 will use brushed mode at 8kHz switching frequency. Up to 32kHz is supported for brushed. Default is 16000 for boards with brushed motors. Note, that in brushed mode, minthrottle is offset to zero. For brushed mode, set max_throttle to 2000." description: "Output frequency (in Hz) for motor pins. Applies only to brushed motors. "
default_value: 400 default_value: 16000
field: motorPwmRate field: motorPwmRate
min: 50 min: 50
max: 32000 max: 32000

View file

@ -36,6 +36,5 @@ void targetConfiguration(void)
{ {
serialConfigMutable()->portConfigs[findSerialPortIndexByIdentifier(TELEMETRY_UART)].functionMask = FUNCTION_TELEMETRY_SMARTPORT; serialConfigMutable()->portConfigs[findSerialPortIndexByIdentifier(TELEMETRY_UART)].functionMask = FUNCTION_TELEMETRY_SMARTPORT;
motorConfigMutable()->motorPwmProtocol = PWM_TYPE_MULTISHOT; motorConfigMutable()->motorPwmProtocol = PWM_TYPE_MULTISHOT;
motorConfigMutable()->motorPwmRate = 4000;
motorConfigMutable()->maxthrottle = 1950; motorConfigMutable()->maxthrottle = 1950;
} }

View file

@ -73,7 +73,6 @@ void validateAndFixTargetConfig(void)
if (mixerConfig()->platformType != PLATFORM_MULTIROTOR && mixerConfig()->platformType != PLATFORM_TRICOPTER) { if (mixerConfig()->platformType != PLATFORM_MULTIROTOR && mixerConfig()->platformType != PLATFORM_TRICOPTER) {
if (motorConfig()->motorPwmProtocol >= PWM_TYPE_DSHOT150) { if (motorConfig()->motorPwmProtocol >= PWM_TYPE_DSHOT150) {
motorConfigMutable()->motorPwmProtocol = PWM_TYPE_STANDARD; motorConfigMutable()->motorPwmProtocol = PWM_TYPE_STANDARD;
motorConfigMutable()->motorPwmRate = MIN(motorConfig()->motorPwmRate, 490);
} }
} }
} }