Fix AlienFlight F3 and Sparky PPM RX
This commit is contained in:
parent
03608bc4fc
commit
c35675d258
|
@ -293,8 +293,8 @@ pwmOutputConfiguration_t *pwmInit(drv_pwm_config_t *init)
|
||||||
if (type == MAP_TO_PPM_INPUT) {
|
if (type == MAP_TO_PPM_INPUT) {
|
||||||
#ifndef SKIP_RX_PWM_PPM
|
#ifndef SKIP_RX_PWM_PPM
|
||||||
#if defined(SPARKY) || defined(ALIENFLIGHTF3)
|
#if defined(SPARKY) || defined(ALIENFLIGHTF3)
|
||||||
if (init->useFastPwm || init->pwmProtocolType == PWM_TYPE_BRUSHED) {
|
if (!(init->pwmProtocolType == PWM_TYPE_CONVENTIONAL)) {
|
||||||
ppmAvoidPWMTimerClash(timerHardwarePtr, TIM2);
|
ppmAvoidPWMTimerClash(timerHardwarePtr, TIM2, init->pwmProtocolType);
|
||||||
}
|
}
|
||||||
#endif
|
#endif
|
||||||
ppmInConfig(timerHardwarePtr);
|
ppmInConfig(timerHardwarePtr);
|
||||||
|
@ -307,7 +307,7 @@ pwmOutputConfiguration_t *pwmInit(drv_pwm_config_t *init)
|
||||||
} else if (type == MAP_TO_MOTOR_OUTPUT) {
|
} else if (type == MAP_TO_MOTOR_OUTPUT) {
|
||||||
|
|
||||||
#ifdef CC3D
|
#ifdef CC3D
|
||||||
if (init->useFastPwm || init->pwmProtocolType == PWM_TYPE_BRUSHED) {
|
if (!(init->pwmProtocolType == PWM_TYPE_CONVENTIONAL)) {
|
||||||
// Skip it if it would cause PPM capture timer to be reconfigured or manually overflowed
|
// Skip it if it would cause PPM capture timer to be reconfigured or manually overflowed
|
||||||
if (timerHardwarePtr->tim == TIM2)
|
if (timerHardwarePtr->tim == TIM2)
|
||||||
continue;
|
continue;
|
||||||
|
|
|
@ -26,18 +26,6 @@
|
||||||
#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_5US_PW (MULTISHOT_TIMER_MHZ * 5)
|
||||||
#define MULTISHOT_20US_MULT (MULTISHOT_TIMER_MHZ * 20 / 1000.0f)
|
#define MULTISHOT_20US_MULT (MULTISHOT_TIMER_MHZ * 20 / 1000.0f)
|
||||||
|
|
||||||
|
|
|
@ -25,6 +25,18 @@ typedef enum {
|
||||||
PWM_TYPE_BRUSHED
|
PWM_TYPE_BRUSHED
|
||||||
} motorPwmProtocolTypes_e;
|
} motorPwmProtocolTypes_e;
|
||||||
|
|
||||||
|
#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
|
||||||
|
|
||||||
struct timerHardware_s;
|
struct timerHardware_s;
|
||||||
void pwmBrushedMotorConfig(const struct timerHardware_s *timerHardware, uint8_t motorIndex, uint16_t motorPwmRate);
|
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 pwmBrushlessMotorConfig(const struct timerHardware_s *timerHardware, uint8_t motorIndex, uint16_t motorPwmRate, uint16_t idlePulse);
|
||||||
|
|
|
@ -33,6 +33,7 @@
|
||||||
#include "gpio.h"
|
#include "gpio.h"
|
||||||
#include "timer.h"
|
#include "timer.h"
|
||||||
|
|
||||||
|
#include "pwm_output.h"
|
||||||
#include "pwm_mapping.h"
|
#include "pwm_mapping.h"
|
||||||
|
|
||||||
#include "pwm_rx.h"
|
#include "pwm_rx.h"
|
||||||
|
@ -85,7 +86,7 @@ static uint16_t captures[PWM_PORTS_OR_PPM_CAPTURE_COUNT];
|
||||||
|
|
||||||
static uint8_t ppmFrameCount = 0;
|
static uint8_t ppmFrameCount = 0;
|
||||||
static uint8_t lastPPMFrameCount = 0;
|
static uint8_t lastPPMFrameCount = 0;
|
||||||
static uint8_t ppmCountShift = 0;
|
static uint8_t ppmCountDivisor = 1;
|
||||||
|
|
||||||
typedef struct ppmDevice_s {
|
typedef struct ppmDevice_s {
|
||||||
uint8_t pulseIndex;
|
uint8_t pulseIndex;
|
||||||
|
@ -204,14 +205,14 @@ static void ppmEdgeCallback(timerCCHandlerRec_t* cbRec, captureCompare_t capture
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
// Divide by 8 if Oneshot125 is active and this is a CC3D board
|
// Divide value if Oneshot, Multishot or brushed motors are active and the timer is shared
|
||||||
currentTime = currentTime >> ppmCountShift;
|
currentTime = currentTime / ppmCountDivisor;
|
||||||
|
|
||||||
/* Capture computation */
|
/* Capture computation */
|
||||||
if (currentTime > previousTime) {
|
if (currentTime > previousTime) {
|
||||||
ppmDev.deltaTime = currentTime - (previousTime + (ppmDev.overflowed ? (PPM_TIMER_PERIOD >> ppmCountShift) : 0));
|
ppmDev.deltaTime = currentTime - (previousTime + (ppmDev.overflowed ? (PPM_TIMER_PERIOD / ppmCountDivisor) : 0));
|
||||||
} else {
|
} else {
|
||||||
ppmDev.deltaTime = (PPM_TIMER_PERIOD >> ppmCountShift) + currentTime - previousTime;
|
ppmDev.deltaTime = (PPM_TIMER_PERIOD / ppmCountDivisor) + currentTime - previousTime;
|
||||||
}
|
}
|
||||||
|
|
||||||
ppmDev.overflowed = false;
|
ppmDev.overflowed = false;
|
||||||
|
@ -383,11 +384,25 @@ void pwmInConfig(const timerHardware_t *timerHardwarePtr, uint8_t channel)
|
||||||
#define UNUSED_PPM_TIMER_REFERENCE 0
|
#define UNUSED_PPM_TIMER_REFERENCE 0
|
||||||
#define FIRST_PWM_PORT 0
|
#define FIRST_PWM_PORT 0
|
||||||
|
|
||||||
void ppmAvoidPWMTimerClash(const timerHardware_t *timerHardwarePtr, TIM_TypeDef *sharedPwmTimer)
|
void ppmAvoidPWMTimerClash(const timerHardware_t *timerHardwarePtr, TIM_TypeDef *sharedPwmTimer, uint8_t pwmProtocol)
|
||||||
{
|
{
|
||||||
if (timerHardwarePtr->tim == sharedPwmTimer) {
|
if (timerHardwarePtr->tim == sharedPwmTimer) {
|
||||||
ppmCountShift = 3; // Divide by 8 if the timer is running at 8 MHz
|
switch (pwmProtocol)
|
||||||
}
|
{
|
||||||
|
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;
|
||||||
|
}
|
||||||
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
void ppmInConfig(const timerHardware_t *timerHardwarePtr)
|
void ppmInConfig(const timerHardware_t *timerHardwarePtr)
|
||||||
|
|
|
@ -26,7 +26,7 @@ typedef enum {
|
||||||
|
|
||||||
|
|
||||||
void ppmInConfig(const timerHardware_t *timerHardwarePtr);
|
void ppmInConfig(const timerHardware_t *timerHardwarePtr);
|
||||||
void ppmAvoidPWMTimerClash(const timerHardware_t *timerHardwarePtr, TIM_TypeDef *sharedPwmTimer);
|
void ppmAvoidPWMTimerClash(const timerHardware_t *timerHardwarePtr, TIM_TypeDef *sharedPwmTimer, uint8_t pwmProtocol);
|
||||||
|
|
||||||
void pwmInConfig(const timerHardware_t *timerHardwarePtr, uint8_t channel);
|
void pwmInConfig(const timerHardware_t *timerHardwarePtr, uint8_t channel);
|
||||||
uint16_t pwmRead(uint8_t channel);
|
uint16_t pwmRead(uint8_t channel);
|
||||||
|
|
Loading…
Reference in New Issue