Merge pull request #872 from AlienWiiBF/PPM_fix
AlienFlightF3 and Sparky PPM fix (timer clash and PPM timer initialization)
This commit is contained in:
commit
96c3b25ee9
|
@ -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);
|
||||||
|
|
|
@ -78,6 +78,12 @@ void targetConfiguration(void)
|
||||||
masterConfig.motor_pwm_rate = 32000;
|
masterConfig.motor_pwm_rate = 32000;
|
||||||
masterConfig.failsafeConfig.failsafe_delay = 2;
|
masterConfig.failsafeConfig.failsafe_delay = 2;
|
||||||
masterConfig.failsafeConfig.failsafe_off_delay = 0;
|
masterConfig.failsafeConfig.failsafe_off_delay = 0;
|
||||||
|
currentProfile->pidProfile.P8[ROLL] = 90;
|
||||||
|
currentProfile->pidProfile.I8[ROLL] = 44;
|
||||||
|
currentProfile->pidProfile.D8[ROLL] = 60;
|
||||||
|
currentProfile->pidProfile.P8[PITCH] = 90;
|
||||||
|
currentProfile->pidProfile.I8[PITCH] = 44;
|
||||||
|
currentProfile->pidProfile.D8[PITCH] = 60;
|
||||||
|
|
||||||
masterConfig.customMotorMixer[0] = (motorMixer_t){ 1.0f, -0.414178f, 1.0f, -1.0f }; // REAR_R
|
masterConfig.customMotorMixer[0] = (motorMixer_t){ 1.0f, -0.414178f, 1.0f, -1.0f }; // REAR_R
|
||||||
masterConfig.customMotorMixer[1] = (motorMixer_t){ 1.0f, -0.414178f, -1.0f, 1.0f }; // FRONT_R
|
masterConfig.customMotorMixer[1] = (motorMixer_t){ 1.0f, -0.414178f, -1.0f, 1.0f }; // FRONT_R
|
||||||
|
|
|
@ -63,28 +63,19 @@ const uint16_t airPWM[] = {
|
||||||
|
|
||||||
|
|
||||||
const timerHardware_t timerHardware[USABLE_TIMER_CHANNEL_COUNT] = {
|
const timerHardware_t timerHardware[USABLE_TIMER_CHANNEL_COUNT] = {
|
||||||
// 6 x 3 pin headers
|
// up to 10 Motor Outputs
|
||||||
{ TIM15, IO_TAG(PB15), TIM_Channel_2, TIM1_BRK_TIM15_IRQn, 1, IOCFG_AF_PP, GPIO_AF_1 }, // PWM1 - PB15 - TIM1_CH3N, TIM15_CH1N, *TIM15_CH2
|
{ TIM15, IO_TAG(PB15), TIM_Channel_2, TIM1_BRK_TIM15_IRQn, 1, IOCFG_AF_PP, GPIO_AF_1 }, // PWM1 - PB15 - TIM1_CH3N, TIM15_CH1N, *TIM15_CH2
|
||||||
{ TIM15, IO_TAG(PB14), TIM_Channel_1, TIM1_BRK_TIM15_IRQn, 1, IOCFG_AF_PP, GPIO_AF_1 }, // PWM2 - PB14 - TIM1_CH2N, *TIM15_CH1
|
{ TIM15, IO_TAG(PB14), TIM_Channel_1, TIM1_BRK_TIM15_IRQn, 1, IOCFG_AF_PP, GPIO_AF_1 }, // PWM2 - PB14 - TIM1_CH2N, *TIM15_CH1
|
||||||
{ TIM1, IO_TAG(PA8), TIM_Channel_1, TIM1_CC_IRQn, 1, IOCFG_AF_PP, GPIO_AF_6 }, // PWM3 - PA8 - *TIM1_CH1, TIM4_ETR
|
{ TIM1, IO_TAG(PA8), TIM_Channel_1, TIM1_CC_IRQn, 1, IOCFG_AF_PP, GPIO_AF_6 }, // PWM3 - PA8 - *TIM1_CH1, TIM4_ETR
|
||||||
{ TIM3, IO_TAG(PB0), TIM_Channel_3, TIM3_IRQn, 0, IOCFG_AF_PP, GPIO_AF_2 }, // PWM4 - PB0 - *TIM3_CH3, TIM1_CH2N, TIM8_CH2N
|
{ TIM3, IO_TAG(PB0), TIM_Channel_3, TIM3_IRQn, 0, IOCFG_AF_PP, GPIO_AF_2 }, // PWM4 - PB0 - *TIM3_CH3, TIM1_CH2N, TIM8_CH2N
|
||||||
{ TIM3, IO_TAG(PA6), TIM_Channel_1, TIM3_IRQn, 0, IOCFG_AF_PP, GPIO_AF_2 }, // PWM5 - PA6 - *TIM3_CH1, TIM8_BKIN, TIM1_BKIN, TIM16_CH1
|
{ TIM3, IO_TAG(PA6), TIM_Channel_1, TIM3_IRQn, 0, IOCFG_AF_PP, GPIO_AF_2 }, // PWM5 - PA6 - *TIM3_CH1, TIM8_BKIN, TIM1_BKIN, TIM16_CH1
|
||||||
{ TIM2, IO_TAG(PA2), TIM_Channel_3, TIM2_IRQn, 0, IOCFG_AF_PP, GPIO_AF_1 }, // PWM6 - PA2 - *TIM2_CH3, !TIM15_CH1
|
{ TIM2, IO_TAG(PA2), TIM_Channel_3, TIM2_IRQn, 0, IOCFG_AF_PP, GPIO_AF_1 }, // PWM6 - PA2 - *TIM2_CH3, !TIM15_CH1
|
||||||
|
|
||||||
// 6 pin header
|
|
||||||
// PWM7-10
|
|
||||||
{ TIM3, IO_TAG(PB1), TIM_Channel_4, TIM3_IRQn, 0, IOCFG_AF_PP, GPIO_AF_2 }, // PWM7 - PB1 - *TIM3_CH4, TIM1_CH3N, TIM8_CH3N
|
{ TIM3, IO_TAG(PB1), TIM_Channel_4, TIM3_IRQn, 0, IOCFG_AF_PP, GPIO_AF_2 }, // PWM7 - PB1 - *TIM3_CH4, TIM1_CH3N, TIM8_CH3N
|
||||||
{ TIM17, IO_TAG(PA7), TIM_Channel_1, TIM1_TRG_COM_TIM17_IRQn, 1, IOCFG_AF_PP, GPIO_AF_1 }, // PWM8 - PA7 - !TIM3_CH2, *TIM17_CH1, TIM1_CH1N, TIM8_CH1
|
{ TIM17, IO_TAG(PA7), TIM_Channel_1, TIM1_TRG_COM_TIM17_IRQn, 1, IOCFG_AF_PP, GPIO_AF_1 }, // PWM8 - PA7 - !TIM3_CH2, *TIM17_CH1, TIM1_CH1N, TIM8_CH1
|
||||||
{ TIM3, IO_TAG(PA4), TIM_Channel_2, TIM3_IRQn, 0, IOCFG_AF_PP, GPIO_AF_2 }, // PWM9 - PA4 - *TIM3_CH2
|
{ TIM3, IO_TAG(PA4), TIM_Channel_2, TIM3_IRQn, 0, IOCFG_AF_PP, GPIO_AF_2 }, // PWM9 - PA4 - *TIM3_CH2
|
||||||
{ TIM2, IO_TAG(PA1), TIM_Channel_2, TIM2_IRQn, 0, IOCFG_AF_PP, GPIO_AF_1 }, // PWM10 - PA1 - *TIM2_CH2, TIM15_CH1N
|
{ TIM2, IO_TAG(PA1), TIM_Channel_2, TIM2_IRQn, 0, IOCFG_AF_PP, GPIO_AF_1 }, // PWM10 - PA1 - *TIM2_CH2, TIM15_CH1N
|
||||||
|
|
||||||
// PPM PORT - Also USART2 RX (AF5)
|
// PPM PORT - Also USART2 RX (AF5)
|
||||||
{ TIM2, IO_TAG(PA3), TIM_Channel_4, TIM2_IRQn, 0, IOCFG_IPD, GPIO_AF_1 } // PPM - PA3 - TIM2_CH4, TIM15_CH2 - PWM13
|
{ TIM2, IO_TAG(PA3), TIM_Channel_4, TIM2_IRQn, 0, IOCFG_AF_PP_PD, GPIO_AF_1 } // PPM - PA3 - TIM2_CH4, TIM15_CH2 - PWM13
|
||||||
//{ TIM15, GPIOA, Pin_3, TIM_Channel_2, TIM1_BRK_TIM15_IRQn, 0, IOCFG_IPD, GPIO_PinSource3, GPIO_AF_9 } // PPM - PA3 - TIM2_CH4, TIM15_CH2 - PWM13
|
|
||||||
|
|
||||||
// USART3 RX/TX
|
|
||||||
// RX conflicts with PPM port
|
|
||||||
//{ TIM2, GPIOB, Pin_11, TIM_Channel_4, TIM3_IRQn, 0, IOCFG_AF_PP, GPIO_PinSource11, GPIO_AF_1 } // RX - PB11 - *TIM2_CH4, UART3_RX (AF7) - PWM11
|
|
||||||
//{ TIM2, GPIOB, Pin_10, TIM_Channel_3, TIM3_IRQn, 0, IOCFG_AF_PP, GPIO_PinSource10, GPIO_AF_1 } // TX - PB10 - *TIM2_CH3, UART3_TX (AF7) - PWM12
|
|
||||||
};
|
};
|
||||||
|
|
||||||
|
|
|
@ -72,7 +72,7 @@
|
||||||
#define USE_UART2 // Receiver - RX (PA3)
|
#define USE_UART2 // Receiver - RX (PA3)
|
||||||
#define USE_UART3 // Not connected - 10/RX (PB11) 11/TX (PB10)
|
#define USE_UART3 // Not connected - 10/RX (PB11) 11/TX (PB10)
|
||||||
#define SERIAL_PORT_COUNT 4
|
#define SERIAL_PORT_COUNT 4
|
||||||
#define AVOID_UART3_FOR_PWM_PPM
|
#define AVOID_UART2_FOR_PWM_PPM
|
||||||
|
|
||||||
#define UART1_TX_PIN PB6
|
#define UART1_TX_PIN PB6
|
||||||
#define UART1_RX_PIN PB7
|
#define UART1_RX_PIN PB7
|
||||||
|
|
|
@ -56,7 +56,7 @@
|
||||||
#define USE_UART2 // Input - RX (PA3)
|
#define USE_UART2 // Input - RX (PA3)
|
||||||
#define USE_UART3 // Servo out - 10/RX (PB11) 11/TX (PB10)
|
#define USE_UART3 // Servo out - 10/RX (PB11) 11/TX (PB10)
|
||||||
#define SERIAL_PORT_COUNT 4
|
#define SERIAL_PORT_COUNT 4
|
||||||
#define AVOID_UART3_FOR_PWM_PPM
|
#define AVOID_UART2_FOR_PWM_PPM
|
||||||
|
|
||||||
#define UART1_TX_PIN PB6
|
#define UART1_TX_PIN PB6
|
||||||
#define UART1_RX_PIN PB7
|
#define UART1_RX_PIN PB7
|
||||||
|
|
Loading…
Reference in New Issue