1
0
Fork 0
mirror of https://github.com/betaflight/betaflight.git synced 2025-07-15 12:25:20 +03:00

Fix compilation when USE_DSHOT and USE_PWM_OUTPUT are not defined.

Fix compilation when USE_DMA and USE_DMA_SPEC are not defined.

Cleanup calling code of `isMotorProtocolDshot`.

Fix 'unused' warning when USE_PWM_OUTPUT is not defined.

Undo isMotoroProtocolDshot change.

Disable USE_SERIAL_4WAY_BLHELI_INTERFACE when USE_PWM_OUTPUT is not
enabled.

Style cleanup.
This commit is contained in:
Dominic Clifton 2019-06-11 18:35:59 +02:00 committed by Michael Keller
parent 1631831147
commit 1f2ef98042
7 changed files with 46 additions and 22 deletions

View file

@ -4868,6 +4868,7 @@ static bool strToPin(char *pch, ioTag_t *tag)
return false; return false;
} }
#ifdef USE_DMA
static void printDma(void) static void printDma(void)
{ {
cliPrintLinefeed(); cliPrintLinefeed();
@ -4891,6 +4892,7 @@ static void printDma(void)
} }
} }
} }
#endif
#ifdef USE_DMA_SPEC #ifdef USE_DMA_SPEC
@ -5274,6 +5276,7 @@ static void cliDmaopt(char *cmdline)
} }
#endif // USE_DMA_SPEC #endif // USE_DMA_SPEC
#ifdef USE_DMA
static void cliDma(char* cmdline) static void cliDma(char* cmdline)
{ {
int len = strlen(cmdline); int len = strlen(cmdline);
@ -5289,6 +5292,8 @@ static void cliDma(char* cmdline)
cliShowParseError(); cliShowParseError();
#endif #endif
} }
#endif
static void cliResource(char *cmdline) static void cliResource(char *cmdline)
{ {
@ -5318,10 +5323,12 @@ static void cliResource(char *cmdline)
cliPrintLinefeed(); cliPrintLinefeed();
} }
#if defined(USE_DMA)
pch = strtok_r(NULL, " ", &saveptr); pch = strtok_r(NULL, " ", &saveptr);
if (strcasecmp(pch, "all") == 0) { if (strcasecmp(pch, "all") == 0) {
cliDma("show"); cliDma("show");
} }
#endif
return; return;
} }
@ -5972,11 +5979,15 @@ const clicmd_t cmdTable[] = {
CLI_COMMAND_DEF("defaults", "reset to defaults and reboot", "[nosave]", cliDefaults), CLI_COMMAND_DEF("defaults", "reset to defaults and reboot", "[nosave]", cliDefaults),
CLI_COMMAND_DEF("diff", "list configuration changes from default", "[master|profile|rates|hardware|all] {defaults|bare}", cliDiff), CLI_COMMAND_DEF("diff", "list configuration changes from default", "[master|profile|rates|hardware|all] {defaults|bare}", cliDiff),
#ifdef USE_RESOURCE_MGMT #ifdef USE_RESOURCE_MGMT
#ifdef USE_DMA
#ifdef USE_DMA_SPEC #ifdef USE_DMA_SPEC
CLI_COMMAND_DEF("dma", "show/set DMA assignments", "<> | <device> <index> list | <device> <index> [<option>|none] | list | show", cliDma), CLI_COMMAND_DEF("dma", "show/set DMA assignments", "<> | <device> <index> list | <device> <index> [<option>|none] | list | show", cliDma),
#else #else
CLI_COMMAND_DEF("dma", "show DMA assignments", "show", cliDma), CLI_COMMAND_DEF("dma", "show DMA assignments", "show", cliDma),
#endif #endif
#endif
#endif #endif
#ifdef USE_DSHOT_TELEMETRY #ifdef USE_DSHOT_TELEMETRY
CLI_COMMAND_DEF("dshot_telemetry_info", "disply dshot telemetry info and stats", NULL, cliDshotTelemetryInfo), CLI_COMMAND_DEF("dshot_telemetry_info", "disply dshot telemetry info and stats", NULL, cliDshotTelemetryInfo),

View file

@ -26,7 +26,6 @@
#include "platform.h" #include "platform.h"
#ifdef USE_PWM_OUTPUT #ifdef USE_PWM_OUTPUT
#include "drivers/time.h" #include "drivers/time.h"
#include "drivers/io.h" #include "drivers/io.h"
@ -781,4 +780,5 @@ void beeperPwmInit(const ioTag_t tag, uint16_t frequency)
} }
} }
#endif // USE_BEEPER #endif // USE_BEEPER
#endif #endif //USE_PWM_OUTPUT

View file

@ -407,6 +407,7 @@ void pwmRxInit(const pwmConfig_t *pwmConfig)
#define FIRST_PWM_PORT 0 #define FIRST_PWM_PORT 0
#ifdef USE_PWM_OUTPUT
void ppmAvoidPWMTimerClash(TIM_TypeDef *pwmTimer) void ppmAvoidPWMTimerClash(TIM_TypeDef *pwmTimer)
{ {
pwmOutputPort_t *motors = pwmGetMotors(); pwmOutputPort_t *motors = pwmGetMotors();
@ -419,6 +420,7 @@ void ppmAvoidPWMTimerClash(TIM_TypeDef *pwmTimer)
return; return;
} }
} }
#endif
void ppmRxInit(const ppmConfig_t *ppmConfig) void ppmRxInit(const ppmConfig_t *ppmConfig)
{ {
@ -432,7 +434,9 @@ void ppmRxInit(const ppmConfig_t *ppmConfig)
return; return;
} }
#ifdef USE_PWM_OUTPUT
ppmAvoidPWMTimerClash(timer->tim); ppmAvoidPWMTimerClash(timer->tim);
#endif
port->mode = INPUT_MODE_PPM; port->mode = INPUT_MODE_PPM;
port->timerHardware = timer; port->timerHardware = timer;

View file

@ -557,17 +557,22 @@ static void calculateThrottleAndCurrentMotorEndpoints(timeUs_t currentTimeUs)
// INVERTED // INVERTED
motorRangeMin = motorOutputLow; motorRangeMin = motorOutputLow;
motorRangeMax = deadbandMotor3dLow; motorRangeMax = deadbandMotor3dLow;
#ifdef USE_DSHOT
if (isMotorProtocolDshot()) { if (isMotorProtocolDshot()) {
motorOutputMin = motorOutputLow; motorOutputMin = motorOutputLow;
motorOutputRange = deadbandMotor3dLow - motorOutputLow; motorOutputRange = deadbandMotor3dLow - motorOutputLow;
} else { } else
#endif
{
motorOutputMin = deadbandMotor3dLow; motorOutputMin = deadbandMotor3dLow;
motorOutputRange = motorOutputLow - deadbandMotor3dLow; motorOutputRange = motorOutputLow - deadbandMotor3dLow;
} }
if (motorOutputMixSign != -1) { if (motorOutputMixSign != -1) {
reversalTimeUs = currentTimeUs; reversalTimeUs = currentTimeUs;
} }
motorOutputMixSign = -1; motorOutputMixSign = -1;
rcThrottlePrevious = rcCommand[THROTTLE]; rcThrottlePrevious = rcCommand[THROTTLE];
throttle = rcCommand3dDeadBandLow - rcCommand[THROTTLE]; throttle = rcCommand3dDeadBandLow - rcCommand[THROTTLE];
currentThrottleInputRange = rcCommandThrottleRange3dLow; currentThrottleInputRange = rcCommandThrottleRange3dLow;
@ -590,17 +595,23 @@ static void calculateThrottleAndCurrentMotorEndpoints(timeUs_t currentTimeUs)
// INVERTED_TO_DEADBAND // INVERTED_TO_DEADBAND
motorRangeMin = motorOutputLow; motorRangeMin = motorOutputLow;
motorRangeMax = deadbandMotor3dLow; motorRangeMax = deadbandMotor3dLow;
#ifdef USE_DSHOT
if (isMotorProtocolDshot()) { if (isMotorProtocolDshot()) {
motorOutputMin = motorOutputLow; motorOutputMin = motorOutputLow;
motorOutputRange = deadbandMotor3dLow - motorOutputLow; motorOutputRange = deadbandMotor3dLow - motorOutputLow;
} else { } else
#endif
{
motorOutputMin = deadbandMotor3dLow; motorOutputMin = deadbandMotor3dLow;
motorOutputRange = motorOutputLow - deadbandMotor3dLow; motorOutputRange = motorOutputLow - deadbandMotor3dLow;
} }
if (motorOutputMixSign != -1) { if (motorOutputMixSign != -1) {
reversalTimeUs = currentTimeUs; reversalTimeUs = currentTimeUs;
} }
motorOutputMixSign = -1; motorOutputMixSign = -1;
throttle = 0; throttle = 0;
currentThrottleInputRange = rcCommandThrottleRange3dLow; currentThrottleInputRange = rcCommandThrottleRange3dLow;
} else { } else {
@ -720,9 +731,11 @@ static void applyMixToMotors(float motorMix[MAX_SUPPORTED_MOTORS], motorMixer_t
} }
#endif #endif
if (failsafeIsActive()) { if (failsafeIsActive()) {
#ifdef USE_DSHOT
if (isMotorProtocolDshot()) { if (isMotorProtocolDshot()) {
motorOutput = (motorOutput < motorRangeMin) ? disarmMotorOutput : motorOutput; // Prevent getting into special reserved range motorOutput = (motorOutput < motorRangeMin) ? disarmMotorOutput : motorOutput; // Prevent getting into special reserved range
} }
#endif
motorOutput = constrain(motorOutput, disarmMotorOutput, motorRangeMax); motorOutput = constrain(motorOutput, disarmMotorOutput, motorRangeMax);
} else { } else {
motorOutput = constrain(motorOutput, motorRangeMin, motorRangeMax); motorOutput = constrain(motorOutput, motorRangeMin, motorRangeMax);
@ -940,9 +953,8 @@ FAST_CODE_NOINLINE void mixTable(timeUs_t currentTimeUs, uint8_t vbatPidCompensa
float convertExternalToMotor(uint16_t externalValue) float convertExternalToMotor(uint16_t externalValue)
{ {
uint16_t motorValue; uint16_t motorValue;
switch ((int)isMotorProtocolDshot()) {
#ifdef USE_DSHOT #ifdef USE_DSHOT
case true: if (isMotorProtocolDshot()) {
externalValue = constrain(externalValue, PWM_RANGE_MIN, PWM_RANGE_MAX); externalValue = constrain(externalValue, PWM_RANGE_MIN, PWM_RANGE_MAX);
if (featureIsEnabled(FEATURE_3D)) { if (featureIsEnabled(FEATURE_3D)) {
@ -956,13 +968,11 @@ float convertExternalToMotor(uint16_t externalValue)
} else { } else {
motorValue = (externalValue == PWM_RANGE_MIN) ? DSHOT_CMD_MOTOR_STOP : scaleRange(externalValue, PWM_RANGE_MIN + 1, PWM_RANGE_MAX, DSHOT_MIN_THROTTLE, DSHOT_MAX_THROTTLE); motorValue = (externalValue == PWM_RANGE_MIN) ? DSHOT_CMD_MOTOR_STOP : scaleRange(externalValue, PWM_RANGE_MIN + 1, PWM_RANGE_MAX, DSHOT_MIN_THROTTLE, DSHOT_MAX_THROTTLE);
} }
}
break; else
case false:
#endif #endif
default: {
motorValue = externalValue; motorValue = externalValue;
break;
} }
return (float)motorValue; return (float)motorValue;
@ -971,9 +981,8 @@ float convertExternalToMotor(uint16_t externalValue)
uint16_t convertMotorToExternal(float motorValue) uint16_t convertMotorToExternal(float motorValue)
{ {
uint16_t externalValue; uint16_t externalValue;
switch ((int)isMotorProtocolDshot()) {
#ifdef USE_DSHOT #ifdef USE_DSHOT
case true: if (isMotorProtocolDshot()) {
if (featureIsEnabled(FEATURE_3D)) { if (featureIsEnabled(FEATURE_3D)) {
if (motorValue == DSHOT_CMD_MOTOR_STOP || motorValue < DSHOT_MIN_THROTTLE) { if (motorValue == DSHOT_CMD_MOTOR_STOP || motorValue < DSHOT_MIN_THROTTLE) {
externalValue = PWM_RANGE_MID; externalValue = PWM_RANGE_MID;
@ -985,12 +994,11 @@ uint16_t convertMotorToExternal(float motorValue)
} else { } else {
externalValue = (motorValue < DSHOT_MIN_THROTTLE) ? PWM_RANGE_MIN : scaleRange(motorValue, DSHOT_MIN_THROTTLE, DSHOT_MAX_THROTTLE, PWM_RANGE_MIN + 1, PWM_RANGE_MAX); externalValue = (motorValue < DSHOT_MIN_THROTTLE) ? PWM_RANGE_MIN : scaleRange(motorValue, DSHOT_MIN_THROTTLE, DSHOT_MAX_THROTTLE, PWM_RANGE_MIN + 1, PWM_RANGE_MAX);
} }
break; }
case false: else
#endif #endif
default: {
externalValue = motorValue; externalValue = motorValue;
break;
} }
return externalValue; return externalValue;

View file

@ -226,9 +226,11 @@ void initActiveBoxIds(void)
BME(BOX3D); BME(BOX3D);
} }
#ifdef USE_DSHOT
if (isMotorProtocolDshot()) { if (isMotorProtocolDshot()) {
BME(BOXFLIPOVERAFTERCRASH); BME(BOXFLIPOVERAFTERCRASH);
} }
#endif
if (featureIsEnabled(FEATURE_SERVO_TILT)) { if (featureIsEnabled(FEATURE_SERVO_TILT)) {
BME(BOXCAMSTAB); BME(BOXCAMSTAB);

View file

@ -424,11 +424,6 @@ bool pwmAreMotorsEnabled(void) {
return pwmMotorsEnabled; return pwmMotorsEnabled;
} }
bool isMotorProtocolDshot(void)
{
return false;
}
void pwmWriteMotor(uint8_t index, float value) { void pwmWriteMotor(uint8_t index, float value) {
motorsPwm[index] = value - idlePulse; motorsPwm[index] = value - idlePulse;
} }

View file

@ -266,6 +266,10 @@
#define USE_SERIAL_4WAY_BLHELI_INTERFACE #define USE_SERIAL_4WAY_BLHELI_INTERFACE
#endif #endif
#if !defined(USE_PWM_OUTPUT)
#undef USE_SERIAL_4WAY_BLHELI_INTERFACE // implementation requires USE_PWM_OUTPUT to find motor outputs.
#endif
#if !defined(USE_LED_STRIP) #if !defined(USE_LED_STRIP)
#undef USE_LED_STRIP_STATUS_MODE #undef USE_LED_STRIP_STATUS_MODE
#endif #endif