Merge pull request #725 from martinbudden/bf_pwm_tidy

Tidied pwm_output and pwm_mapping
This commit is contained in:
J Blackman 2016-07-16 12:47:45 +10:00 committed by GitHub
commit 22e8a61a6f
4 changed files with 87 additions and 91 deletions

View File

@ -30,11 +30,6 @@
#include "pwm_rx.h" #include "pwm_rx.h"
#include "pwm_mapping.h" #include "pwm_mapping.h"
void pwmBrushedMotorConfig(const timerHardware_t *timerHardware, uint8_t motorIndex, uint16_t motorPwmRate);
void pwmBrushlessMotorConfig(const timerHardware_t *timerHardware, uint8_t motorIndex, uint16_t motorPwmRate, uint16_t idlePulse);
void pwmFastPwmMotorConfig(const timerHardware_t *timerHardware, uint8_t motorIndex, uint8_t fastPwmProtocolType, uint16_t motorPwmRate, uint16_t idlePulse);
void pwmServoConfig(const timerHardware_t *timerHardware, uint8_t servoIndex, uint16_t servoPwmRate, uint16_t servoCenterPulse);
/* /*
Configuration maps Configuration maps
@ -313,14 +308,14 @@ pwmOutputConfiguration_t *pwmInit(drv_pwm_config_t *init)
} }
#endif #endif
if (init->useFastPwm) { if (init->useFastPwm) {
pwmFastPwmMotorConfig(timerHardwarePtr, pwmOutputConfiguration.motorCount, init->pwmProtocolType, init->motorPwmRate, init->idlePulse); pwmFastPwmMotorConfig(timerHardwarePtr, pwmOutputConfiguration.motorCount, init->motorPwmRate, init->idlePulse, init->pwmProtocolType);
pwmOutputConfiguration.portConfigurations[pwmOutputConfiguration.outputCount].flags = PWM_PF_MOTOR | PWM_PF_OUTPUT_PROTOCOL_ONESHOT|PWM_PF_OUTPUT_PROTOCOL_PWM ; pwmOutputConfiguration.portConfigurations[pwmOutputConfiguration.outputCount].flags = PWM_PF_MOTOR | PWM_PF_OUTPUT_PROTOCOL_PWM | PWM_PF_OUTPUT_PROTOCOL_ONESHOT;
} else if (init->pwmProtocolType == PWM_TYPE_BRUSHED) { } else if (init->pwmProtocolType == PWM_TYPE_BRUSHED) {
pwmBrushedMotorConfig(timerHardwarePtr, pwmOutputConfiguration.motorCount, init->motorPwmRate); pwmBrushedMotorConfig(timerHardwarePtr, pwmOutputConfiguration.motorCount, init->motorPwmRate);
pwmOutputConfiguration.portConfigurations[pwmOutputConfiguration.outputCount].flags = PWM_PF_MOTOR | PWM_PF_MOTOR_MODE_BRUSHED | PWM_PF_OUTPUT_PROTOCOL_PWM; pwmOutputConfiguration.portConfigurations[pwmOutputConfiguration.outputCount].flags = PWM_PF_MOTOR | PWM_PF_OUTPUT_PROTOCOL_PWM | PWM_PF_MOTOR_MODE_BRUSHED;
} else { } else {
pwmBrushlessMotorConfig(timerHardwarePtr, pwmOutputConfiguration.motorCount, init->motorPwmRate, init->idlePulse); pwmBrushlessMotorConfig(timerHardwarePtr, pwmOutputConfiguration.motorCount, init->motorPwmRate, init->idlePulse);
pwmOutputConfiguration.portConfigurations[pwmOutputConfiguration.outputCount].flags = PWM_PF_MOTOR | PWM_PF_OUTPUT_PROTOCOL_PWM ; pwmOutputConfiguration.portConfigurations[pwmOutputConfiguration.outputCount].flags = PWM_PF_MOTOR | PWM_PF_OUTPUT_PROTOCOL_PWM;
} }
pwmOutputConfiguration.portConfigurations[pwmOutputConfiguration.outputCount].index = pwmOutputConfiguration.motorCount; pwmOutputConfiguration.portConfigurations[pwmOutputConfiguration.outputCount].index = pwmOutputConfiguration.motorCount;
pwmOutputConfiguration.portConfigurations[pwmOutputConfiguration.outputCount].timerHardware = timerHardwarePtr; pwmOutputConfiguration.portConfigurations[pwmOutputConfiguration.outputCount].timerHardware = timerHardwarePtr;

View File

@ -30,24 +30,8 @@
#error Invalid motor/servo/port configuration #error Invalid motor/servo/port configuration
#endif #endif
#define PULSE_1MS (1000) // 1ms pulse width
#define MAX_INPUTS 8
#define PWM_TIMER_MHZ 1 #define PWM_TIMER_MHZ 1
#if defined(STM32F40_41xxx) // must be multiples of timer clock
#define ONESHOT42_TIMER_MHZ 21
#define ONESHOT125_TIMER_MHZ 12
#define PWM_BRUSHED_TIMER_MHZ 21
#define MULTISHOT_TIMER_MHZ 84
#else
#define PWM_BRUSHED_TIMER_MHZ 24
#define MULTISHOT_TIMER_MHZ 72
#define ONESHOT42_TIMER_MHZ 24
#define ONESHOT125_TIMER_MHZ 8
#endif
#define MULTISHOT_5US_PW (MULTISHOT_TIMER_MHZ * 5)
#define MULTISHOT_20US_MULT (MULTISHOT_TIMER_MHZ * 20 / 1000.0f)
typedef struct sonarIOConfig_s { typedef struct sonarIOConfig_s {
ioTag_t triggerTag; ioTag_t triggerTag;

View File

@ -17,21 +17,31 @@
#include <stdbool.h> #include <stdbool.h>
#include <stdint.h> #include <stdint.h>
#include <stdlib.h>
#include <math.h> #include <math.h>
#include "platform.h" #include "platform.h"
#include "io.h" #include "io.h"
#include "timer.h" #include "timer.h"
#include "flight/failsafe.h" // FIXME dependency into the main code from a driver
#include "pwm_mapping.h" #include "pwm_mapping.h"
#include "pwm_output.h" #include "pwm_output.h"
#if defined(STM32F40_41xxx) // must be multiples of timer clock
#define ONESHOT125_TIMER_MHZ 12
#define ONESHOT42_TIMER_MHZ 21
#define MULTISHOT_TIMER_MHZ 84
#define PWM_BRUSHED_TIMER_MHZ 21
#else
#define ONESHOT125_TIMER_MHZ 8
#define ONESHOT42_TIMER_MHZ 24
#define MULTISHOT_TIMER_MHZ 72
#define PWM_BRUSHED_TIMER_MHZ 24
#endif
#define MULTISHOT_5US_PW (MULTISHOT_TIMER_MHZ * 5)
#define MULTISHOT_20US_MULT (MULTISHOT_TIMER_MHZ * 20 / 1000.0f)
typedef void (*pwmWriteFuncPtr)(uint8_t index, uint16_t value); // function pointer used to write motors typedef void (*pwmWriteFuncPtr)(uint8_t index, uint16_t value); // function pointer used to write motors
typedef struct { typedef struct {
@ -52,6 +62,8 @@ static pwmOutputPort_t *servos[MAX_PWM_SERVOS];
static uint8_t allocatedOutputPortCount = 0; static uint8_t allocatedOutputPortCount = 0;
static bool pwmMotorsEnabled = true; static bool pwmMotorsEnabled = true;
static void pwmOCConfig(TIM_TypeDef *tim, uint8_t channel, uint16_t value, uint8_t ouputPolarity) static void pwmOCConfig(TIM_TypeDef *tim, uint8_t channel, uint16_t value, uint8_t ouputPolarity)
{ {
TIM_OCInitTypeDef TIM_OCInitStructure; TIM_OCInitTypeDef TIM_OCInitStructure;
@ -65,22 +77,22 @@ static void pwmOCConfig(TIM_TypeDef *tim, uint8_t channel, uint16_t value, uint8
TIM_OCInitStructure.TIM_OCIdleState = TIM_OCIdleState_Set; TIM_OCInitStructure.TIM_OCIdleState = TIM_OCIdleState_Set;
switch (channel) { switch (channel) {
case TIM_Channel_1: case TIM_Channel_1:
TIM_OC1Init(tim, &TIM_OCInitStructure); TIM_OC1Init(tim, &TIM_OCInitStructure);
TIM_OC1PreloadConfig(tim, TIM_OCPreload_Enable); TIM_OC1PreloadConfig(tim, TIM_OCPreload_Enable);
break; break;
case TIM_Channel_2: case TIM_Channel_2:
TIM_OC2Init(tim, &TIM_OCInitStructure); TIM_OC2Init(tim, &TIM_OCInitStructure);
TIM_OC2PreloadConfig(tim, TIM_OCPreload_Enable); TIM_OC2PreloadConfig(tim, TIM_OCPreload_Enable);
break; break;
case TIM_Channel_3: case TIM_Channel_3:
TIM_OC3Init(tim, &TIM_OCInitStructure); TIM_OC3Init(tim, &TIM_OCInitStructure);
TIM_OC3PreloadConfig(tim, TIM_OCPreload_Enable); TIM_OC3PreloadConfig(tim, TIM_OCPreload_Enable);
break; break;
case TIM_Channel_4: case TIM_Channel_4:
TIM_OC4Init(tim, &TIM_OCInitStructure); TIM_OC4Init(tim, &TIM_OCInitStructure);
TIM_OC4PreloadConfig(tim, TIM_OCPreload_Enable); TIM_OC4PreloadConfig(tim, TIM_OCPreload_Enable);
break; break;
} }
} }
@ -90,7 +102,7 @@ static pwmOutputPort_t *pwmOutConfig(const timerHardware_t *timerHardware, uint8
configTimeBase(timerHardware->tim, period, mhz); configTimeBase(timerHardware->tim, period, mhz);
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); IOConfigGPIO(io, IOCFG_AF_PP);
@ -102,18 +114,18 @@ static pwmOutputPort_t *pwmOutConfig(const timerHardware_t *timerHardware, uint8
TIM_Cmd(timerHardware->tim, ENABLE); TIM_Cmd(timerHardware->tim, ENABLE);
switch (timerHardware->channel) { switch (timerHardware->channel) {
case TIM_Channel_1: case TIM_Channel_1:
p->ccr = &timerHardware->tim->CCR1; p->ccr = &timerHardware->tim->CCR1;
break; break;
case TIM_Channel_2: case TIM_Channel_2:
p->ccr = &timerHardware->tim->CCR2; p->ccr = &timerHardware->tim->CCR2;
break; break;
case TIM_Channel_3: case TIM_Channel_3:
p->ccr = &timerHardware->tim->CCR3; p->ccr = &timerHardware->tim->CCR3;
break; break;
case TIM_Channel_4: case TIM_Channel_4:
p->ccr = &timerHardware->tim->CCR4; p->ccr = &timerHardware->tim->CCR4;
break; break;
} }
p->period = period; p->period = period;
p->tim = timerHardware->tim; p->tim = timerHardware->tim;
@ -133,16 +145,16 @@ static void pwmWriteStandard(uint8_t index, uint16_t value)
*motors[index]->ccr = value; *motors[index]->ccr = value;
} }
static void pwmWriteOneShot42(uint8_t index, uint16_t value)
{
*motors[index]->ccr = lrintf((float)(value * ONESHOT42_TIMER_MHZ/24.0f));
}
static void pwmWriteOneShot125(uint8_t index, uint16_t value) static void pwmWriteOneShot125(uint8_t index, uint16_t value)
{ {
*motors[index]->ccr = lrintf((float)(value * ONESHOT125_TIMER_MHZ/8.0f)); *motors[index]->ccr = lrintf((float)(value * ONESHOT125_TIMER_MHZ/8.0f));
} }
static void pwmWriteOneShot42(uint8_t index, uint16_t value)
{
*motors[index]->ccr = lrintf((float)(value * ONESHOT42_TIMER_MHZ/24.0f));
}
static void pwmWriteMultiShot(uint8_t index, uint16_t value) static void pwmWriteMultiShot(uint8_t index, uint16_t value)
{ {
*motors[index]->ccr = lrintf(((float)(value-1000) * MULTISHOT_20US_MULT) + MULTISHOT_5US_PW); *motors[index]->ccr = lrintf(((float)(value-1000) * MULTISHOT_20US_MULT) + MULTISHOT_5US_PW);
@ -150,15 +162,14 @@ static void pwmWriteMultiShot(uint8_t index, uint16_t value)
void pwmWriteMotor(uint8_t index, uint16_t value) void pwmWriteMotor(uint8_t index, uint16_t value)
{ {
if (motors[index] && index < MAX_MOTORS && pwmMotorsEnabled) if (motors[index] && index < MAX_MOTORS && pwmMotorsEnabled) {
motors[index]->pwmWritePtr(index, value); motors[index]->pwmWritePtr(index, value);
}
} }
void pwmShutdownPulsesForAllMotors(uint8_t motorCount) void pwmShutdownPulsesForAllMotors(uint8_t motorCount)
{ {
uint8_t index; for(int index = 0; index < motorCount; index++){
for(index = 0; index < motorCount; index++){
// Set the compare register to 0, which stops the output pulsing if the timer overflows // Set the compare register to 0, which stops the output pulsing if the timer overflows
*motors[index]->ccr = 0; *motors[index]->ccr = 0;
} }
@ -176,17 +187,14 @@ void pwmEnableMotors(void)
void pwmCompleteOneshotMotorUpdate(uint8_t motorCount) void pwmCompleteOneshotMotorUpdate(uint8_t motorCount)
{ {
uint8_t index;
TIM_TypeDef *lastTimerPtr = NULL; TIM_TypeDef *lastTimerPtr = NULL;
for (index = 0; index < motorCount; index++) { for (int index = 0; index < motorCount; index++) {
// Force the timer to overflow if it's the first motor to output, or if we change timers // Force the timer to overflow if it's the first motor to output, or if we change timers
if (motors[index]->tim != lastTimerPtr) { if (motors[index]->tim != lastTimerPtr) {
lastTimerPtr = motors[index]->tim; lastTimerPtr = motors[index]->tim;
timerForceOverflow(motors[index]->tim); timerForceOverflow(motors[index]->tim);
} }
// Set the compare register to 0, which stops the output pulsing if the timer overflows before the main loop completes again. // Set the compare register to 0, which stops the output pulsing if the timer overflows before the main loop completes again.
// This compare register will be set to the output value on the next main loop. // This compare register will be set to the output value on the next main loop.
*motors[index]->ccr = 0; *motors[index]->ccr = 0;
@ -195,44 +203,46 @@ void pwmCompleteOneshotMotorUpdate(uint8_t motorCount)
void pwmBrushedMotorConfig(const timerHardware_t *timerHardware, uint8_t motorIndex, uint16_t motorPwmRate) void pwmBrushedMotorConfig(const timerHardware_t *timerHardware, uint8_t motorIndex, uint16_t motorPwmRate)
{ {
uint32_t hz = PWM_BRUSHED_TIMER_MHZ * 1000000; const uint32_t hz = PWM_BRUSHED_TIMER_MHZ * 1000000;
motors[motorIndex] = pwmOutConfig(timerHardware, PWM_BRUSHED_TIMER_MHZ, hz / motorPwmRate, 0); motors[motorIndex] = pwmOutConfig(timerHardware, PWM_BRUSHED_TIMER_MHZ, hz / motorPwmRate, 0);
motors[motorIndex]->pwmWritePtr = pwmWriteBrushed; motors[motorIndex]->pwmWritePtr = pwmWriteBrushed;
} }
void pwmBrushlessMotorConfig(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)
{ {
uint32_t hz = PWM_TIMER_MHZ * 1000000; const uint32_t hz = PWM_TIMER_MHZ * 1000000;
motors[motorIndex] = pwmOutConfig(timerHardware, PWM_TIMER_MHZ, hz / motorPwmRate, idlePulse); motors[motorIndex] = pwmOutConfig(timerHardware, PWM_TIMER_MHZ, hz / motorPwmRate, idlePulse);
motors[motorIndex]->pwmWritePtr = pwmWriteStandard; motors[motorIndex]->pwmWritePtr = pwmWriteStandard;
} }
void pwmFastPwmMotorConfig(const timerHardware_t *timerHardware, uint8_t motorIndex, uint8_t fastPwmProtocolType, uint16_t motorPwmRate, uint16_t idlePulse) void pwmFastPwmMotorConfig(const timerHardware_t *timerHardware, uint8_t motorIndex, uint16_t motorPwmRate, uint16_t idlePulse, uint8_t fastPwmProtocolType)
{ {
uint32_t timerMhzCounter; uint32_t timerMhzCounter;
pwmWriteFuncPtr pwmWritePtr;
switch (fastPwmProtocolType) { switch (fastPwmProtocolType) {
default: default:
case (PWM_TYPE_ONESHOT125): case (PWM_TYPE_ONESHOT125):
timerMhzCounter = ONESHOT125_TIMER_MHZ; timerMhzCounter = ONESHOT125_TIMER_MHZ;
break; pwmWritePtr = pwmWriteOneShot125;
case (PWM_TYPE_ONESHOT42): break;
timerMhzCounter = ONESHOT42_TIMER_MHZ; case (PWM_TYPE_ONESHOT42):
break; timerMhzCounter = ONESHOT42_TIMER_MHZ;
case (PWM_TYPE_MULTISHOT): pwmWritePtr = pwmWriteOneShot42;
timerMhzCounter = MULTISHOT_TIMER_MHZ; break;
case (PWM_TYPE_MULTISHOT):
timerMhzCounter = MULTISHOT_TIMER_MHZ;
pwmWritePtr = pwmWriteMultiShot;
break;
} }
if (motorPwmRate > 0) { if (motorPwmRate > 0) {
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);
} else { } else {
motors[motorIndex] = pwmOutConfig(timerHardware, timerMhzCounter, 0xFFFF, 0); motors[motorIndex] = pwmOutConfig(timerHardware, timerMhzCounter, 0xFFFF, 0);
} }
motors[motorIndex]->pwmWritePtr = pwmWritePtr;
motors[motorIndex]->pwmWritePtr = (fastPwmProtocolType == PWM_TYPE_MULTISHOT) ? pwmWriteMultiShot :
((fastPwmProtocolType == PWM_TYPE_ONESHOT125) ? pwmWriteOneShot125 :
pwmWriteOneShot42);
} }
#ifdef USE_SERVOS #ifdef USE_SERVOS
@ -243,7 +253,8 @@ void pwmServoConfig(const timerHardware_t *timerHardware, uint8_t servoIndex, ui
void pwmWriteServo(uint8_t index, uint16_t value) void pwmWriteServo(uint8_t index, uint16_t value)
{ {
if (servos[index] && index < MAX_SERVOS) if (servos[index] && index < MAX_SERVOS) {
*servos[index]->ccr = value; *servos[index]->ccr = value;
}
} }
#endif #endif

View File

@ -25,6 +25,12 @@ typedef enum {
PWM_TYPE_BRUSHED PWM_TYPE_BRUSHED
} motorPwmProtocolTypes_e; } motorPwmProtocolTypes_e;
struct timerHardware_s;
void pwmBrushedMotorConfig(const struct timerHardware_s *timerHardware, uint8_t motorIndex, uint16_t motorPwmRate);
void pwmBrushlessMotorConfig(const struct timerHardware_s *timerHardware, uint8_t motorIndex, uint16_t motorPwmRate, uint16_t idlePulse);
void pwmFastPwmMotorConfig(const struct timerHardware_s *timerHardware, uint8_t motorIndex, uint16_t motorPwmRate, uint16_t idlePulse, uint8_t fastPwmProtocolType);
void pwmServoConfig(const struct timerHardware_s *timerHardware, uint8_t servoIndex, uint16_t servoPwmRate, uint16_t servoCenterPulse);
void pwmWriteMotor(uint8_t index, uint16_t value); void pwmWriteMotor(uint8_t index, uint16_t value);
void pwmShutdownPulsesForAllMotors(uint8_t motorCount); void pwmShutdownPulsesForAllMotors(uint8_t motorCount);
void pwmCompleteOneshotMotorUpdate(uint8_t motorCount); void pwmCompleteOneshotMotorUpdate(uint8_t motorCount);