PWM output calculations dynamic based on clock speed
This commit is contained in:
parent
14f82e2a63
commit
b9ebf8f4fd
|
@ -28,9 +28,6 @@
|
||||||
#include "timer.h"
|
#include "timer.h"
|
||||||
#include "drivers/pwm_output.h"
|
#include "drivers/pwm_output.h"
|
||||||
|
|
||||||
#define MULTISHOT_5US_PW (MULTISHOT_TIMER_MHZ * 5)
|
|
||||||
#define MULTISHOT_20US_MULT (MULTISHOT_TIMER_MHZ * 20 / 1000.0f)
|
|
||||||
|
|
||||||
static pwmWriteFunc *pwmWrite;
|
static pwmWriteFunc *pwmWrite;
|
||||||
static pwmOutputPort_t motors[MAX_SUPPORTED_MOTORS];
|
static pwmOutputPort_t motors[MAX_SUPPORTED_MOTORS];
|
||||||
static pwmCompleteWriteFunc *pwmCompleteWrite = NULL;
|
static pwmCompleteWriteFunc *pwmCompleteWrite = NULL;
|
||||||
|
@ -99,16 +96,19 @@ static void pwmOCConfig(TIM_TypeDef *tim, uint8_t channel, uint16_t value, uint8
|
||||||
#endif
|
#endif
|
||||||
}
|
}
|
||||||
|
|
||||||
static void pwmOutConfig(pwmOutputPort_t *port, const timerHardware_t *timerHardware, uint8_t mhz, uint16_t period, uint16_t value, uint8_t inversion)
|
static void pwmOutConfig(pwmOutputPort_t *port, const timerHardware_t *timerHardware, uint32_t hz, uint16_t period, uint16_t value, uint8_t inversion)
|
||||||
{
|
{
|
||||||
#if defined(USE_HAL_DRIVER)
|
#if defined(USE_HAL_DRIVER)
|
||||||
TIM_HandleTypeDef* Handle = timerFindTimerHandle(timerHardware->tim);
|
TIM_HandleTypeDef* Handle = timerFindTimerHandle(timerHardware->tim);
|
||||||
if(Handle == NULL) return;
|
if(Handle == NULL) return;
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
configTimeBase(timerHardware->tim, period, mhz);
|
configTimeBase(timerHardware->tim, period, hz);
|
||||||
pwmOCConfig(timerHardware->tim, timerHardware->channel, value,
|
pwmOCConfig(timerHardware->tim,
|
||||||
inversion ? timerHardware->output ^ TIMER_OUTPUT_INVERTED : timerHardware->output);
|
timerHardware->channel,
|
||||||
|
value,
|
||||||
|
inversion ? timerHardware->output ^ TIMER_OUTPUT_INVERTED : timerHardware->output
|
||||||
|
);
|
||||||
|
|
||||||
#if defined(USE_HAL_DRIVER)
|
#if defined(USE_HAL_DRIVER)
|
||||||
if(timerHardware->output & TIMER_OUTPUT_N_CHANNEL)
|
if(timerHardware->output & TIMER_OUTPUT_N_CHANNEL)
|
||||||
|
@ -122,7 +122,7 @@ static void pwmOutConfig(pwmOutputPort_t *port, const timerHardware_t *timerHard
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
port->ccr = timerChCCR(timerHardware);
|
port->ccr = timerChCCR(timerHardware);
|
||||||
port->period = period;
|
|
||||||
port->tim = timerHardware->tim;
|
port->tim = timerHardware->tim;
|
||||||
|
|
||||||
*port->ccr = 0;
|
*port->ccr = 0;
|
||||||
|
@ -134,29 +134,10 @@ static void pwmWriteUnused(uint8_t index, float value)
|
||||||
UNUSED(value);
|
UNUSED(value);
|
||||||
}
|
}
|
||||||
|
|
||||||
static void pwmWriteBrushed(uint8_t index, float value)
|
|
||||||
{
|
|
||||||
*motors[index].ccr = lrintf((value - 1000) * motors[index].period / 1000);
|
|
||||||
}
|
|
||||||
|
|
||||||
static void pwmWriteStandard(uint8_t index, float value)
|
static void pwmWriteStandard(uint8_t index, float value)
|
||||||
{
|
{
|
||||||
*motors[index].ccr = lrintf(value);
|
/* TODO: move value to be a number between 0-1 (i.e. percent throttle from mixer) */
|
||||||
}
|
*motors[index].ccr = lrintf((value * motors[index].pulseScale) + motors[index].pulseOffset);
|
||||||
|
|
||||||
static void pwmWriteOneShot125(uint8_t index, float value)
|
|
||||||
{
|
|
||||||
*motors[index].ccr = lrintf(value * ONESHOT125_TIMER_MHZ/8.0f);
|
|
||||||
}
|
|
||||||
|
|
||||||
static void pwmWriteOneShot42(uint8_t index, float value)
|
|
||||||
{
|
|
||||||
*motors[index].ccr = lrintf(value * ONESHOT42_TIMER_MHZ/24.0f);
|
|
||||||
}
|
|
||||||
|
|
||||||
static void pwmWriteMultiShot(uint8_t index, float value)
|
|
||||||
{
|
|
||||||
*motors[index].ccr = lrintf(((value-1000) * MULTISHOT_20US_MULT) + MULTISHOT_5US_PW);
|
|
||||||
}
|
}
|
||||||
|
|
||||||
#ifdef USE_DSHOT
|
#ifdef USE_DSHOT
|
||||||
|
@ -246,32 +227,32 @@ void motorDevInit(const motorDevConfig_t *motorConfig, uint16_t idlePulse, uint8
|
||||||
{
|
{
|
||||||
memset(motors, 0, sizeof(motors));
|
memset(motors, 0, sizeof(motors));
|
||||||
|
|
||||||
uint32_t timerMhzCounter = 0;
|
|
||||||
bool useUnsyncedPwm = motorConfig->useUnsyncedPwm;
|
bool useUnsyncedPwm = motorConfig->useUnsyncedPwm;
|
||||||
|
|
||||||
|
float sMin = 0;
|
||||||
|
float sLen = 0;
|
||||||
switch (motorConfig->motorPwmProtocol) {
|
switch (motorConfig->motorPwmProtocol) {
|
||||||
default:
|
default:
|
||||||
case PWM_TYPE_ONESHOT125:
|
case PWM_TYPE_ONESHOT125:
|
||||||
timerMhzCounter = ONESHOT125_TIMER_MHZ;
|
sMin = 125e-6f;
|
||||||
pwmWrite = &pwmWriteOneShot125;
|
sLen = 125e-6f;
|
||||||
break;
|
break;
|
||||||
case PWM_TYPE_ONESHOT42:
|
case PWM_TYPE_ONESHOT42:
|
||||||
timerMhzCounter = ONESHOT42_TIMER_MHZ;
|
sMin = 42e-6f;
|
||||||
pwmWrite = &pwmWriteOneShot42;
|
sLen = 42e-6f;
|
||||||
break;
|
break;
|
||||||
case PWM_TYPE_MULTISHOT:
|
case PWM_TYPE_MULTISHOT:
|
||||||
timerMhzCounter = MULTISHOT_TIMER_MHZ;
|
sMin = 5e-6f;
|
||||||
pwmWrite = &pwmWriteMultiShot;
|
sLen = 20e-6f;
|
||||||
break;
|
break;
|
||||||
case PWM_TYPE_BRUSHED:
|
case PWM_TYPE_BRUSHED:
|
||||||
timerMhzCounter = PWM_BRUSHED_TIMER_MHZ;
|
sMin = 0;
|
||||||
pwmWrite = &pwmWriteBrushed;
|
|
||||||
useUnsyncedPwm = true;
|
useUnsyncedPwm = true;
|
||||||
idlePulse = 0;
|
idlePulse = 0;
|
||||||
break;
|
break;
|
||||||
case PWM_TYPE_STANDARD:
|
case PWM_TYPE_STANDARD:
|
||||||
timerMhzCounter = PWM_TIMER_MHZ;
|
sMin = 1e-3f;
|
||||||
pwmWrite = &pwmWriteStandard;
|
sLen = 1e-3f;
|
||||||
useUnsyncedPwm = true;
|
useUnsyncedPwm = true;
|
||||||
idlePulse = 0;
|
idlePulse = 0;
|
||||||
break;
|
break;
|
||||||
|
@ -295,6 +276,7 @@ void motorDevInit(const motorDevConfig_t *motorConfig, uint16_t idlePulse, uint8
|
||||||
}
|
}
|
||||||
|
|
||||||
if (!isDshot) {
|
if (!isDshot) {
|
||||||
|
pwmWrite = &pwmWriteStandard;
|
||||||
pwmCompleteWrite = useUnsyncedPwm ? &pwmCompleteWriteUnused : &pwmCompleteOneshotMotorUpdate;
|
pwmCompleteWrite = useUnsyncedPwm ? &pwmCompleteWriteUnused : &pwmCompleteOneshotMotorUpdate;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
@ -314,7 +296,9 @@ void motorDevInit(const motorDevConfig_t *motorConfig, uint16_t idlePulse, uint8
|
||||||
|
|
||||||
#ifdef USE_DSHOT
|
#ifdef USE_DSHOT
|
||||||
if (isDshot) {
|
if (isDshot) {
|
||||||
pwmDshotMotorHardwareConfig(timerHardware, motorIndex, motorConfig->motorPwmProtocol,
|
pwmDshotMotorHardwareConfig(timerHardware,
|
||||||
|
motorIndex,
|
||||||
|
motorConfig->motorPwmProtocol,
|
||||||
motorConfig->motorPwmInversion ? timerHardware->output ^ TIMER_OUTPUT_INVERTED : timerHardware->output);
|
motorConfig->motorPwmInversion ? timerHardware->output ^ TIMER_OUTPUT_INVERTED : timerHardware->output);
|
||||||
motors[motorIndex].enabled = true;
|
motors[motorIndex].enabled = true;
|
||||||
continue;
|
continue;
|
||||||
|
@ -328,12 +312,24 @@ void motorDevInit(const motorDevConfig_t *motorConfig, uint16_t idlePulse, uint8
|
||||||
IOConfigGPIO(motors[motorIndex].io, IOCFG_AF_PP);
|
IOConfigGPIO(motors[motorIndex].io, IOCFG_AF_PP);
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
if (useUnsyncedPwm) {
|
/* standard PWM outputs */
|
||||||
const uint32_t hz = timerMhzCounter * 1000000;
|
const unsigned pwmRateHz = useUnsyncedPwm ? motorConfig->motorPwmRate : ceilf(1 / (sMin + sLen));
|
||||||
pwmOutConfig(&motors[motorIndex], timerHardware, timerMhzCounter, hz / motorConfig->motorPwmRate, idlePulse, motorConfig->motorPwmInversion);
|
|
||||||
} else {
|
const uint32_t clock = timerClock(timerHardware->tim);
|
||||||
pwmOutConfig(&motors[motorIndex], timerHardware, timerMhzCounter, 0xFFFF, 0, motorConfig->motorPwmInversion);
|
/* used to find the desired timer frequency for max resolution */
|
||||||
}
|
const unsigned prescaler = ((clock / pwmRateHz) + 0xffff) / 0x10000; /* rounding up */
|
||||||
|
const uint32_t hz = clock / prescaler;
|
||||||
|
const unsigned period = hz / pwmRateHz;
|
||||||
|
|
||||||
|
/*
|
||||||
|
if brushed then it is the entire length of the period.
|
||||||
|
TODO: this can be moved back to periodMin and periodLen
|
||||||
|
once mixer outputs a 0..1 float value.
|
||||||
|
*/
|
||||||
|
motors[motorIndex].pulseScale = ((motorConfig->motorPwmProtocol == PWM_TYPE_BRUSHED) ? period : (sLen * hz)) / 1000.0f;
|
||||||
|
motors[motorIndex].pulseOffset = (sMin * hz) - (motors[motorIndex].pulseScale * 1000);
|
||||||
|
|
||||||
|
pwmOutConfig(&motors[motorIndex], timerHardware, hz, period, idlePulse, motorConfig->motorPwmInversion);
|
||||||
|
|
||||||
bool timerAlreadyUsed = false;
|
bool timerAlreadyUsed = false;
|
||||||
for (int i = 0; i < motorIndex; i++) {
|
for (int i = 0; i < motorIndex; i++) {
|
||||||
|
@ -364,16 +360,16 @@ uint32_t getDshotHz(motorPwmProtocolTypes_e pwmProtocolType)
|
||||||
{
|
{
|
||||||
switch (pwmProtocolType) {
|
switch (pwmProtocolType) {
|
||||||
case(PWM_TYPE_PROSHOT1000):
|
case(PWM_TYPE_PROSHOT1000):
|
||||||
return MOTOR_PROSHOT1000_MHZ * 1000000;
|
return MOTOR_PROSHOT1000_HZ;
|
||||||
case(PWM_TYPE_DSHOT1200):
|
case(PWM_TYPE_DSHOT1200):
|
||||||
return MOTOR_DSHOT1200_MHZ * 1000000;
|
return MOTOR_DSHOT1200_HZ;
|
||||||
case(PWM_TYPE_DSHOT600):
|
case(PWM_TYPE_DSHOT600):
|
||||||
return MOTOR_DSHOT600_MHZ * 1000000;
|
return MOTOR_DSHOT600_HZ;
|
||||||
case(PWM_TYPE_DSHOT300):
|
case(PWM_TYPE_DSHOT300):
|
||||||
return MOTOR_DSHOT300_MHZ * 1000000;
|
return MOTOR_DSHOT300_HZ;
|
||||||
default:
|
default:
|
||||||
case(PWM_TYPE_DSHOT150):
|
case(PWM_TYPE_DSHOT150):
|
||||||
return MOTOR_DSHOT150_MHZ * 1000000;
|
return MOTOR_DSHOT150_HZ;
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
|
@ -460,8 +456,7 @@ void servoDevInit(const servoDevConfig_t *servoConfig)
|
||||||
/* flag failure and disable ability to arm */
|
/* flag failure and disable ability to arm */
|
||||||
break;
|
break;
|
||||||
}
|
}
|
||||||
|
pwmOutConfig(&servos[servoIndex], timer, PWM_TIMER_HZ, PWM_TIMER_HZ / servoConfig->servoPwmRate, servoConfig->servoCenterPulse, 0);
|
||||||
pwmOutConfig(&servos[servoIndex], timer, PWM_TIMER_MHZ, 1000000 / servoConfig->servoPwmRate, servoConfig->servoCenterPulse, 0);
|
|
||||||
servos[servoIndex].enabled = true;
|
servos[servoIndex].enabled = true;
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
@ -474,7 +469,7 @@ void pwmWriteBeeper(bool onoffBeep)
|
||||||
if(!beeperPwm.io)
|
if(!beeperPwm.io)
|
||||||
return;
|
return;
|
||||||
if(onoffBeep == true) {
|
if(onoffBeep == true) {
|
||||||
*beeperPwm.ccr = (1000000/freqBeep)/2;
|
*beeperPwm.ccr = (PWM_TIMER_HZ / freqBeep) / 2;
|
||||||
beeperPwm.enabled = true;
|
beeperPwm.enabled = true;
|
||||||
} else {
|
} else {
|
||||||
*beeperPwm.ccr = 0;
|
*beeperPwm.ccr = 0;
|
||||||
|
@ -500,7 +495,7 @@ void beeperPwmInit(IO_t io, uint16_t frequency)
|
||||||
IOConfigGPIO(beeperPwm.io, IOCFG_AF_PP);
|
IOConfigGPIO(beeperPwm.io, IOCFG_AF_PP);
|
||||||
#endif
|
#endif
|
||||||
freqBeep = frequency;
|
freqBeep = frequency;
|
||||||
pwmOutConfig(&beeperPwm, timer, PWM_TIMER_MHZ, 1000000/freqBeep, (1000000/freqBeep)/2,0);
|
pwmOutConfig(&beeperPwm, timer, PWM_TIMER_HZ, PWM_TIMER_HZ / freqBeep, (PWM_TIMER_HZ / freqBeep) / 2, 0);
|
||||||
}
|
}
|
||||||
*beeperPwm.ccr = 0;
|
*beeperPwm.ccr = 0;
|
||||||
beeperPwm.enabled = false;
|
beeperPwm.enabled = false;
|
||||||
|
|
|
@ -20,7 +20,9 @@
|
||||||
#include "drivers/io_types.h"
|
#include "drivers/io_types.h"
|
||||||
#include "timer.h"
|
#include "timer.h"
|
||||||
|
|
||||||
|
#ifndef MAX_SUPPORTED_MOTORS
|
||||||
#define MAX_SUPPORTED_MOTORS 12
|
#define MAX_SUPPORTED_MOTORS 12
|
||||||
|
#endif
|
||||||
|
|
||||||
#if defined(USE_QUAD_MIXER_ONLY)
|
#if defined(USE_QUAD_MIXER_ONLY)
|
||||||
#define MAX_SUPPORTED_SERVOS 1
|
#define MAX_SUPPORTED_SERVOS 1
|
||||||
|
@ -75,45 +77,29 @@ typedef enum {
|
||||||
PWM_TYPE_MAX
|
PWM_TYPE_MAX
|
||||||
} motorPwmProtocolTypes_e;
|
} motorPwmProtocolTypes_e;
|
||||||
|
|
||||||
#define PWM_TIMER_MHZ 1
|
#define PWM_TIMER_HZ MHZ_TO_HZ(1)
|
||||||
|
|
||||||
#ifdef USE_DSHOT
|
#ifdef USE_DSHOT
|
||||||
#define MAX_DMA_TIMERS 8
|
#define MAX_DMA_TIMERS 8
|
||||||
|
|
||||||
#define MOTOR_DSHOT1200_MHZ 24
|
#define MOTOR_DSHOT1200_HZ MHZ_TO_HZ(24)
|
||||||
#define MOTOR_DSHOT600_MHZ 12
|
#define MOTOR_DSHOT600_HZ MHZ_TO_HZ(12)
|
||||||
#define MOTOR_DSHOT300_MHZ 6
|
#define MOTOR_DSHOT300_HZ MHZ_TO_HZ(6)
|
||||||
#define MOTOR_DSHOT150_MHZ 3
|
#define MOTOR_DSHOT150_HZ MHZ_TO_HZ(3)
|
||||||
|
|
||||||
#define MOTOR_BIT_0 7
|
#define MOTOR_BIT_0 7
|
||||||
#define MOTOR_BIT_1 14
|
#define MOTOR_BIT_1 14
|
||||||
#define MOTOR_BITLENGTH 19
|
#define MOTOR_BITLENGTH 19
|
||||||
|
|
||||||
#define MOTOR_PROSHOT1000_MHZ 24
|
#define MOTOR_PROSHOT1000_HZ MHZ_TO_HZ(24)
|
||||||
#define PROSHOT_BASE_SYMBOL 24 // 1uS
|
#define PROSHOT_BASE_SYMBOL 24 // 1uS
|
||||||
#define PROSHOT_BIT_WIDTH 3
|
#define PROSHOT_BIT_WIDTH 3
|
||||||
#define MOTOR_NIBBLE_LENGTH_PROSHOT 96 // 4uS
|
#define MOTOR_NIBBLE_LENGTH_PROSHOT 96 // 4uS
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#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
|
|
||||||
#elif defined(STM32F7) // must be multiples of timer clock
|
|
||||||
#define ONESHOT125_TIMER_MHZ 9
|
|
||||||
#define ONESHOT42_TIMER_MHZ 27
|
|
||||||
#define MULTISHOT_TIMER_MHZ 54
|
|
||||||
#define PWM_BRUSHED_TIMER_MHZ 27
|
|
||||||
#else
|
|
||||||
#define ONESHOT125_TIMER_MHZ 8
|
|
||||||
#define ONESHOT42_TIMER_MHZ 24
|
|
||||||
#define MULTISHOT_TIMER_MHZ 72
|
|
||||||
#define PWM_BRUSHED_TIMER_MHZ 24
|
|
||||||
#endif
|
|
||||||
|
|
||||||
#define DSHOT_DMA_BUFFER_SIZE 18 /* resolution + frame reset (2us) */
|
#define DSHOT_DMA_BUFFER_SIZE 18 /* resolution + frame reset (2us) */
|
||||||
#define PROSHOT_DMA_BUFFER_SIZE 6/* resolution + frame reset (2us) */
|
#define PROSHOT_DMA_BUFFER_SIZE 6 /* resolution + frame reset (2us) */
|
||||||
|
|
||||||
typedef struct {
|
typedef struct {
|
||||||
TIM_TypeDef *timer;
|
TIM_TypeDef *timer;
|
||||||
|
@ -149,9 +135,10 @@ typedef struct {
|
||||||
volatile timCCR_t *ccr;
|
volatile timCCR_t *ccr;
|
||||||
TIM_TypeDef *tim;
|
TIM_TypeDef *tim;
|
||||||
bool forceOverflow;
|
bool forceOverflow;
|
||||||
uint16_t period;
|
|
||||||
bool enabled;
|
bool enabled;
|
||||||
IO_t io;
|
IO_t io;
|
||||||
|
float pulseScale;
|
||||||
|
float pulseOffset;
|
||||||
} pwmOutputPort_t;
|
} pwmOutputPort_t;
|
||||||
|
|
||||||
typedef struct motorDevConfig_s {
|
typedef struct motorDevConfig_s {
|
||||||
|
|
|
@ -391,7 +391,7 @@ void pwmRxInit(const pwmConfig_t *pwmConfig)
|
||||||
IOConfigGPIO(io, IOCFG_AF_PP);
|
IOConfigGPIO(io, IOCFG_AF_PP);
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
timerConfigure(timer, (uint16_t)PWM_TIMER_PERIOD, PWM_TIMER_MHZ);
|
timerConfigure(timer, (uint16_t)PWM_TIMER_PERIOD, PWM_TIMER_HZ);
|
||||||
timerChCCHandlerInit(&port->edgeCb, pwmEdgeCallback);
|
timerChCCHandlerInit(&port->edgeCb, pwmEdgeCallback);
|
||||||
timerChOvrHandlerInit(&port->overflowCb, pwmOverflowCallback);
|
timerChOvrHandlerInit(&port->overflowCb, pwmOverflowCallback);
|
||||||
timerChConfigCallbacks(timer, &port->edgeCb, &port->overflowCb);
|
timerChConfigCallbacks(timer, &port->edgeCb, &port->overflowCb);
|
||||||
|
@ -408,7 +408,7 @@ void pwmRxInit(const pwmConfig_t *pwmConfig)
|
||||||
#define UNUSED_PPM_TIMER_REFERENCE 0
|
#define UNUSED_PPM_TIMER_REFERENCE 0
|
||||||
#define FIRST_PWM_PORT 0
|
#define FIRST_PWM_PORT 0
|
||||||
|
|
||||||
void ppmAvoidPWMTimerClash(TIM_TypeDef *pwmTimer, uint8_t pwmProtocol)
|
void ppmAvoidPWMTimerClash(TIM_TypeDef *pwmTimer)
|
||||||
{
|
{
|
||||||
pwmOutputPort_t *motors = pwmGetMotors();
|
pwmOutputPort_t *motors = pwmGetMotors();
|
||||||
for (int motorIndex = 0; motorIndex < MAX_SUPPORTED_MOTORS; motorIndex++) {
|
for (int motorIndex = 0; motorIndex < MAX_SUPPORTED_MOTORS; motorIndex++) {
|
||||||
|
@ -416,26 +416,12 @@ void ppmAvoidPWMTimerClash(TIM_TypeDef *pwmTimer, uint8_t pwmProtocol)
|
||||||
continue;
|
continue;
|
||||||
}
|
}
|
||||||
|
|
||||||
switch (pwmProtocol)
|
ppmCountDivisor = timerClock(pwmTimer) / (pwmTimer->PSC + 1);
|
||||||
{
|
|
||||||
case PWM_TYPE_ONESHOT125:
|
|
||||||
ppmCountDivisor = ONESHOT125_TIMER_MHZ;
|
|
||||||
break;
|
|
||||||
case PWM_TYPE_ONESHOT42:
|
|
||||||
ppmCountDivisor = ONESHOT42_TIMER_MHZ;
|
|
||||||
break;
|
|
||||||
case PWM_TYPE_MULTISHOT:
|
|
||||||
ppmCountDivisor = MULTISHOT_TIMER_MHZ;
|
|
||||||
break;
|
|
||||||
case PWM_TYPE_BRUSHED:
|
|
||||||
ppmCountDivisor = PWM_BRUSHED_TIMER_MHZ;
|
|
||||||
break;
|
|
||||||
}
|
|
||||||
return;
|
return;
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
void ppmRxInit(const ppmConfig_t *ppmConfig, uint8_t pwmProtocol)
|
void ppmRxInit(const ppmConfig_t *ppmConfig)
|
||||||
{
|
{
|
||||||
ppmResetDevice();
|
ppmResetDevice();
|
||||||
|
|
||||||
|
@ -447,7 +433,7 @@ void ppmRxInit(const ppmConfig_t *ppmConfig, uint8_t pwmProtocol)
|
||||||
return;
|
return;
|
||||||
}
|
}
|
||||||
|
|
||||||
ppmAvoidPWMTimerClash(timer->tim, pwmProtocol);
|
ppmAvoidPWMTimerClash(timer->tim);
|
||||||
|
|
||||||
port->mode = INPUT_MODE_PPM;
|
port->mode = INPUT_MODE_PPM;
|
||||||
port->timerHardware = timer;
|
port->timerHardware = timer;
|
||||||
|
@ -462,7 +448,7 @@ void ppmRxInit(const ppmConfig_t *ppmConfig, uint8_t pwmProtocol)
|
||||||
IOConfigGPIO(io, IOCFG_AF_PP);
|
IOConfigGPIO(io, IOCFG_AF_PP);
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
timerConfigure(timer, (uint16_t)PPM_TIMER_PERIOD, PWM_TIMER_MHZ);
|
timerConfigure(timer, (uint16_t)PPM_TIMER_PERIOD, PWM_TIMER_HZ);
|
||||||
timerChCCHandlerInit(&port->edgeCb, ppmEdgeCallback);
|
timerChCCHandlerInit(&port->edgeCb, ppmEdgeCallback);
|
||||||
timerChOvrHandlerInit(&port->overflowCb, ppmOverflowCallback);
|
timerChOvrHandlerInit(&port->overflowCb, ppmOverflowCallback);
|
||||||
timerChConfigCallbacks(timer, &port->edgeCb, &port->overflowCb);
|
timerChConfigCallbacks(timer, &port->edgeCb, &port->overflowCb);
|
||||||
|
|
|
@ -36,7 +36,7 @@ typedef struct pwmConfig_s {
|
||||||
inputFilteringMode_e inputFilteringMode;
|
inputFilteringMode_e inputFilteringMode;
|
||||||
} pwmConfig_t;
|
} pwmConfig_t;
|
||||||
|
|
||||||
void ppmRxInit(const ppmConfig_t *ppmConfig, uint8_t pwmProtocol);
|
void ppmRxInit(const ppmConfig_t *ppmConfig);
|
||||||
void pwmRxInit(const pwmConfig_t *pwmConfig);
|
void pwmRxInit(const pwmConfig_t *pwmConfig);
|
||||||
|
|
||||||
uint16_t pwmRead(uint8_t channel);
|
uint16_t pwmRead(uint8_t channel);
|
||||||
|
|
|
@ -184,8 +184,7 @@ static void serialTimerTxConfigBL(const timerHardware_t *timerHardwarePtr, uint8
|
||||||
}
|
}
|
||||||
} while (isTimerPeriodTooLarge(timerPeriod));
|
} while (isTimerPeriodTooLarge(timerPeriod));
|
||||||
|
|
||||||
uint8_t mhz = clock / 1000000;
|
timerConfigure(timerHardwarePtr, timerPeriod, clock);
|
||||||
timerConfigure(timerHardwarePtr, timerPeriod, mhz);
|
|
||||||
timerChCCHandlerInit(&escSerialPorts[reference].timerCb, onSerialTimerBL);
|
timerChCCHandlerInit(&escSerialPorts[reference].timerCb, onSerialTimerBL);
|
||||||
timerChConfigCallbacks(timerHardwarePtr, &escSerialPorts[reference].timerCb, NULL);
|
timerChConfigCallbacks(timerHardwarePtr, &escSerialPorts[reference].timerCb, NULL);
|
||||||
}
|
}
|
||||||
|
@ -193,9 +192,8 @@ static void serialTimerTxConfigBL(const timerHardware_t *timerHardwarePtr, uint8
|
||||||
static void serialTimerRxConfigBL(const timerHardware_t *timerHardwarePtr, uint8_t reference, portOptions_t options)
|
static void serialTimerRxConfigBL(const timerHardware_t *timerHardwarePtr, uint8_t reference, portOptions_t options)
|
||||||
{
|
{
|
||||||
// start bit is usually a FALLING signal
|
// start bit is usually a FALLING signal
|
||||||
uint8_t mhz = SystemCoreClock / 2000000;
|
|
||||||
TIM_DeInit(timerHardwarePtr->tim);
|
TIM_DeInit(timerHardwarePtr->tim);
|
||||||
timerConfigure(timerHardwarePtr, 0xFFFF, mhz);
|
timerConfigure(timerHardwarePtr, 0xFFFF, SystemCoreClock / 2);
|
||||||
escSerialICConfig(timerHardwarePtr->tim, timerHardwarePtr->channel, (options & SERIAL_INVERTED) ? TIM_ICPolarity_Rising : TIM_ICPolarity_Falling);
|
escSerialICConfig(timerHardwarePtr->tim, timerHardwarePtr->channel, (options & SERIAL_INVERTED) ? TIM_ICPolarity_Rising : TIM_ICPolarity_Falling);
|
||||||
timerChCCHandlerInit(&escSerialPorts[reference].edgeCb, onSerialRxPinChangeBL);
|
timerChCCHandlerInit(&escSerialPorts[reference].edgeCb, onSerialRxPinChangeBL);
|
||||||
timerChConfigCallbacks(timerHardwarePtr, &escSerialPorts[reference].edgeCb, NULL);
|
timerChConfigCallbacks(timerHardwarePtr, &escSerialPorts[reference].edgeCb, NULL);
|
||||||
|
@ -203,9 +201,9 @@ static void serialTimerRxConfigBL(const timerHardware_t *timerHardwarePtr, uint8
|
||||||
|
|
||||||
static void escSerialTimerTxConfig(const timerHardware_t *timerHardwarePtr, uint8_t reference)
|
static void escSerialTimerTxConfig(const timerHardware_t *timerHardwarePtr, uint8_t reference)
|
||||||
{
|
{
|
||||||
uint32_t timerPeriod=34;
|
uint32_t timerPeriod = 34;
|
||||||
TIM_DeInit(timerHardwarePtr->tim);
|
TIM_DeInit(timerHardwarePtr->tim);
|
||||||
timerConfigure(timerHardwarePtr, timerPeriod, 1);
|
timerConfigure(timerHardwarePtr, timerPeriod, 1e6);
|
||||||
timerChCCHandlerInit(&escSerialPorts[reference].timerCb, onSerialTimerEsc);
|
timerChCCHandlerInit(&escSerialPorts[reference].timerCb, onSerialTimerEsc);
|
||||||
timerChConfigCallbacks(timerHardwarePtr, &escSerialPorts[reference].timerCb, NULL);
|
timerChConfigCallbacks(timerHardwarePtr, &escSerialPorts[reference].timerCb, NULL);
|
||||||
}
|
}
|
||||||
|
@ -228,7 +226,7 @@ static void escSerialTimerRxConfig(const timerHardware_t *timerHardwarePtr, uint
|
||||||
{
|
{
|
||||||
// start bit is usually a FALLING signal
|
// start bit is usually a FALLING signal
|
||||||
TIM_DeInit(timerHardwarePtr->tim);
|
TIM_DeInit(timerHardwarePtr->tim);
|
||||||
timerConfigure(timerHardwarePtr, 0xFFFF, 1);
|
timerConfigure(timerHardwarePtr, 0xFFFF, 1e6);
|
||||||
escSerialICConfig(timerHardwarePtr->tim, timerHardwarePtr->channel, TIM_ICPolarity_Falling);
|
escSerialICConfig(timerHardwarePtr->tim, timerHardwarePtr->channel, TIM_ICPolarity_Falling);
|
||||||
timerChCCHandlerInit(&escSerialPorts[reference].edgeCb, onSerialRxPinChangeEsc);
|
timerChCCHandlerInit(&escSerialPorts[reference].edgeCb, onSerialRxPinChangeEsc);
|
||||||
timerChConfigCallbacks(timerHardwarePtr, &escSerialPorts[reference].edgeCb, NULL);
|
timerChConfigCallbacks(timerHardwarePtr, &escSerialPorts[reference].edgeCb, NULL);
|
||||||
|
|
|
@ -204,7 +204,7 @@ static bool isTimerPeriodTooLarge(uint32_t timerPeriod)
|
||||||
|
|
||||||
static void serialTimerConfigureTimebase(const timerHardware_t *timerHardwarePtr, uint32_t baud)
|
static void serialTimerConfigureTimebase(const timerHardware_t *timerHardwarePtr, uint32_t baud)
|
||||||
{
|
{
|
||||||
uint32_t baseClock = SystemCoreClock / timerClockDivisor(timerHardwarePtr->tim);
|
uint32_t baseClock = timerClock(timerHardwarePtr->tim);
|
||||||
uint32_t clock = baseClock;
|
uint32_t clock = baseClock;
|
||||||
uint32_t timerPeriod;
|
uint32_t timerPeriod;
|
||||||
|
|
||||||
|
@ -220,9 +220,7 @@ static void serialTimerConfigureTimebase(const timerHardware_t *timerHardwarePtr
|
||||||
}
|
}
|
||||||
} while (isTimerPeriodTooLarge(timerPeriod));
|
} while (isTimerPeriodTooLarge(timerPeriod));
|
||||||
|
|
||||||
uint8_t mhz = baseClock / 1000000;
|
timerConfigure(timerHardwarePtr, timerPeriod, baseClock);
|
||||||
|
|
||||||
timerConfigure(timerHardwarePtr, timerPeriod, mhz);
|
|
||||||
}
|
}
|
||||||
|
|
||||||
static void resetBuffers(softSerial_t *softSerial)
|
static void resetBuffers(softSerial_t *softSerial)
|
||||||
|
|
|
@ -229,16 +229,16 @@ void timerNVICConfigure(uint8_t irq)
|
||||||
NVIC_Init(&NVIC_InitStructure);
|
NVIC_Init(&NVIC_InitStructure);
|
||||||
}
|
}
|
||||||
|
|
||||||
void configTimeBase(TIM_TypeDef *tim, uint16_t period, uint8_t mhz)
|
void configTimeBase(TIM_TypeDef *tim, uint16_t period, uint32_t hz)
|
||||||
{
|
{
|
||||||
TIM_TimeBaseInitTypeDef TIM_TimeBaseStructure;
|
TIM_TimeBaseInitTypeDef TIM_TimeBaseStructure;
|
||||||
|
|
||||||
TIM_TimeBaseStructInit(&TIM_TimeBaseStructure);
|
TIM_TimeBaseStructInit(&TIM_TimeBaseStructure);
|
||||||
TIM_TimeBaseStructure.TIM_Period = (period - 1) & 0xffff; // AKA TIMx_ARR
|
TIM_TimeBaseStructure.TIM_Period = (period - 1) & 0xFFFF; // AKA TIMx_ARR
|
||||||
|
|
||||||
// "The counter clock frequency (CK_CNT) is equal to f CK_PSC / (PSC[15:0] + 1)." - STM32F10x Reference Manual 14.4.11
|
// "The counter clock frequency (CK_CNT) is equal to f CK_PSC / (PSC[15:0] + 1)." - STM32F10x Reference Manual 14.4.11
|
||||||
// Thus for 1Mhz: 72000000 / 1000000 = 72, 72 - 1 = 71 = TIM_Prescaler
|
// Thus for 1Mhz: 72000000 / 1000000 = 72, 72 - 1 = 71 = TIM_Prescaler
|
||||||
TIM_TimeBaseStructure.TIM_Prescaler = (SystemCoreClock / timerClockDivisor(tim) / ((uint32_t)mhz * 1000000)) - 1;
|
TIM_TimeBaseStructure.TIM_Prescaler = (timerClock(tim) / hz) - 1;
|
||||||
|
|
||||||
TIM_TimeBaseStructure.TIM_ClockDivision = 0;
|
TIM_TimeBaseStructure.TIM_ClockDivision = 0;
|
||||||
TIM_TimeBaseStructure.TIM_CounterMode = TIM_CounterMode_Up;
|
TIM_TimeBaseStructure.TIM_CounterMode = TIM_CounterMode_Up;
|
||||||
|
@ -246,9 +246,9 @@ void configTimeBase(TIM_TypeDef *tim, uint16_t period, uint8_t mhz)
|
||||||
}
|
}
|
||||||
|
|
||||||
// old interface for PWM inputs. It should be replaced
|
// old interface for PWM inputs. It should be replaced
|
||||||
void timerConfigure(const timerHardware_t *timerHardwarePtr, uint16_t period, uint8_t mhz)
|
void timerConfigure(const timerHardware_t *timerHardwarePtr, uint16_t period, uint32_t hz)
|
||||||
{
|
{
|
||||||
configTimeBase(timerHardwarePtr->tim, period, mhz);
|
configTimeBase(timerHardwarePtr->tim, period, hz);
|
||||||
TIM_Cmd(timerHardwarePtr->tim, ENABLE);
|
TIM_Cmd(timerHardwarePtr->tim, ENABLE);
|
||||||
|
|
||||||
uint8_t irq = timerInputIrq(timerHardwarePtr->tim);
|
uint8_t irq = timerInputIrq(timerHardwarePtr->tim);
|
||||||
|
@ -849,14 +849,19 @@ uint16_t timerDmaSource(uint8_t channel)
|
||||||
|
|
||||||
uint16_t timerGetPrescalerByDesiredMhz(TIM_TypeDef *tim, uint16_t mhz)
|
uint16_t timerGetPrescalerByDesiredMhz(TIM_TypeDef *tim, uint16_t mhz)
|
||||||
{
|
{
|
||||||
// protection here for desired MHZ > timerClock???
|
return timerGetPrescalerByDesiredHertz(tim, MHZ_TO_HZ(mhz));
|
||||||
if ((uint32_t)(mhz * 1000000) > timerClock(tim)) {
|
|
||||||
return 0;
|
|
||||||
}
|
|
||||||
return (uint16_t)(round((timerClock(tim) / (mhz * 1000000)) - 1));
|
|
||||||
}
|
}
|
||||||
|
|
||||||
uint16_t timerGetPeriodByPrescaler(TIM_TypeDef *tim, uint16_t prescaler, uint32_t hertz)
|
uint16_t timerGetPeriodByPrescaler(TIM_TypeDef *tim, uint16_t prescaler, uint32_t hz)
|
||||||
{
|
{
|
||||||
return ((uint16_t)((timerClock(tim) / (prescaler + 1)) / hertz));
|
return ((uint16_t)((timerClock(tim) / (prescaler + 1)) / hz));
|
||||||
|
}
|
||||||
|
|
||||||
|
uint16_t timerGetPrescalerByDesiredHertz(TIM_TypeDef *tim, uint32_t hz)
|
||||||
|
{
|
||||||
|
// protection here for desired hertz > SystemCoreClock???
|
||||||
|
if (hz > timerClock(tim)) {
|
||||||
|
return 0;
|
||||||
|
}
|
||||||
|
return (uint16_t)((timerClock(tim) + hz / 2 ) / hz) - 1;
|
||||||
}
|
}
|
||||||
|
|
|
@ -134,6 +134,8 @@ typedef enum {
|
||||||
#define HARDWARE_TIMER_DEFINITION_COUNT 14
|
#define HARDWARE_TIMER_DEFINITION_COUNT 14
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
#define MHZ_TO_HZ(x) (x * 1000000)
|
||||||
|
|
||||||
extern const timerHardware_t timerHardware[];
|
extern const timerHardware_t timerHardware[];
|
||||||
extern const timerDef_t timerDefinitions[];
|
extern const timerDef_t timerDefinitions[];
|
||||||
|
|
||||||
|
@ -155,7 +157,7 @@ typedef enum {
|
||||||
TYPE_TIMER
|
TYPE_TIMER
|
||||||
} channelType_t;
|
} channelType_t;
|
||||||
|
|
||||||
void timerConfigure(const timerHardware_t *timHw, uint16_t period, uint8_t mhz); // This interface should be replaced.
|
void timerConfigure(const timerHardware_t *timHw, uint16_t period, uint32_t hz); // This interface should be replaced.
|
||||||
|
|
||||||
void timerChConfigIC(const timerHardware_t *timHw, bool polarityRising, unsigned inputFilterSamples);
|
void timerChConfigIC(const timerHardware_t *timHw, bool polarityRising, unsigned inputFilterSamples);
|
||||||
void timerChConfigICDual(const timerHardware_t* timHw, bool polarityRising, unsigned inputFilterSamples);
|
void timerChConfigICDual(const timerHardware_t* timHw, bool polarityRising, unsigned inputFilterSamples);
|
||||||
|
@ -183,7 +185,7 @@ void timerForceOverflow(TIM_TypeDef *tim);
|
||||||
uint8_t timerClockDivisor(TIM_TypeDef *tim);
|
uint8_t timerClockDivisor(TIM_TypeDef *tim);
|
||||||
uint32_t timerClock(TIM_TypeDef *tim);
|
uint32_t timerClock(TIM_TypeDef *tim);
|
||||||
|
|
||||||
void configTimeBase(TIM_TypeDef *tim, uint16_t period, uint8_t mhz); // TODO - just for migration
|
void configTimeBase(TIM_TypeDef *tim, uint16_t period, uint32_t hz); // TODO - just for migration
|
||||||
|
|
||||||
rccPeriphTag_t timerRCC(TIM_TypeDef *tim);
|
rccPeriphTag_t timerRCC(TIM_TypeDef *tim);
|
||||||
uint8_t timerInputIrq(TIM_TypeDef *tim);
|
uint8_t timerInputIrq(TIM_TypeDef *tim);
|
||||||
|
@ -200,5 +202,6 @@ void timerOCPreloadConfig(TIM_TypeDef *tim, uint8_t channel, uint16_t preload);
|
||||||
volatile timCCR_t *timerCCR(TIM_TypeDef *tim, uint8_t channel);
|
volatile timCCR_t *timerCCR(TIM_TypeDef *tim, uint8_t channel);
|
||||||
uint16_t timerDmaSource(uint8_t channel);
|
uint16_t timerDmaSource(uint8_t channel);
|
||||||
|
|
||||||
|
uint16_t timerGetPrescalerByDesiredHertz(TIM_TypeDef *tim, uint32_t hz);
|
||||||
uint16_t timerGetPrescalerByDesiredMhz(TIM_TypeDef *tim, uint16_t mhz);
|
uint16_t timerGetPrescalerByDesiredMhz(TIM_TypeDef *tim, uint16_t mhz);
|
||||||
uint16_t timerGetPeriodByPrescaler(TIM_TypeDef *tim, uint16_t prescaler, uint32_t hertz);
|
uint16_t timerGetPeriodByPrescaler(TIM_TypeDef *tim, uint16_t prescaler, uint32_t hz);
|
||||||
|
|
|
@ -241,7 +241,7 @@ TIM_HandleTypeDef* timerFindTimerHandle(TIM_TypeDef *tim)
|
||||||
return &timerHandle[timerIndex].Handle;
|
return &timerHandle[timerIndex].Handle;
|
||||||
}
|
}
|
||||||
|
|
||||||
void configTimeBase(TIM_TypeDef *tim, uint16_t period, uint8_t mhz)
|
void configTimeBase(TIM_TypeDef *tim, uint16_t period, uint32_t hz)
|
||||||
{
|
{
|
||||||
uint8_t timerIndex = lookupTimerIndex(tim);
|
uint8_t timerIndex = lookupTimerIndex(tim);
|
||||||
if (timerIndex >= USED_TIMER_COUNT) {
|
if (timerIndex >= USED_TIMER_COUNT) {
|
||||||
|
@ -256,7 +256,7 @@ void configTimeBase(TIM_TypeDef *tim, uint16_t period, uint8_t mhz)
|
||||||
timerHandle[timerIndex].Handle.Instance = tim;
|
timerHandle[timerIndex].Handle.Instance = tim;
|
||||||
|
|
||||||
timerHandle[timerIndex].Handle.Init.Period = (period - 1) & 0xffff; // AKA TIMx_ARR
|
timerHandle[timerIndex].Handle.Init.Period = (period - 1) & 0xffff; // AKA TIMx_ARR
|
||||||
timerHandle[timerIndex].Handle.Init.Prescaler = (SystemCoreClock / timerClockDivisor(tim) / ((uint32_t)mhz * 1000000)) - 1;
|
timerHandle[timerIndex].Handle.Init.Prescaler = (timerClock(tim) / hz) - 1;
|
||||||
|
|
||||||
timerHandle[timerIndex].Handle.Init.ClockDivision = TIM_CLOCKDIVISION_DIV1;
|
timerHandle[timerIndex].Handle.Init.ClockDivision = TIM_CLOCKDIVISION_DIV1;
|
||||||
timerHandle[timerIndex].Handle.Init.CounterMode = TIM_COUNTERMODE_UP;
|
timerHandle[timerIndex].Handle.Init.CounterMode = TIM_COUNTERMODE_UP;
|
||||||
|
@ -287,14 +287,14 @@ void configTimeBase(TIM_TypeDef *tim, uint16_t period, uint8_t mhz)
|
||||||
}
|
}
|
||||||
|
|
||||||
// old interface for PWM inputs. It should be replaced
|
// old interface for PWM inputs. It should be replaced
|
||||||
void timerConfigure(const timerHardware_t *timerHardwarePtr, uint16_t period, uint8_t mhz)
|
void timerConfigure(const timerHardware_t *timerHardwarePtr, uint16_t period, uint32_t hz)
|
||||||
{
|
{
|
||||||
uint8_t timerIndex = lookupTimerIndex(timerHardwarePtr->tim);
|
uint8_t timerIndex = lookupTimerIndex(timerHardwarePtr->tim);
|
||||||
if (timerIndex >= USED_TIMER_COUNT) {
|
if (timerIndex >= USED_TIMER_COUNT) {
|
||||||
return;
|
return;
|
||||||
}
|
}
|
||||||
|
|
||||||
configTimeBase(timerHardwarePtr->tim, period, mhz);
|
configTimeBase(timerHardwarePtr->tim, period, hz);
|
||||||
HAL_TIM_Base_Start(&timerHandle[timerIndex].Handle);
|
HAL_TIM_Base_Start(&timerHandle[timerIndex].Handle);
|
||||||
|
|
||||||
uint8_t irq = timerInputIrq(timerHardwarePtr->tim);
|
uint8_t irq = timerInputIrq(timerHardwarePtr->tim);
|
||||||
|
@ -898,14 +898,19 @@ uint16_t timerDmaSource(uint8_t channel)
|
||||||
|
|
||||||
uint16_t timerGetPrescalerByDesiredMhz(TIM_TypeDef *tim, uint16_t mhz)
|
uint16_t timerGetPrescalerByDesiredMhz(TIM_TypeDef *tim, uint16_t mhz)
|
||||||
{
|
{
|
||||||
// protection here for desired MHZ > SystemCoreClock???
|
return timerGetPrescalerByDesiredHertz(tim, MHZ_TO_HZ(mhz));
|
||||||
if (mhz * 1000000 > (SystemCoreClock / timerClockDivisor(tim))) {
|
|
||||||
return 0;
|
|
||||||
}
|
|
||||||
return (uint16_t)(round((SystemCoreClock / timerClockDivisor(tim) / (mhz * 1000000)) - 1));
|
|
||||||
}
|
}
|
||||||
|
|
||||||
uint16_t timerGetPeriodByPrescaler(TIM_TypeDef *tim, uint16_t prescaler, uint32_t hertz)
|
uint16_t timerGetPeriodByPrescaler(TIM_TypeDef *tim, uint16_t prescaler, uint32_t hz)
|
||||||
{
|
{
|
||||||
return ((uint16_t)((SystemCoreClock / timerClockDivisor(tim) / (prescaler + 1)) / hertz));
|
return ((uint16_t)((timerClock(tim) / (prescaler + 1)) / hz));
|
||||||
|
}
|
||||||
|
|
||||||
|
uint16_t timerGetPrescalerByDesiredHertz(TIM_TypeDef *tim, uint32_t hz)
|
||||||
|
{
|
||||||
|
// protection here for desired hertz > SystemCoreClock???
|
||||||
|
if (hz > timerClock(tim)) {
|
||||||
|
return 0;
|
||||||
|
}
|
||||||
|
return (uint16_t)((timerClock(tim) + hz / 2 ) / hz) - 1;
|
||||||
}
|
}
|
|
@ -384,7 +384,7 @@ void init(void)
|
||||||
if (0) {}
|
if (0) {}
|
||||||
#if defined(USE_PPM)
|
#if defined(USE_PPM)
|
||||||
else if (feature(FEATURE_RX_PPM)) {
|
else if (feature(FEATURE_RX_PPM)) {
|
||||||
ppmRxInit(ppmConfig(), motorConfig()->dev.motorPwmProtocol);
|
ppmRxInit(ppmConfig());
|
||||||
}
|
}
|
||||||
#endif
|
#endif
|
||||||
#if defined(USE_PWM)
|
#if defined(USE_PWM)
|
||||||
|
|
|
@ -36,6 +36,7 @@
|
||||||
// Using RX DMA disables the use of receive callbacks
|
// Using RX DMA disables the use of receive callbacks
|
||||||
#define USE_UART1_RX_DMA
|
#define USE_UART1_RX_DMA
|
||||||
#define USE_UART1_TX_DMA
|
#define USE_UART1_TX_DMA
|
||||||
|
#define MAX_SUPPORTED_MOTORS 8
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#ifdef STM32F3
|
#ifdef STM32F3
|
||||||
|
|
Loading…
Reference in New Issue