1
0
Fork 0
mirror of https://github.com/betaflight/betaflight.git synced 2025-07-16 04:45:24 +03:00

Software serial implementation. Compile with SOFTSERIAL_19200_LOOPBACK to test. Without the define the implementation will have no effect. Next step is to add a 'feature' to enable softserial and settings for the baud rate. Note, only READ is currently supported, write will come later. The highlevel api calls are used in main.c. Uart implementation needs cleanup to make serial port code generic, see uart files for details.

git-svn-id: https://afrodevices.googlecode.com/svn/trunk/baseflight@390 7c89a4a9-59b9-e629-4cfe-3a2d53b20e61
This commit is contained in:
timecop@gmail.com 2013-08-28 01:26:10 +00:00
parent fa7eecac18
commit 77a241bd5f
13 changed files with 466 additions and 162 deletions

View file

@ -1,4 +1,4 @@
#include "board.h"
#include "board.h"
#define PULSE_1MS (1000) // 1ms pulse width
@ -6,9 +6,9 @@
Configuration maps:
1) multirotor PPM input
PWM1 used for PPM
PWM5..8 used for motors
PWM9..10 used for servo or else motors
PWM1 used for PPM
PWM5..8 used for motors
PWM9..10 used for servo or else motors
PWM11..14 used for motors
2) multirotor PPM input with more servos
@ -28,9 +28,9 @@
PWM11.14 used for servos
4) airplane / flying wing with PPM
PWM1 used for PPM
PWM5..8 used for servos
PWM9 used for motor throttle +PWM10 for 2nd motor
PWM1 used for PPM
PWM5..8 used for servos
PWM9 used for motor throttle +PWM10 for 2nd motor
PWM11.14 used for servos
*/
@ -38,9 +38,9 @@ typedef struct {
volatile uint16_t *ccr;
uint16_t period;
// for input only
uint8_t channel;
uint8_t state;
// for input only
uint8_t channel;
uint8_t state;
uint16_t rise;
uint16_t fall;
uint16_t capture;
@ -134,27 +134,17 @@ static const uint8_t * const hardwareMaps[] = {
multiPWM,
multiPPM,
airPWM,
airPPM,
};
static void pwmTimeBase(TIM_TypeDef *tim, uint32_t period)
{
TIM_TimeBaseInitTypeDef TIM_TimeBaseStructure;
TIM_TimeBaseStructInit(&TIM_TimeBaseStructure);
TIM_TimeBaseStructure.TIM_Period = period - 1;
TIM_TimeBaseStructure.TIM_Prescaler = (SystemCoreClock / 1000000) - 1; // all timers run at 1MHz
TIM_TimeBaseStructure.TIM_ClockDivision = 0;
TIM_TimeBaseStructure.TIM_CounterMode = TIM_CounterMode_Up;
TIM_TimeBaseInit(tim, &TIM_TimeBaseStructure);
}
airPPM,
};
#define PWM_TIMER_MHZ 1
static void pwmOCConfig(TIM_TypeDef *tim, uint8_t channel, uint16_t value)
{
TIM_OCInitTypeDef TIM_OCInitStructure;
TIM_OCStructInit(&TIM_OCInitStructure);
TIM_OCInitStructure.TIM_OCMode = TIM_OCMode_PWM2;
TIM_OCStructInit(&TIM_OCInitStructure);
TIM_OCInitStructure.TIM_OCMode = TIM_OCMode_PWM2;
TIM_OCInitStructure.TIM_OutputState = TIM_OutputState_Enable;
TIM_OCInitStructure.TIM_OutputNState = TIM_OutputNState_Disable;
TIM_OCInitStructure.TIM_Pulse = value;
@ -178,13 +168,13 @@ static void pwmOCConfig(TIM_TypeDef *tim, uint8_t channel, uint16_t value)
TIM_OC4Init(tim, &TIM_OCInitStructure);
TIM_OC4PreloadConfig(tim, TIM_OCPreload_Enable);
break;
}
}
static void pwmICConfig(TIM_TypeDef *tim, uint8_t channel, uint16_t polarity)
{
TIM_ICInitTypeDef TIM_ICInitStructure;
}
}
void pwmICConfig(TIM_TypeDef *tim, uint8_t channel, uint16_t polarity)
{
TIM_ICInitTypeDef TIM_ICInitStructure;
TIM_ICStructInit(&TIM_ICInitStructure);
TIM_ICInitStructure.TIM_Channel = channel;
TIM_ICInitStructure.TIM_ICPolarity = polarity;
@ -205,13 +195,13 @@ static void pwmGPIOConfig(GPIO_TypeDef *gpio, uint32_t pin, GPIO_Mode mode)
gpioInit(gpio, &cfg);
}
static pwmPortData_t *pwmOutConfig(uint8_t port, uint16_t period, uint16_t value)
{
pwmPortData_t *p = &pwmPorts[port];
pwmTimeBase(timerHardware[port].tim, period);
pwmGPIOConfig(timerHardware[port].gpio, timerHardware[port].pin, Mode_AF_PP);
pwmOCConfig(timerHardware[port].tim, timerHardware[port].channel, value);
// Needed only on TIM1
static pwmPortData_t *pwmOutConfig(uint8_t port, uint16_t period, uint16_t value)
{
pwmPortData_t *p = &pwmPorts[port];
configTimeBase(timerHardware[port].tim, period, PWM_TIMER_MHZ);
pwmGPIOConfig(timerHardware[port].gpio, timerHardware[port].pin, Mode_AF_PP);
pwmOCConfig(timerHardware[port].tim, timerHardware[port].channel, value);
// Needed only on TIM1
if (timerHardware[port].outputEnable)
TIM_CtrlPWMOutputs(timerHardware[port].tim, ENABLE);
TIM_Cmd(timerHardware[port].tim, ENABLE);
@ -227,32 +217,32 @@ static pwmPortData_t *pwmOutConfig(uint8_t port, uint16_t period, uint16_t value
p->ccr = &timerHardware[port].tim->CCR3;
break;
case TIM_Channel_4:
p->ccr = &timerHardware[port].tim->CCR4;
break;
}
p->ccr = &timerHardware[port].tim->CCR4;
break;
}
return p;
}
static pwmPortData_t *pwmInConfig(uint8_t port, timerCCCallbackPtr callback, uint8_t channel)
{
pwmPortData_t *p = &pwmPorts[port];
pwmTimeBase(timerHardware[port].tim, 0xFFFF);
pwmGPIOConfig(timerHardware[port].gpio, timerHardware[port].pin, Mode_IPD);
pwmICConfig(timerHardware[port].tim, timerHardware[port].channel, TIM_ICPolarity_Rising);
TIM_Cmd(timerHardware[port].tim, ENABLE);
timerNVICConfig(timerHardware[port].irq);
const timerHardware_t *timerHardwarePtr = &(timerHardware[port]);
p->channel = channel;
configureTimerCaptureCompareInterrupt(&(timerHardware[port]), port, callback);
pwmGPIOConfig(timerHardwarePtr->gpio, timerHardwarePtr->pin, Mode_IPD);
pwmICConfig(timerHardwarePtr->tim, timerHardwarePtr->channel, TIM_ICPolarity_Rising);
timerInConfig(timerHardwarePtr, 0xFFFF, PWM_TIMER_MHZ);
configureTimerCaptureCompareInterrupt(timerHardwarePtr, port, callback);
return p;
}
static void ppmCallback(uint8_t port, uint16_t capture)
{
uint16_t diff;
static uint16_t now;
{
uint16_t diff;
static uint16_t now;
static uint16_t last = 0;
static uint8_t chan = 0;
static uint8_t GoodPulses;
@ -317,9 +307,9 @@ bool pwmInit(drv_pwm_config_t *init)
setup = hardwareMaps[i];
for (i = 0; i < MAX_PORTS; i++) {
uint8_t port = setup[i] & 0x0F;
uint8_t mask = setup[i] & 0xF0;
uint8_t port = setup[i] & 0x0F;
uint8_t mask = setup[i] & 0xF0;
if (setup[i] == 0xFF) // terminator
break;
@ -328,14 +318,20 @@ bool pwmInit(drv_pwm_config_t *init)
if (port == PWM2)
continue;
#endif
// skip UART ports for GPS
if (init->useUART && (port == PWM3 || port == PWM4))
continue;
// skip ADC for powerMeter if configured
if (init->adcChannel && (init->adcChannel == port))
continue;
// skip UART ports for GPS
if (init->useUART && (port == PWM3 || port == PWM4))
continue;
#ifdef SOFTSERIAL_19200_LOOPBACK
// skip softSerial ports
if ((port == PWM5 || port == PWM6))
continue;
#endif
// skip ADC for powerMeter if configured
if (init->adcChannel && (init->adcChannel == port))
continue;
// hacks to allow current functionality
if (mask & (TYPE_IP | TYPE_IW) && !init->enableInput)