1
0
Fork 0
mirror of https://github.com/iNavFlight/inav.git synced 2025-07-23 16:25:26 +03:00

First cut on PWM output disable/enable feature

This commit is contained in:
Konstantin Sharlaimov (DigitalEntity) 2016-10-17 18:39:07 +10:00
parent cf23e879a4
commit 82b08d2b7d
6 changed files with 25 additions and 11 deletions

View file

@ -72,6 +72,7 @@ typedef enum {
FEATURE_RX_SPI = 1 << 25, FEATURE_RX_SPI = 1 << 25,
FEATURE_SOFTSPI = 1 << 26, FEATURE_SOFTSPI = 1 << 26,
FEATURE_PWM_SERVO_DRIVER = 1 << 27, FEATURE_PWM_SERVO_DRIVER = 1 << 27,
FEATURE_PWM_OUTPUT_ENABLE = 1 << 28,
} features_e; } features_e;
typedef enum { typedef enum {

View file

@ -32,8 +32,8 @@
#include "pwm_rx.h" #include "pwm_rx.h"
#include "pwm_mapping.h" #include "pwm_mapping.h"
void pwmMotorConfig(const timerHardware_t *timerHardware, uint8_t motorIndex, uint16_t motorPwmRate, uint16_t idlePulse, motorPwmProtocolTypes_e proto); void pwmMotorConfig(const timerHardware_t *timerHardware, uint8_t motorIndex, uint16_t motorPwmRate, uint16_t idlePulse, motorPwmProtocolTypes_e proto, bool enableOutput);
void pwmServoConfig(const timerHardware_t *timerHardware, uint8_t servoIndex, uint16_t servoPwmRate, uint16_t servoCenterPulse); void pwmServoConfig(const timerHardware_t *timerHardware, uint8_t servoIndex, uint16_t servoPwmRate, uint16_t servoCenterPulse, bool enableOutput);
/* /*
Configuration maps Configuration maps
@ -370,7 +370,7 @@ pwmIOConfiguration_t *pwmInit(drv_pwm_config_t *init)
} }
#endif #endif
pwmMotorConfig(timerHardwarePtr, pwmIOConfiguration.motorCount, init->motorPwmRate, init->idlePulse, init->pwmProtocolType); pwmMotorConfig(timerHardwarePtr, pwmIOConfiguration.motorCount, init->motorPwmRate, init->idlePulse, init->pwmProtocolType, init->enablePWMOutput);
if (init->useFastPwm) { if (init->useFastPwm) {
pwmIOConfiguration.ioConfigurations[pwmIOConfiguration.ioCount].flags = PWM_PF_MOTOR | PWM_PF_OUTPUT_PROTOCOL_FASTPWM | PWM_PF_OUTPUT_PROTOCOL_PWM; pwmIOConfiguration.ioConfigurations[pwmIOConfiguration.ioCount].flags = PWM_PF_MOTOR | PWM_PF_OUTPUT_PROTOCOL_FASTPWM | PWM_PF_OUTPUT_PROTOCOL_PWM;
} else if (init->pwmProtocolType == PWM_TYPE_BRUSHED) { } else if (init->pwmProtocolType == PWM_TYPE_BRUSHED) {
@ -392,7 +392,7 @@ pwmIOConfiguration_t *pwmInit(drv_pwm_config_t *init)
} }
#ifdef USE_SERVOS #ifdef USE_SERVOS
pwmServoConfig(timerHardwarePtr, pwmIOConfiguration.servoCount, init->servoPwmRate, init->servoCenterPulse); pwmServoConfig(timerHardwarePtr, pwmIOConfiguration.servoCount, init->servoPwmRate, init->servoCenterPulse, init->enablePWMOutput);
pwmIOConfiguration.ioConfigurations[pwmIOConfiguration.ioCount].flags = PWM_PF_SERVO | PWM_PF_OUTPUT_PROTOCOL_PWM; pwmIOConfiguration.ioConfigurations[pwmIOConfiguration.ioCount].flags = PWM_PF_SERVO | PWM_PF_OUTPUT_PROTOCOL_PWM;
pwmIOConfiguration.ioConfigurations[pwmIOConfiguration.ioCount].index = pwmIOConfiguration.servoCount; pwmIOConfiguration.ioConfigurations[pwmIOConfiguration.ioCount].index = pwmIOConfiguration.servoCount;

View file

@ -50,6 +50,7 @@ typedef struct sonarIOConfig_s {
} sonarIOConfig_t; } sonarIOConfig_t;
typedef struct drv_pwm_config_s { typedef struct drv_pwm_config_s {
bool enablePWMOutput;
bool useParallelPWM; bool useParallelPWM;
bool usePPM; bool usePPM;
bool useSerialRx; bool useSerialRx;

View file

@ -109,7 +109,7 @@ static void pwmOCConfig(TIM_TypeDef *tim, uint8_t channel, uint16_t value, uint8
} }
} }
static pwmOutputPort_t *pwmOutConfig(const timerHardware_t *timerHardware, uint8_t mhz, uint16_t period, uint16_t value) static pwmOutputPort_t *pwmOutConfig(const timerHardware_t *timerHardware, uint8_t mhz, uint16_t period, uint16_t value, bool enableOutput)
{ {
pwmOutputPort_t *p = &pwmOutputPorts[allocatedOutputPortCount++]; pwmOutputPort_t *p = &pwmOutputPorts[allocatedOutputPortCount++];
@ -117,7 +117,17 @@ static pwmOutputPort_t *pwmOutConfig(const timerHardware_t *timerHardware, uint8
const IO_t io = IOGetByTag(timerHardware->tag); const IO_t io = IOGetByTag(timerHardware->tag);
IOInit(io, OWNER_MOTOR, RESOURCE_OUTPUT, allocatedOutputPortCount); IOInit(io, OWNER_MOTOR, RESOURCE_OUTPUT, allocatedOutputPortCount);
IOConfigGPIO(io, IOCFG_AF_PP);
if (enableOutput) {
// If PWM outputs are enabled - configure as AF_PP - map to timer
// AF itself was configured by timerInit();
IOConfigGPIO(io, IOCFG_AF_PP);
}
else {
// If PWM outputs are disabled - configure as GPIO and drive low
IOConfigGPIO(io, IOCFG_OUT_OD);
IOLo(io);
}
pwmOCConfig(timerHardware->tim, timerHardware->channel, value, timerHardware->output & TIMER_OUTPUT_INVERTED); pwmOCConfig(timerHardware->tim, timerHardware->channel, value, timerHardware->output & TIMER_OUTPUT_INVERTED);
if (timerHardware->output & TIMER_OUTPUT_ENABLED) { if (timerHardware->output & TIMER_OUTPUT_ENABLED) {
@ -204,7 +214,7 @@ bool isMotorBrushed(uint16_t motorPwmRate)
return (motorPwmRate > 500); return (motorPwmRate > 500);
} }
void pwmMotorConfig(const timerHardware_t *timerHardware, uint8_t motorIndex, uint16_t motorPwmRate, uint16_t idlePulse, motorPwmProtocolTypes_e proto) void pwmMotorConfig(const timerHardware_t *timerHardware, uint8_t motorIndex, uint16_t motorPwmRate, uint16_t idlePulse, motorPwmProtocolTypes_e proto, bool enableOutput)
{ {
uint32_t timerMhzCounter; uint32_t timerMhzCounter;
pwmWriteFuncPtr pwmWritePtr; pwmWriteFuncPtr pwmWritePtr;
@ -243,14 +253,14 @@ void pwmMotorConfig(const timerHardware_t *timerHardware, uint8_t motorIndex, ui
} }
const uint32_t hz = timerMhzCounter * 1000000; const uint32_t hz = timerMhzCounter * 1000000;
motors[motorIndex] = pwmOutConfig(timerHardware, timerMhzCounter, hz / motorPwmRate, idlePulse); motors[motorIndex] = pwmOutConfig(timerHardware, timerMhzCounter, hz / motorPwmRate, idlePulse, enableOutput);
motors[motorIndex]->pwmWritePtr = pwmWritePtr; motors[motorIndex]->pwmWritePtr = pwmWritePtr;
} }
#ifdef USE_SERVOS #ifdef USE_SERVOS
void pwmServoConfig(const timerHardware_t *timerHardware, uint8_t servoIndex, uint16_t servoPwmRate, uint16_t servoCenterPulse) void pwmServoConfig(const timerHardware_t *timerHardware, uint8_t servoIndex, uint16_t servoPwmRate, uint16_t servoCenterPulse, bool enableOutput)
{ {
servos[servoIndex] = pwmOutConfig(timerHardware, PWM_TIMER_MHZ, 1000000 / servoPwmRate, servoCenterPulse); servos[servoIndex] = pwmOutConfig(timerHardware, PWM_TIMER_MHZ, 1000000 / servoPwmRate, servoCenterPulse, enableOutput);
} }
void pwmWriteServo(uint8_t index, uint16_t value) void pwmWriteServo(uint8_t index, uint16_t value)

View file

@ -289,6 +289,8 @@ void init(void)
pwm_params.idlePulse = 0; // brushed motors pwm_params.idlePulse = 0; // brushed motors
} }
pwm_params.enablePWMOutput = feature(FEATURE_PWM_OUTPUT_ENABLE);
#ifndef SKIP_RX_PWM_PPM #ifndef SKIP_RX_PWM_PPM
pwmRxInit(masterConfig.inputFilteringMode); pwmRxInit(masterConfig.inputFilteringMode);
#endif #endif

View file

@ -219,7 +219,7 @@ static const char * const featureNames[] = {
"SONAR", "TELEMETRY", "CURRENT_METER", "3D", "RX_PARALLEL_PWM", "SONAR", "TELEMETRY", "CURRENT_METER", "3D", "RX_PARALLEL_PWM",
"RX_MSP", "RSSI_ADC", "LED_STRIP", "DISPLAY", "UNUSED_2", "RX_MSP", "RSSI_ADC", "LED_STRIP", "DISPLAY", "UNUSED_2",
"BLACKBOX", "CHANNEL_FORWARDING", "TRANSPONDER", "AIRMODE", "BLACKBOX", "CHANNEL_FORWARDING", "TRANSPONDER", "AIRMODE",
"SUPEREXPO", "VTX", "RX_SPI", "SOFTSPI", "PWM_SERVO_DRIVER", NULL "SUPEREXPO", "VTX", "RX_SPI", "SOFTSPI", "PWM_SERVO_DRIVER", "PWM_OUTPUT_ENABLE", NULL
}; };
// sync this with rxFailsafeChannelMode_e // sync this with rxFailsafeChannelMode_e