mirror of
https://github.com/betaflight/betaflight.git
synced 2025-07-13 03:20:00 +03:00
Merge branch 'softserial'
This commit is contained in:
commit
1fdc6f118f
10 changed files with 482 additions and 482 deletions
200
src/drv_pwm.c
200
src/drv_pwm.c
|
@ -1,14 +1,14 @@
|
||||||
#include "board.h"
|
#include "board.h"
|
||||||
|
|
||||||
#define PULSE_1MS (1000) // 1ms pulse width
|
#define PULSE_1MS (1000) // 1ms pulse width
|
||||||
|
|
||||||
/*
|
/*
|
||||||
Configuration maps:
|
Configuration maps:
|
||||||
|
|
||||||
1) multirotor PPM input
|
1) multirotor PPM input
|
||||||
PWM1 used for PPM
|
PWM1 used for PPM
|
||||||
PWM5..8 used for motors
|
PWM5..8 used for motors
|
||||||
PWM9..10 used for servo or else motors
|
PWM9..10 used for servo or else motors
|
||||||
PWM11..14 used for motors
|
PWM11..14 used for motors
|
||||||
|
|
||||||
2) multirotor PPM input with more servos
|
2) multirotor PPM input with more servos
|
||||||
|
@ -28,19 +28,19 @@
|
||||||
PWM11.14 used for servos
|
PWM11.14 used for servos
|
||||||
|
|
||||||
4) airplane / flying wing with PPM
|
4) airplane / flying wing with PPM
|
||||||
PWM1 used for PPM
|
PWM1 used for PPM
|
||||||
PWM5..8 used for servos
|
PWM5..8 used for servos
|
||||||
PWM9 used for motor throttle +PWM10 for 2nd motor
|
PWM9 used for motor throttle +PWM10 for 2nd motor
|
||||||
PWM11.14 used for servos
|
PWM11.14 used for servos
|
||||||
*/
|
*/
|
||||||
|
|
||||||
typedef struct {
|
typedef struct {
|
||||||
volatile uint16_t *ccr;
|
volatile uint16_t *ccr;
|
||||||
uint16_t period;
|
uint16_t period;
|
||||||
|
|
||||||
// for input only
|
// for input only
|
||||||
uint8_t channel;
|
uint8_t channel;
|
||||||
uint8_t state;
|
uint8_t state;
|
||||||
uint16_t rise;
|
uint16_t rise;
|
||||||
uint16_t fall;
|
uint16_t fall;
|
||||||
uint16_t capture;
|
uint16_t capture;
|
||||||
|
@ -134,17 +134,17 @@ static const uint8_t * const hardwareMaps[] = {
|
||||||
multiPWM,
|
multiPWM,
|
||||||
multiPPM,
|
multiPPM,
|
||||||
airPWM,
|
airPWM,
|
||||||
airPPM,
|
airPPM,
|
||||||
};
|
};
|
||||||
|
|
||||||
#define PWM_TIMER_MHZ 1
|
#define PWM_TIMER_MHZ 1
|
||||||
|
|
||||||
static void pwmOCConfig(TIM_TypeDef *tim, uint8_t channel, uint16_t value)
|
static void pwmOCConfig(TIM_TypeDef *tim, uint8_t channel, uint16_t value)
|
||||||
{
|
{
|
||||||
TIM_OCInitTypeDef TIM_OCInitStructure;
|
TIM_OCInitTypeDef TIM_OCInitStructure;
|
||||||
|
|
||||||
TIM_OCStructInit(&TIM_OCInitStructure);
|
TIM_OCStructInit(&TIM_OCInitStructure);
|
||||||
TIM_OCInitStructure.TIM_OCMode = TIM_OCMode_PWM2;
|
TIM_OCInitStructure.TIM_OCMode = TIM_OCMode_PWM2;
|
||||||
TIM_OCInitStructure.TIM_OutputState = TIM_OutputState_Enable;
|
TIM_OCInitStructure.TIM_OutputState = TIM_OutputState_Enable;
|
||||||
TIM_OCInitStructure.TIM_OutputNState = TIM_OutputNState_Disable;
|
TIM_OCInitStructure.TIM_OutputNState = TIM_OutputNState_Disable;
|
||||||
TIM_OCInitStructure.TIM_Pulse = value;
|
TIM_OCInitStructure.TIM_Pulse = value;
|
||||||
|
@ -168,13 +168,13 @@ static void pwmOCConfig(TIM_TypeDef *tim, uint8_t channel, uint16_t value)
|
||||||
TIM_OC4Init(tim, &TIM_OCInitStructure);
|
TIM_OC4Init(tim, &TIM_OCInitStructure);
|
||||||
TIM_OC4PreloadConfig(tim, TIM_OCPreload_Enable);
|
TIM_OC4PreloadConfig(tim, TIM_OCPreload_Enable);
|
||||||
break;
|
break;
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
void pwmICConfig(TIM_TypeDef *tim, uint8_t channel, uint16_t polarity)
|
void pwmICConfig(TIM_TypeDef *tim, uint8_t channel, uint16_t polarity)
|
||||||
{
|
{
|
||||||
TIM_ICInitTypeDef TIM_ICInitStructure;
|
TIM_ICInitTypeDef TIM_ICInitStructure;
|
||||||
|
|
||||||
TIM_ICStructInit(&TIM_ICInitStructure);
|
TIM_ICStructInit(&TIM_ICInitStructure);
|
||||||
TIM_ICInitStructure.TIM_Channel = channel;
|
TIM_ICInitStructure.TIM_Channel = channel;
|
||||||
TIM_ICInitStructure.TIM_ICPolarity = polarity;
|
TIM_ICInitStructure.TIM_ICPolarity = polarity;
|
||||||
|
@ -195,13 +195,13 @@ static void pwmGPIOConfig(GPIO_TypeDef *gpio, uint32_t pin, GPIO_Mode mode)
|
||||||
gpioInit(gpio, &cfg);
|
gpioInit(gpio, &cfg);
|
||||||
}
|
}
|
||||||
|
|
||||||
static pwmPortData_t *pwmOutConfig(uint8_t port, uint16_t period, uint16_t value)
|
static pwmPortData_t *pwmOutConfig(uint8_t port, uint16_t period, uint16_t value)
|
||||||
{
|
{
|
||||||
pwmPortData_t *p = &pwmPorts[port];
|
pwmPortData_t *p = &pwmPorts[port];
|
||||||
configTimeBase(timerHardware[port].tim, period, PWM_TIMER_MHZ);
|
configTimeBase(timerHardware[port].tim, period, PWM_TIMER_MHZ);
|
||||||
pwmGPIOConfig(timerHardware[port].gpio, timerHardware[port].pin, Mode_AF_PP);
|
pwmGPIOConfig(timerHardware[port].gpio, timerHardware[port].pin, Mode_AF_PP);
|
||||||
pwmOCConfig(timerHardware[port].tim, timerHardware[port].channel, value);
|
pwmOCConfig(timerHardware[port].tim, timerHardware[port].channel, value);
|
||||||
// Needed only on TIM1
|
// Needed only on TIM1
|
||||||
if (timerHardware[port].outputEnable)
|
if (timerHardware[port].outputEnable)
|
||||||
TIM_CtrlPWMOutputs(timerHardware[port].tim, ENABLE);
|
TIM_CtrlPWMOutputs(timerHardware[port].tim, ENABLE);
|
||||||
TIM_Cmd(timerHardware[port].tim, ENABLE);
|
TIM_Cmd(timerHardware[port].tim, ENABLE);
|
||||||
|
@ -217,32 +217,32 @@ static pwmPortData_t *pwmOutConfig(uint8_t port, uint16_t period, uint16_t value
|
||||||
p->ccr = &timerHardware[port].tim->CCR3;
|
p->ccr = &timerHardware[port].tim->CCR3;
|
||||||
break;
|
break;
|
||||||
case TIM_Channel_4:
|
case TIM_Channel_4:
|
||||||
p->ccr = &timerHardware[port].tim->CCR4;
|
p->ccr = &timerHardware[port].tim->CCR4;
|
||||||
break;
|
break;
|
||||||
}
|
}
|
||||||
return p;
|
return p;
|
||||||
}
|
}
|
||||||
|
|
||||||
static pwmPortData_t *pwmInConfig(uint8_t port, timerCCCallbackPtr callback, uint8_t channel)
|
static pwmPortData_t *pwmInConfig(uint8_t port, timerCCCallbackPtr callback, uint8_t channel)
|
||||||
{
|
{
|
||||||
pwmPortData_t *p = &pwmPorts[port];
|
pwmPortData_t *p = &pwmPorts[port];
|
||||||
const timerHardware_t *timerHardwarePtr = &(timerHardware[port]);
|
const timerHardware_t *timerHardwarePtr = &(timerHardware[port]);
|
||||||
|
|
||||||
p->channel = channel;
|
p->channel = channel;
|
||||||
|
|
||||||
pwmGPIOConfig(timerHardwarePtr->gpio, timerHardwarePtr->pin, Mode_IPD);
|
pwmGPIOConfig(timerHardwarePtr->gpio, timerHardwarePtr->pin, Mode_IPD);
|
||||||
pwmICConfig(timerHardwarePtr->tim, timerHardwarePtr->channel, TIM_ICPolarity_Rising);
|
pwmICConfig(timerHardwarePtr->tim, timerHardwarePtr->channel, TIM_ICPolarity_Rising);
|
||||||
|
|
||||||
timerInConfig(timerHardwarePtr, 0xFFFF, PWM_TIMER_MHZ);
|
timerInConfig(timerHardwarePtr, 0xFFFF, PWM_TIMER_MHZ);
|
||||||
configureTimerCaptureCompareInterrupt(timerHardwarePtr, port, callback);
|
configureTimerCaptureCompareInterrupt(timerHardwarePtr, port, callback);
|
||||||
|
|
||||||
return p;
|
return p;
|
||||||
}
|
}
|
||||||
|
|
||||||
static void ppmCallback(uint8_t port, uint16_t capture)
|
static void ppmCallback(uint8_t port, uint16_t capture)
|
||||||
{
|
{
|
||||||
uint16_t diff;
|
uint16_t diff;
|
||||||
static uint16_t now;
|
static uint16_t now;
|
||||||
static uint16_t last = 0;
|
static uint16_t last = 0;
|
||||||
static uint8_t chan = 0;
|
static uint8_t chan = 0;
|
||||||
static uint8_t GoodPulses;
|
static uint8_t GoodPulses;
|
||||||
|
@ -307,31 +307,31 @@ bool pwmInit(drv_pwm_config_t *init)
|
||||||
setup = hardwareMaps[i];
|
setup = hardwareMaps[i];
|
||||||
|
|
||||||
for (i = 0; i < MAX_PORTS; i++) {
|
for (i = 0; i < MAX_PORTS; i++) {
|
||||||
uint8_t port = setup[i] & 0x0F;
|
uint8_t port = setup[i] & 0x0F;
|
||||||
uint8_t mask = setup[i] & 0xF0;
|
uint8_t mask = setup[i] & 0xF0;
|
||||||
|
|
||||||
if (setup[i] == 0xFF) // terminator
|
if (setup[i] == 0xFF) // terminator
|
||||||
break;
|
break;
|
||||||
|
|
||||||
#ifdef OLIMEXINO_UNCUT_LED2_E_JUMPER
|
#ifdef OLIMEXINO_UNCUT_LED2_E_JUMPER
|
||||||
// PWM2 is connected to LED2 on the board and cannot be connected unless you cut LED2_E
|
// PWM2 is connected to LED2 on the board and cannot be connected unless you cut LED2_E
|
||||||
if (port == PWM2)
|
if (port == PWM2)
|
||||||
continue;
|
continue;
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
// skip UART ports for GPS
|
// skip UART ports for GPS
|
||||||
if (init->useUART && (port == PWM3 || port == PWM4))
|
if (init->useUART && (port == PWM3 || port == PWM4))
|
||||||
continue;
|
continue;
|
||||||
|
|
||||||
#ifdef SOFTSERIAL_19200_LOOPBACK
|
#ifdef SOFTSERIAL_19200_LOOPBACK
|
||||||
// skip softSerial ports
|
// skip softSerial ports
|
||||||
if ((port == PWM5 || port == PWM6))
|
if ((port == PWM5 || port == PWM6))
|
||||||
continue;
|
continue;
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
// skip ADC for powerMeter if configured
|
// skip ADC for powerMeter if configured
|
||||||
if (init->adcChannel && (init->adcChannel == port))
|
if (init->adcChannel && (init->adcChannel == port))
|
||||||
continue;
|
continue;
|
||||||
|
|
||||||
// hacks to allow current functionality
|
// hacks to allow current functionality
|
||||||
if (mask & (TYPE_IP | TYPE_IW) && !init->enableInput)
|
if (mask & (TYPE_IP | TYPE_IW) && !init->enableInput)
|
||||||
|
|
|
@ -30,17 +30,17 @@ enum {
|
||||||
PWM9,
|
PWM9,
|
||||||
PWM10,
|
PWM10,
|
||||||
PWM11,
|
PWM11,
|
||||||
PWM12,
|
PWM12,
|
||||||
PWM13,
|
PWM13,
|
||||||
PWM14,
|
PWM14,
|
||||||
MAX_PORTS
|
MAX_PORTS
|
||||||
};
|
};
|
||||||
|
|
||||||
void pwmICConfig(TIM_TypeDef *tim, uint8_t channel, uint16_t polarity);
|
void pwmICConfig(TIM_TypeDef *tim, uint8_t channel, uint16_t polarity);
|
||||||
|
|
||||||
bool pwmInit(drv_pwm_config_t *init); // returns whether driver is asking to calibrate throttle or not
|
bool pwmInit(drv_pwm_config_t *init); // returns whether driver is asking to calibrate throttle or not
|
||||||
void pwmWriteMotor(uint8_t index, uint16_t value);
|
void pwmWriteMotor(uint8_t index, uint16_t value);
|
||||||
void pwmWriteServo(uint8_t index, uint16_t value);
|
void pwmWriteServo(uint8_t index, uint16_t value);
|
||||||
uint16_t pwmRead(uint8_t channel);
|
uint16_t pwmRead(uint8_t channel);
|
||||||
|
|
||||||
// void pwmWrite(uint8_t channel, uint16_t value);
|
// void pwmWrite(uint8_t channel, uint16_t value);
|
||||||
|
|
|
@ -1,203 +1,203 @@
|
||||||
#include "board.h"
|
#include "board.h"
|
||||||
|
|
||||||
enum serialBitStatus {
|
enum serialBitStatus {
|
||||||
WAITING_FOR_START_BIT = -1, BIT_0, BIT_1, BIT_2, BIT_3, BIT_4, BIT_5, BIT_6, BIT_7, WAITING_FOR_STOP_BIT
|
WAITING_FOR_START_BIT = -1, BIT_0, BIT_1, BIT_2, BIT_3, BIT_4, BIT_5, BIT_6, BIT_7, WAITING_FOR_STOP_BIT
|
||||||
};
|
};
|
||||||
|
|
||||||
#define MAX_SOFTSERIAL_PORTS 2
|
#define MAX_SOFTSERIAL_PORTS 2
|
||||||
softSerial_t softSerialPorts[MAX_SOFTSERIAL_PORTS];
|
softSerial_t softSerialPorts[MAX_SOFTSERIAL_PORTS];
|
||||||
|
|
||||||
softSerial_t* lookupSoftSerial(uint8_t reference)
|
softSerial_t* lookupSoftSerial(uint8_t reference)
|
||||||
{
|
{
|
||||||
assert_param(reference >= 0 && reference <= MAX_SOFTSERIAL_PORTS);
|
assert_param(reference >= 0 && reference <= MAX_SOFTSERIAL_PORTS);
|
||||||
|
|
||||||
return &(softSerialPorts[reference]);
|
return &(softSerialPorts[reference]);
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
||||||
void stopSerialTimer(softSerial_t *softSerial)
|
void stopSerialTimer(softSerial_t *softSerial)
|
||||||
{
|
{
|
||||||
TIM_Cmd(softSerial->timerHardware->tim, DISABLE);
|
TIM_Cmd(softSerial->timerHardware->tim, DISABLE);
|
||||||
TIM_SetCounter(softSerial->timerHardware->tim, 0);
|
TIM_SetCounter(softSerial->timerHardware->tim, 0);
|
||||||
}
|
}
|
||||||
|
|
||||||
void startSerialTimer(softSerial_t *softSerial)
|
void startSerialTimer(softSerial_t *softSerial)
|
||||||
{
|
{
|
||||||
TIM_SetCounter(softSerial->timerHardware->tim, 0);
|
TIM_SetCounter(softSerial->timerHardware->tim, 0);
|
||||||
TIM_Cmd(softSerial->timerHardware->tim, ENABLE);
|
TIM_Cmd(softSerial->timerHardware->tim, ENABLE);
|
||||||
}
|
}
|
||||||
|
|
||||||
static void waitForFirstBit(softSerial_t *softSerial)
|
static void waitForFirstBit(softSerial_t *softSerial)
|
||||||
{
|
{
|
||||||
softSerial->state = BIT_0;
|
softSerial->state = BIT_0;
|
||||||
startSerialTimer(softSerial);
|
startSerialTimer(softSerial);
|
||||||
}
|
}
|
||||||
|
|
||||||
static void onSerialPinChange(uint8_t reference, uint16_t capture)
|
static void onSerialPinChange(uint8_t reference, uint16_t capture)
|
||||||
{
|
{
|
||||||
softSerial_t *softSerial = lookupSoftSerial(reference);
|
softSerial_t *softSerial = lookupSoftSerial(reference);
|
||||||
if (softSerial->state == WAITING_FOR_START_BIT) {
|
if (softSerial->state == WAITING_FOR_START_BIT) {
|
||||||
waitForFirstBit(softSerial);
|
waitForFirstBit(softSerial);
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
uint8_t readSerialSignal(softSerial_t *softSerial)
|
uint8_t readSerialSignal(softSerial_t *softSerial)
|
||||||
{
|
{
|
||||||
return GPIO_ReadInputDataBit(softSerial->timerHardware->gpio, softSerial->timerHardware->pin);
|
return GPIO_ReadInputDataBit(softSerial->timerHardware->gpio, softSerial->timerHardware->pin);
|
||||||
}
|
}
|
||||||
|
|
||||||
void mergeSignalWithCurrentByte(softSerial_t *softSerial, uint8_t serialSignal)
|
void mergeSignalWithCurrentByte(softSerial_t *softSerial, uint8_t serialSignal)
|
||||||
{
|
{
|
||||||
softSerial->rxBuffer[softSerial->port.rxBufferTail] |= (serialSignal << softSerial->state);
|
softSerial->rxBuffer[softSerial->port.rxBufferTail] |= (serialSignal << softSerial->state);
|
||||||
}
|
}
|
||||||
|
|
||||||
inline void initialiseCurrentByteWithFirstSignal(softSerial_t *softSerial, uint8_t serialSignal)
|
inline void initialiseCurrentByteWithFirstSignal(softSerial_t *softSerial, uint8_t serialSignal)
|
||||||
{
|
{
|
||||||
softSerial->rxBuffer[softSerial->port.rxBufferTail] = serialSignal;
|
softSerial->rxBuffer[softSerial->port.rxBufferTail] = serialSignal;
|
||||||
}
|
}
|
||||||
|
|
||||||
inline void prepareForNextSignal(softSerial_t *softSerial) {
|
inline void prepareForNextSignal(softSerial_t *softSerial) {
|
||||||
softSerial->state++;
|
softSerial->state++;
|
||||||
}
|
}
|
||||||
|
|
||||||
void updateBufferIndex(softSerial_t *softSerial)
|
void updateBufferIndex(softSerial_t *softSerial)
|
||||||
{
|
{
|
||||||
if (softSerial->port.rxBufferTail >= softSerial->port.rxBufferSize - 1)
|
if (softSerial->port.rxBufferTail >= softSerial->port.rxBufferSize - 1)
|
||||||
{
|
{
|
||||||
softSerial->port.rxBufferTail = 0; //cycling the buffer
|
softSerial->port.rxBufferTail = 0; //cycling the buffer
|
||||||
} else {
|
} else {
|
||||||
softSerial->port.rxBufferTail++;
|
softSerial->port.rxBufferTail++;
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
void prepareForNextByte(softSerial_t *softSerial)
|
void prepareForNextByte(softSerial_t *softSerial)
|
||||||
{
|
{
|
||||||
stopSerialTimer(softSerial);
|
stopSerialTimer(softSerial);
|
||||||
softSerial->state = WAITING_FOR_START_BIT;
|
softSerial->state = WAITING_FOR_START_BIT;
|
||||||
updateBufferIndex(softSerial);
|
updateBufferIndex(softSerial);
|
||||||
}
|
}
|
||||||
|
|
||||||
void onSerialTimer(uint8_t portIndex, uint16_t capture)
|
void onSerialTimer(uint8_t portIndex, uint16_t capture)
|
||||||
{
|
{
|
||||||
softSerial_t *softSerial = &(softSerialPorts[portIndex]);
|
softSerial_t *softSerial = &(softSerialPorts[portIndex]);
|
||||||
|
|
||||||
uint8_t serialSignal = readSerialSignal(softSerial);
|
uint8_t serialSignal = readSerialSignal(softSerial);
|
||||||
|
|
||||||
switch (softSerial->state) {
|
switch (softSerial->state) {
|
||||||
case BIT_0:
|
case BIT_0:
|
||||||
initialiseCurrentByteWithFirstSignal(softSerial, serialSignal);
|
initialiseCurrentByteWithFirstSignal(softSerial, serialSignal);
|
||||||
prepareForNextSignal(softSerial);
|
prepareForNextSignal(softSerial);
|
||||||
break;
|
break;
|
||||||
|
|
||||||
case BIT_1:
|
case BIT_1:
|
||||||
case BIT_2:
|
case BIT_2:
|
||||||
case BIT_3:
|
case BIT_3:
|
||||||
case BIT_4:
|
case BIT_4:
|
||||||
case BIT_5:
|
case BIT_5:
|
||||||
case BIT_6:
|
case BIT_6:
|
||||||
case BIT_7:
|
case BIT_7:
|
||||||
mergeSignalWithCurrentByte(softSerial, serialSignal);
|
mergeSignalWithCurrentByte(softSerial, serialSignal);
|
||||||
|
|
||||||
prepareForNextSignal(softSerial);
|
prepareForNextSignal(softSerial);
|
||||||
break;
|
break;
|
||||||
|
|
||||||
case WAITING_FOR_STOP_BIT:
|
case WAITING_FOR_STOP_BIT:
|
||||||
prepareForNextByte(softSerial);
|
prepareForNextByte(softSerial);
|
||||||
break;
|
break;
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
#define SOFT_SERIAL_TIMER_MHZ 1
|
#define SOFT_SERIAL_TIMER_MHZ 1
|
||||||
#define SOFT_SERIAL_1_TIMER_HARDWARE 4
|
#define SOFT_SERIAL_1_TIMER_HARDWARE 4
|
||||||
|
|
||||||
static void softSerialGPIOConfig(GPIO_TypeDef *gpio, uint32_t pin, GPIO_Mode mode)
|
static void softSerialGPIOConfig(GPIO_TypeDef *gpio, uint32_t pin, GPIO_Mode mode)
|
||||||
{
|
{
|
||||||
gpio_config_t cfg;
|
gpio_config_t cfg;
|
||||||
|
|
||||||
cfg.pin = pin;
|
cfg.pin = pin;
|
||||||
cfg.mode = mode;
|
cfg.mode = mode;
|
||||||
cfg.speed = Speed_2MHz;
|
cfg.speed = Speed_2MHz;
|
||||||
gpioInit(gpio, &cfg);
|
gpioInit(gpio, &cfg);
|
||||||
}
|
}
|
||||||
|
|
||||||
void serialInputPortConfig(const timerHardware_t *timerHardwarePtr, uint16_t baud, uint8_t reference, timerCCCallbackPtr callback)
|
void serialInputPortConfig(const timerHardware_t *timerHardwarePtr, uint16_t baud, uint8_t reference, timerCCCallbackPtr callback)
|
||||||
{
|
{
|
||||||
softSerialGPIOConfig(timerHardwarePtr->gpio, timerHardwarePtr->pin, Mode_IPU);
|
softSerialGPIOConfig(timerHardwarePtr->gpio, timerHardwarePtr->pin, Mode_IPU);
|
||||||
|
|
||||||
pwmICConfig(timerHardwarePtr->tim, timerHardwarePtr->channel, TIM_ICPolarity_Falling);
|
pwmICConfig(timerHardwarePtr->tim, timerHardwarePtr->channel, TIM_ICPolarity_Falling);
|
||||||
|
|
||||||
int oneBitPeriod = (SOFT_SERIAL_TIMER_MHZ * 1000000) / baud;
|
int oneBitPeriod = (SOFT_SERIAL_TIMER_MHZ * 1000000) / baud;
|
||||||
|
|
||||||
timerInConfig(timerHardwarePtr, oneBitPeriod, SOFT_SERIAL_TIMER_MHZ);
|
timerInConfig(timerHardwarePtr, oneBitPeriod, SOFT_SERIAL_TIMER_MHZ);
|
||||||
configureTimerCaptureCompareInterrupt(timerHardwarePtr, reference, callback);
|
configureTimerCaptureCompareInterrupt(timerHardwarePtr, reference, callback);
|
||||||
}
|
}
|
||||||
|
|
||||||
void setupSoftSerial1(uint32_t baud)
|
void setupSoftSerial1(uint32_t baud)
|
||||||
{
|
{
|
||||||
int portIndex = 0;
|
int portIndex = 0;
|
||||||
softSerial_t *softSerial = &(softSerialPorts[portIndex]);
|
softSerial_t *softSerial = &(softSerialPorts[portIndex]);
|
||||||
|
|
||||||
softSerial->timerHardware = &(timerHardware[SOFT_SERIAL_1_TIMER_HARDWARE]);
|
softSerial->timerHardware = &(timerHardware[SOFT_SERIAL_1_TIMER_HARDWARE]);
|
||||||
softSerial->timerIndex = SOFT_SERIAL_1_TIMER_HARDWARE;
|
softSerial->timerIndex = SOFT_SERIAL_1_TIMER_HARDWARE;
|
||||||
softSerial->state = WAITING_FOR_START_BIT;
|
softSerial->state = WAITING_FOR_START_BIT;
|
||||||
|
|
||||||
softSerial->port.rxBufferSize = SOFT_SERIAL_BUFFER_SIZE;
|
softSerial->port.rxBufferSize = SOFT_SERIAL_BUFFER_SIZE;
|
||||||
softSerial->port.rxBuffer = softSerial->rxBuffer;
|
softSerial->port.rxBuffer = softSerial->rxBuffer;
|
||||||
softSerial->port.rxBufferTail = 0;
|
softSerial->port.rxBufferTail = 0;
|
||||||
softSerial->port.rxBufferHead = 0;
|
softSerial->port.rxBufferHead = 0;
|
||||||
|
|
||||||
softSerial->port.txBuffer = 0;
|
softSerial->port.txBuffer = 0;
|
||||||
softSerial->port.txBufferSize = 0;
|
softSerial->port.txBufferSize = 0;
|
||||||
softSerial->port.txBufferTail = 0;
|
softSerial->port.txBufferTail = 0;
|
||||||
softSerial->port.txBufferHead = 0;
|
softSerial->port.txBufferHead = 0;
|
||||||
|
|
||||||
softSerial->port.baudRate = baud;
|
softSerial->port.baudRate = baud;
|
||||||
softSerial->port.mode = MODE_RX;
|
softSerial->port.mode = MODE_RX;
|
||||||
|
|
||||||
// FIXME this uart specific initialisation doesn't belong really here
|
// FIXME this uart specific initialisation doesn't belong really here
|
||||||
softSerial->port.txDMAChannel = 0;
|
softSerial->port.txDMAChannel = 0;
|
||||||
softSerial->port.txDMAChannel = 0;
|
softSerial->port.txDMAChannel = 0;
|
||||||
|
|
||||||
configureTimerChannelCallback(softSerial->timerHardware->tim, TIM_Channel_2, portIndex, onSerialTimer);
|
configureTimerChannelCallback(softSerial->timerHardware->tim, TIM_Channel_2, portIndex, onSerialTimer);
|
||||||
|
|
||||||
TIM_ITConfig(TIM3, TIM_IT_CC2, ENABLE);
|
TIM_ITConfig(TIM3, TIM_IT_CC2, ENABLE);
|
||||||
stopSerialTimer(softSerial);
|
stopSerialTimer(softSerial);
|
||||||
|
|
||||||
serialInputPortConfig(softSerial->timerHardware, baud, portIndex, onSerialPinChange);
|
serialInputPortConfig(softSerial->timerHardware, baud, portIndex, onSerialPinChange);
|
||||||
}
|
}
|
||||||
|
|
||||||
bool serialAvailable(softSerial_t *softSerial)
|
bool serialAvailable(softSerial_t *softSerial)
|
||||||
{
|
{
|
||||||
if (softSerial->port.rxBufferTail == softSerial->port.rxBufferHead) {
|
if (softSerial->port.rxBufferTail == softSerial->port.rxBufferHead) {
|
||||||
return 0;
|
return 0;
|
||||||
}
|
}
|
||||||
|
|
||||||
int availableBytes;
|
int availableBytes;
|
||||||
if (softSerial->port.rxBufferTail > softSerial->port.rxBufferHead) {
|
if (softSerial->port.rxBufferTail > softSerial->port.rxBufferHead) {
|
||||||
availableBytes = softSerial->port.rxBufferTail - softSerial->port.rxBufferHead;
|
availableBytes = softSerial->port.rxBufferTail - softSerial->port.rxBufferHead;
|
||||||
} else {
|
} else {
|
||||||
availableBytes = softSerial->port.rxBufferTail + softSerial->port.rxBufferSize - softSerial->port.rxBufferHead;
|
availableBytes = softSerial->port.rxBufferTail + softSerial->port.rxBufferSize - softSerial->port.rxBufferHead;
|
||||||
}
|
}
|
||||||
return availableBytes;
|
return availableBytes;
|
||||||
}
|
}
|
||||||
|
|
||||||
static void moveHeadToNextByte(softSerial_t *softSerial)
|
static void moveHeadToNextByte(softSerial_t *softSerial)
|
||||||
{
|
{
|
||||||
if (softSerial->port.rxBufferHead < softSerial->port.rxBufferSize - 1) {
|
if (softSerial->port.rxBufferHead < softSerial->port.rxBufferSize - 1) {
|
||||||
softSerial->port.rxBufferHead++;
|
softSerial->port.rxBufferHead++;
|
||||||
} else {
|
} else {
|
||||||
softSerial->port.rxBufferHead = 0;
|
softSerial->port.rxBufferHead = 0;
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
uint8_t serialReadByte(softSerial_t *softSerial)
|
uint8_t serialReadByte(softSerial_t *softSerial)
|
||||||
{
|
{
|
||||||
if (serialAvailable(softSerial) == 0) {
|
if (serialAvailable(softSerial) == 0) {
|
||||||
return 0;
|
return 0;
|
||||||
}
|
}
|
||||||
|
|
||||||
char b = softSerial->port.rxBuffer[softSerial->port.rxBufferHead];
|
char b = softSerial->port.rxBuffer[softSerial->port.rxBufferHead];
|
||||||
|
|
||||||
moveHeadToNextByte(softSerial);
|
moveHeadToNextByte(softSerial);
|
||||||
return b;
|
return b;
|
||||||
}
|
}
|
||||||
|
|
|
@ -1,25 +1,25 @@
|
||||||
/*
|
/*
|
||||||
* drv_softserial.h
|
* drv_softserial.h
|
||||||
*
|
*
|
||||||
* Created on: 23 Aug 2013
|
* Created on: 23 Aug 2013
|
||||||
* Author: Hydra
|
* Author: Hydra
|
||||||
*/
|
*/
|
||||||
|
|
||||||
#pragma once
|
#pragma once
|
||||||
|
|
||||||
#define SOFT_SERIAL_BUFFER_SIZE 256
|
#define SOFT_SERIAL_BUFFER_SIZE 256
|
||||||
|
|
||||||
typedef struct softSerial_s {
|
typedef struct softSerial_s {
|
||||||
const timerHardware_t *timerHardware;
|
const timerHardware_t *timerHardware;
|
||||||
uint8_t timerIndex;
|
uint8_t timerIndex;
|
||||||
serialPort_t port;
|
serialPort_t port;
|
||||||
volatile int state;
|
volatile int state;
|
||||||
volatile uint8_t rxBuffer[SOFT_SERIAL_BUFFER_SIZE];
|
volatile uint8_t rxBuffer[SOFT_SERIAL_BUFFER_SIZE];
|
||||||
} softSerial_t;
|
} softSerial_t;
|
||||||
void setupSoftSerial1(uint32_t baud);
|
void setupSoftSerial1(uint32_t baud);
|
||||||
|
|
||||||
uint8_t serialReadByte(softSerial_t *softSerial);
|
uint8_t serialReadByte(softSerial_t *softSerial);
|
||||||
bool serialAvailable(softSerial_t *softSerial);
|
bool serialAvailable(softSerial_t *softSerial);
|
||||||
|
|
||||||
extern timerHardware_t* serialTimerHardware;
|
extern timerHardware_t* serialTimerHardware;
|
||||||
extern softSerial_t softSerialPorts[];
|
extern softSerial_t softSerialPorts[];
|
||||||
|
|
120
src/drv_timer.c
120
src/drv_timer.c
|
@ -72,8 +72,8 @@ static const uint8_t channels[CC_CHANNELS_PER_TIMER] = {
|
||||||
|
|
||||||
typedef struct timerConfig_s {
|
typedef struct timerConfig_s {
|
||||||
TIM_TypeDef *tim;
|
TIM_TypeDef *tim;
|
||||||
uint8_t channel;
|
uint8_t channel;
|
||||||
timerCCCallbackPtr *callback;
|
timerCCCallbackPtr *callback;
|
||||||
uint8_t reference;
|
uint8_t reference;
|
||||||
} timerConfig_t;
|
} timerConfig_t;
|
||||||
|
|
||||||
|
@ -95,22 +95,22 @@ static uint8_t lookupChannelIndex(const uint8_t channel)
|
||||||
channelIndex++;
|
channelIndex++;
|
||||||
}
|
}
|
||||||
return channelIndex;
|
return channelIndex;
|
||||||
}
|
}
|
||||||
|
|
||||||
void configureTimerChannelCallback(TIM_TypeDef *tim, uint8_t channel, uint8_t reference, timerCCCallbackPtr *callback)
|
void configureTimerChannelCallback(TIM_TypeDef *tim, uint8_t channel, uint8_t reference, timerCCCallbackPtr *callback)
|
||||||
{
|
{
|
||||||
assert_param(IS_TIM_CHANNEL(channel));
|
assert_param(IS_TIM_CHANNEL(channel));
|
||||||
|
|
||||||
uint8_t timerConfigIndex = (lookupTimerIndex(tim) * MAX_TIMERS) + lookupChannelIndex(channel);
|
uint8_t timerConfigIndex = (lookupTimerIndex(tim) * MAX_TIMERS) + lookupChannelIndex(channel);
|
||||||
|
|
||||||
if (timerConfigIndex >= MAX_TIMERS * CC_CHANNELS_PER_TIMER) {
|
if (timerConfigIndex >= MAX_TIMERS * CC_CHANNELS_PER_TIMER) {
|
||||||
return;
|
return;
|
||||||
}
|
}
|
||||||
|
|
||||||
timerConfig[timerConfigIndex].callback = callback;
|
timerConfig[timerConfigIndex].callback = callback;
|
||||||
timerConfig[timerConfigIndex].channel = channel;
|
timerConfig[timerConfigIndex].channel = channel;
|
||||||
timerConfig[timerConfigIndex].reference = reference;
|
timerConfig[timerConfigIndex].reference = reference;
|
||||||
}
|
}
|
||||||
|
|
||||||
void configureTimerInputCaptureCompareChannel(TIM_TypeDef *tim, const uint8_t channel)
|
void configureTimerInputCaptureCompareChannel(TIM_TypeDef *tim, const uint8_t channel)
|
||||||
{
|
{
|
||||||
|
@ -129,47 +129,47 @@ void configureTimerInputCaptureCompareChannel(TIM_TypeDef *tim, const uint8_t ch
|
||||||
break;
|
break;
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
void configureTimerCaptureCompareInterrupt(const timerHardware_t *timerHardwarePtr, uint8_t reference, timerCCCallbackPtr *callback)
|
void configureTimerCaptureCompareInterrupt(const timerHardware_t *timerHardwarePtr, uint8_t reference, timerCCCallbackPtr *callback)
|
||||||
{
|
{
|
||||||
configureTimerChannelCallback(timerHardwarePtr->tim, timerHardwarePtr->channel, reference, callback);
|
configureTimerChannelCallback(timerHardwarePtr->tim, timerHardwarePtr->channel, reference, callback);
|
||||||
configureTimerInputCaptureCompareChannel(timerHardwarePtr->tim, timerHardwarePtr->channel);
|
configureTimerInputCaptureCompareChannel(timerHardwarePtr->tim, timerHardwarePtr->channel);
|
||||||
|
}
|
||||||
|
|
||||||
|
void timerNVICConfig(uint8_t irq)
|
||||||
|
{
|
||||||
|
NVIC_InitTypeDef NVIC_InitStructure;
|
||||||
|
|
||||||
|
NVIC_InitStructure.NVIC_IRQChannel = irq;
|
||||||
|
NVIC_InitStructure.NVIC_IRQChannelPreemptionPriority = 0;
|
||||||
|
NVIC_InitStructure.NVIC_IRQChannelSubPriority = 1;
|
||||||
|
NVIC_InitStructure.NVIC_IRQChannelCmd = ENABLE;
|
||||||
|
NVIC_Init(&NVIC_InitStructure);
|
||||||
}
|
}
|
||||||
|
|
||||||
void timerNVICConfig(uint8_t irq)
|
void configTimeBase(TIM_TypeDef *tim, uint32_t period, uint8_t mhz)
|
||||||
{
|
{
|
||||||
NVIC_InitTypeDef NVIC_InitStructure;
|
TIM_TimeBaseInitTypeDef TIM_TimeBaseStructure;
|
||||||
|
|
||||||
NVIC_InitStructure.NVIC_IRQChannel = irq;
|
TIM_TimeBaseStructInit(&TIM_TimeBaseStructure);
|
||||||
NVIC_InitStructure.NVIC_IRQChannelPreemptionPriority = 0;
|
TIM_TimeBaseStructure.TIM_Period = period - 1;
|
||||||
NVIC_InitStructure.NVIC_IRQChannelSubPriority = 1;
|
TIM_TimeBaseStructure.TIM_Prescaler = (SystemCoreClock / ((uint32_t)mhz * 1000000)) - 1;
|
||||||
NVIC_InitStructure.NVIC_IRQChannelCmd = ENABLE;
|
TIM_TimeBaseStructure.TIM_ClockDivision = 0;
|
||||||
NVIC_Init(&NVIC_InitStructure);
|
TIM_TimeBaseStructure.TIM_CounterMode = TIM_CounterMode_Up;
|
||||||
}
|
TIM_TimeBaseInit(tim, &TIM_TimeBaseStructure);
|
||||||
|
}
|
||||||
void configTimeBase(TIM_TypeDef *tim, uint32_t period, uint8_t mhz)
|
|
||||||
{
|
void timerInConfig(const timerHardware_t *timerHardwarePtr, uint32_t period, uint8_t mhz)
|
||||||
TIM_TimeBaseInitTypeDef TIM_TimeBaseStructure;
|
{
|
||||||
|
configTimeBase(timerHardwarePtr->tim, period, mhz);
|
||||||
TIM_TimeBaseStructInit(&TIM_TimeBaseStructure);
|
TIM_Cmd(timerHardwarePtr->tim, ENABLE);
|
||||||
TIM_TimeBaseStructure.TIM_Period = period - 1;
|
timerNVICConfig(timerHardwarePtr->irq);
|
||||||
TIM_TimeBaseStructure.TIM_Prescaler = (SystemCoreClock / ((uint32_t)mhz * 1000000)) - 1;
|
}
|
||||||
TIM_TimeBaseStructure.TIM_ClockDivision = 0;
|
|
||||||
TIM_TimeBaseStructure.TIM_CounterMode = TIM_CounterMode_Up;
|
|
||||||
TIM_TimeBaseInit(tim, &TIM_TimeBaseStructure);
|
timerConfig_t *findTimerConfig(TIM_TypeDef *tim, uint8_t channel)
|
||||||
}
|
{
|
||||||
|
uint8_t timerConfigIndex = (lookupTimerIndex(tim) * MAX_TIMERS) + lookupChannelIndex(channel);
|
||||||
void timerInConfig(const timerHardware_t *timerHardwarePtr, uint32_t period, uint8_t mhz)
|
|
||||||
{
|
|
||||||
configTimeBase(timerHardwarePtr->tim, period, mhz);
|
|
||||||
TIM_Cmd(timerHardwarePtr->tim, ENABLE);
|
|
||||||
timerNVICConfig(timerHardwarePtr->irq);
|
|
||||||
}
|
|
||||||
|
|
||||||
|
|
||||||
timerConfig_t *findTimerConfig(TIM_TypeDef *tim, uint8_t channel)
|
|
||||||
{
|
|
||||||
uint8_t timerConfigIndex = (lookupTimerIndex(tim) * MAX_TIMERS) + lookupChannelIndex(channel);
|
|
||||||
return &(timerConfig[timerConfigIndex]);
|
return &(timerConfig[timerConfigIndex]);
|
||||||
}
|
}
|
||||||
|
|
||||||
|
@ -198,8 +198,8 @@ static void timCCxHandler(TIM_TypeDef *tim)
|
||||||
|
|
||||||
timerConfig = findTimerConfig(tim, TIM_Channel_4);
|
timerConfig = findTimerConfig(tim, TIM_Channel_4);
|
||||||
capture = TIM_GetCapture4(tim);
|
capture = TIM_GetCapture4(tim);
|
||||||
} else {
|
} else {
|
||||||
return; // avoid uninitialised variable dereference
|
return; // avoid uninitialised variable dereference
|
||||||
}
|
}
|
||||||
|
|
||||||
if (!timerConfig->callback) {
|
if (!timerConfig->callback) {
|
||||||
|
|
|
@ -1,22 +1,22 @@
|
||||||
#pragma once
|
#pragma once
|
||||||
|
|
||||||
typedef void timerCCCallbackPtr(uint8_t port, uint16_t capture);
|
typedef void timerCCCallbackPtr(uint8_t port, uint16_t capture);
|
||||||
|
|
||||||
typedef struct {
|
typedef struct {
|
||||||
TIM_TypeDef *tim;
|
TIM_TypeDef *tim;
|
||||||
GPIO_TypeDef *gpio;
|
GPIO_TypeDef *gpio;
|
||||||
uint32_t pin;
|
uint32_t pin;
|
||||||
uint8_t channel;
|
uint8_t channel;
|
||||||
uint8_t irq;
|
uint8_t irq;
|
||||||
uint8_t outputEnable;
|
uint8_t outputEnable;
|
||||||
} timerHardware_t;
|
} timerHardware_t;
|
||||||
|
|
||||||
extern const timerHardware_t timerHardware[];
|
extern const timerHardware_t timerHardware[];
|
||||||
|
|
||||||
void configTimeBase(TIM_TypeDef *tim, uint32_t period, uint8_t mhz);
|
void configTimeBase(TIM_TypeDef *tim, uint32_t period, uint8_t mhz);
|
||||||
void timerInConfig(const timerHardware_t *timerHardwarePtr, uint32_t period, uint8_t mhz);
|
void timerInConfig(const timerHardware_t *timerHardwarePtr, uint32_t period, uint8_t mhz);
|
||||||
void timerNVICConfig(uint8_t irq);
|
void timerNVICConfig(uint8_t irq);
|
||||||
|
|
||||||
void configureTimerInputCaptureCompareChannel(TIM_TypeDef *tim, const uint8_t channel);
|
void configureTimerInputCaptureCompareChannel(TIM_TypeDef *tim, const uint8_t channel);
|
||||||
void configureTimerCaptureCompareInterrupt(const timerHardware_t *timerHardwarePtr, uint8_t reference, timerCCCallbackPtr *callback);
|
void configureTimerCaptureCompareInterrupt(const timerHardware_t *timerHardwarePtr, uint8_t reference, timerCCCallbackPtr *callback);
|
||||||
void configureTimerChannelCallback(TIM_TypeDef *tim, uint8_t channel, uint8_t reference, timerCCCallbackPtr *callback);
|
void configureTimerChannelCallback(TIM_TypeDef *tim, uint8_t channel, uint8_t reference, timerCCCallbackPtr *callback);
|
||||||
|
|
|
@ -238,20 +238,20 @@ void uartWrite(serialPort_t *s, uint8_t ch)
|
||||||
uartStartTxDMA(s);
|
uartStartTxDMA(s);
|
||||||
} else {
|
} else {
|
||||||
USART_ITConfig(s->USARTx, USART_IT_TXE, ENABLE);
|
USART_ITConfig(s->USARTx, USART_IT_TXE, ENABLE);
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
void uartPrint(serialPort_t *s, const char *str)
|
void uartPrint(serialPort_t *s, const char *str)
|
||||||
{
|
{
|
||||||
uint8_t ch;
|
uint8_t ch;
|
||||||
while ((ch = *(str++))) {
|
while ((ch = *(str++))) {
|
||||||
uartWrite(s, ch);
|
uartWrite(s, ch);
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
// Handlers
|
// Handlers
|
||||||
|
|
||||||
// USART1 Tx DMA Handler
|
// USART1 Tx DMA Handler
|
||||||
void DMA1_Channel4_IRQHandler(void)
|
void DMA1_Channel4_IRQHandler(void)
|
||||||
{
|
{
|
||||||
serialPort_t *s = &serialPort1;
|
serialPort_t *s = &serialPort1;
|
||||||
|
|
|
@ -12,40 +12,40 @@
|
||||||
typedef enum portmode_t {
|
typedef enum portmode_t {
|
||||||
MODE_RX = 1,
|
MODE_RX = 1,
|
||||||
MODE_TX = 2,
|
MODE_TX = 2,
|
||||||
MODE_RXTX = 3
|
MODE_RXTX = 3
|
||||||
} portmode_t;
|
} portmode_t;
|
||||||
|
|
||||||
// FIXME this is a uart_t really. Move the generic properties into a separate structure (serialPort_t) and update the code to use it
|
// FIXME this is a uart_t really. Move the generic properties into a separate structure (serialPort_t) and update the code to use it
|
||||||
typedef struct {
|
typedef struct {
|
||||||
portmode_t mode;
|
portmode_t mode;
|
||||||
uint32_t baudRate;
|
uint32_t baudRate;
|
||||||
|
|
||||||
uint32_t rxBufferSize;
|
uint32_t rxBufferSize;
|
||||||
uint32_t txBufferSize;
|
uint32_t txBufferSize;
|
||||||
volatile uint8_t *rxBuffer;
|
volatile uint8_t *rxBuffer;
|
||||||
volatile uint8_t *txBuffer;
|
volatile uint8_t *txBuffer;
|
||||||
uint32_t rxBufferHead;
|
uint32_t rxBufferHead;
|
||||||
uint32_t rxBufferTail;
|
uint32_t rxBufferTail;
|
||||||
uint32_t txBufferHead;
|
uint32_t txBufferHead;
|
||||||
uint32_t txBufferTail;
|
uint32_t txBufferTail;
|
||||||
|
|
||||||
// FIXME rename callback type so something more generic
|
// FIXME rename callback type so something more generic
|
||||||
uartReceiveCallbackPtr callback;
|
uartReceiveCallbackPtr callback;
|
||||||
|
|
||||||
// FIXME these are uart specific and do not belong in here
|
// FIXME these are uart specific and do not belong in here
|
||||||
DMA_Channel_TypeDef *rxDMAChannel;
|
DMA_Channel_TypeDef *rxDMAChannel;
|
||||||
DMA_Channel_TypeDef *txDMAChannel;
|
DMA_Channel_TypeDef *txDMAChannel;
|
||||||
|
|
||||||
uint32_t rxDMAIrq;
|
uint32_t rxDMAIrq;
|
||||||
uint32_t txDMAIrq;
|
uint32_t txDMAIrq;
|
||||||
|
|
||||||
uint32_t rxDMAPos;
|
uint32_t rxDMAPos;
|
||||||
bool txDMAEmpty;
|
bool txDMAEmpty;
|
||||||
|
|
||||||
USART_TypeDef *USARTx;
|
USART_TypeDef *USARTx;
|
||||||
} serialPort_t;
|
} serialPort_t;
|
||||||
|
|
||||||
serialPort_t *uartOpen(USART_TypeDef *USARTx, uartReceiveCallbackPtr callback, uint32_t baudRate, portmode_t mode);
|
serialPort_t *uartOpen(USART_TypeDef *USARTx, uartReceiveCallbackPtr callback, uint32_t baudRate, portmode_t mode);
|
||||||
void uartChangeBaud(serialPort_t *s, uint32_t baudRate);
|
void uartChangeBaud(serialPort_t *s, uint32_t baudRate);
|
||||||
bool isUartAvailable(serialPort_t *s);
|
bool isUartAvailable(serialPort_t *s);
|
||||||
bool isUartTransmitEmpty(serialPort_t *s);
|
bool isUartTransmitEmpty(serialPort_t *s);
|
||||||
|
|
|
@ -120,7 +120,7 @@ int main(void)
|
||||||
|
|
||||||
// Check battery type/voltage
|
// Check battery type/voltage
|
||||||
if (feature(FEATURE_VBAT))
|
if (feature(FEATURE_VBAT))
|
||||||
batteryInit();
|
batteryInit();
|
||||||
|
|
||||||
#ifdef SOFTSERIAL_19200_LOOPBACK
|
#ifdef SOFTSERIAL_19200_LOOPBACK
|
||||||
|
|
||||||
|
@ -130,7 +130,7 @@ int main(void)
|
||||||
#else
|
#else
|
||||||
serialInit(mcfg.serial_baudrate);
|
serialInit(mcfg.serial_baudrate);
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
previousTime = micros();
|
previousTime = micros();
|
||||||
if (mcfg.mixerConfiguration == MULTITYPE_GIMBAL)
|
if (mcfg.mixerConfiguration == MULTITYPE_GIMBAL)
|
||||||
calibratingA = 400;
|
calibratingA = 400;
|
||||||
|
|
|
@ -64,14 +64,14 @@ retry:
|
||||||
mpu6050Detect(&acc, &gyro, mcfg.gyro_lpf, &mcfg.mpu6050_scale); // yes, i'm rerunning it again. re-fill acc struct
|
mpu6050Detect(&acc, &gyro, mcfg.gyro_lpf, &mcfg.mpu6050_scale); // yes, i'm rerunning it again. re-fill acc struct
|
||||||
accHardware = ACC_MPU6050;
|
accHardware = ACC_MPU6050;
|
||||||
if (mcfg.acc_hardware == ACC_MPU6050)
|
if (mcfg.acc_hardware == ACC_MPU6050)
|
||||||
break;
|
break;
|
||||||
}
|
}
|
||||||
; // fallthrough
|
; // fallthrough
|
||||||
#ifndef OLIMEXINO
|
#ifndef OLIMEXINO
|
||||||
case 3: // MMA8452
|
case 3: // MMA8452
|
||||||
if (mma8452Detect(&acc)) {
|
if (mma8452Detect(&acc)) {
|
||||||
accHardware = ACC_MMA8452;
|
accHardware = ACC_MMA8452;
|
||||||
if (mcfg.acc_hardware == ACC_MMA8452)
|
if (mcfg.acc_hardware == ACC_MMA8452)
|
||||||
break;
|
break;
|
||||||
}
|
}
|
||||||
#endif
|
#endif
|
||||||
|
|
Loading…
Add table
Add a link
Reference in a new issue