Cleanup CC3D softserial - it only has enough pins/timers for one port.
PR #124 incorrectly re-used the same timer hardware for the second port which was bad.
This commit is contained in:
parent
b08f51d88c
commit
91c7407806
|
@ -64,7 +64,6 @@ void adcInit(drv_adc_config_t *init)
|
|||
GPIO_InitStructure.GPIO_Mode = GPIO_Mode_AIN;
|
||||
|
||||
#ifdef CC3D
|
||||
UNUSED(init);
|
||||
GPIO_InitStructure.GPIO_Pin = GPIO_Pin_0;
|
||||
adcConfig[ADC_BATTERY].adcChannel = ADC_Channel_0;
|
||||
adcConfig[ADC_BATTERY].dmaIndex = configuredAdcChannels++;
|
||||
|
|
|
@ -21,7 +21,7 @@
|
|||
|
||||
#include "platform.h"
|
||||
|
||||
#ifdef USE_SOFT_SERIAL
|
||||
#if defined(USE_SOFTSERIAL1) || defined(USE_SOFTSERIAL2)
|
||||
|
||||
#include "build_config.h"
|
||||
|
||||
|
@ -33,24 +33,22 @@
|
|||
#include "serial_softserial.h"
|
||||
|
||||
#if defined(CC3D)
|
||||
#define SOFT_SERIAL_1_TIMER_RX_HARDWARE 2 // PWM 3
|
||||
#define SOFT_SERIAL_1_TIMER_TX_HARDWARE 3 // PWM 4
|
||||
#define SOFT_SERIAL_2_TIMER_RX_HARDWARE 2 // PWM 3
|
||||
#define SOFT_SERIAL_2_TIMER_TX_HARDWARE 3 // PWM 4
|
||||
#define SOFTSERIAL_1_TIMER_RX_HARDWARE 2 // PWM 3
|
||||
#define SOFTSERIAL_1_TIMER_TX_HARDWARE 3 // PWM 4
|
||||
#else
|
||||
|
||||
#if defined(STM32F10X) || defined(CHEBUZZF3)
|
||||
#define SOFT_SERIAL_1_TIMER_RX_HARDWARE 4 // PWM 5
|
||||
#define SOFT_SERIAL_1_TIMER_TX_HARDWARE 5 // PWM 6
|
||||
#define SOFT_SERIAL_2_TIMER_RX_HARDWARE 6 // PWM 7
|
||||
#define SOFT_SERIAL_2_TIMER_TX_HARDWARE 7 // PWM 8
|
||||
#define SOFTSERIAL_1_TIMER_RX_HARDWARE 4 // PWM 5
|
||||
#define SOFTSERIAL_1_TIMER_TX_HARDWARE 5 // PWM 6
|
||||
#define SOFTSERIAL_2_TIMER_RX_HARDWARE 6 // PWM 7
|
||||
#define SOFTSERIAL_2_TIMER_TX_HARDWARE 7 // PWM 8
|
||||
#endif
|
||||
|
||||
#if defined(STM32F303) && !defined(CHEBUZZF3)
|
||||
#define SOFT_SERIAL_1_TIMER_RX_HARDWARE 8 // PWM 9
|
||||
#define SOFT_SERIAL_1_TIMER_TX_HARDWARE 9 // PWM 10
|
||||
#define SOFT_SERIAL_2_TIMER_RX_HARDWARE 10 // PWM 11
|
||||
#define SOFT_SERIAL_2_TIMER_TX_HARDWARE 11 // PWM 12
|
||||
#define SOFTSERIAL_1_TIMER_RX_HARDWARE 8 // PWM 9
|
||||
#define SOFTSERIAL_1_TIMER_TX_HARDWARE 9 // PWM 10
|
||||
#define SOFTSERIAL_2_TIMER_RX_HARDWARE 10 // PWM 11
|
||||
#define SOFTSERIAL_2_TIMER_TX_HARDWARE 11 // PWM 12
|
||||
#endif
|
||||
#endif
|
||||
|
||||
|
@ -60,7 +58,6 @@
|
|||
#define MAX_SOFTSERIAL_PORTS 2
|
||||
softSerial_t softSerialPorts[MAX_SOFTSERIAL_PORTS];
|
||||
|
||||
|
||||
void onSerialTimer(uint8_t portIndex, captureCompare_t capture);
|
||||
void onSerialRxPinChange(uint8_t portIndex, captureCompare_t capture);
|
||||
|
||||
|
@ -146,13 +143,13 @@ static void serialOutputPortConfig(const timerHardware_t *timerHardwarePtr)
|
|||
|
||||
static void resetBuffers(softSerial_t *softSerial)
|
||||
{
|
||||
softSerial->port.rxBufferSize = SOFT_SERIAL_BUFFER_SIZE;
|
||||
softSerial->port.rxBufferSize = SOFTSERIAL_BUFFER_SIZE;
|
||||
softSerial->port.rxBuffer = softSerial->rxBuffer;
|
||||
softSerial->port.rxBufferTail = 0;
|
||||
softSerial->port.rxBufferHead = 0;
|
||||
|
||||
softSerial->port.txBuffer = softSerial->txBuffer;
|
||||
softSerial->port.txBufferSize = SOFT_SERIAL_BUFFER_SIZE;
|
||||
softSerial->port.txBufferSize = SOFTSERIAL_BUFFER_SIZE;
|
||||
softSerial->port.txBufferTail = 0;
|
||||
softSerial->port.txBufferHead = 0;
|
||||
}
|
||||
|
@ -161,15 +158,19 @@ serialPort_t *openSoftSerial(softSerialPortIndex_e portIndex, serialReceiveCallb
|
|||
{
|
||||
softSerial_t *softSerial = &(softSerialPorts[portIndex]);
|
||||
|
||||
#ifdef USE_SOFTSERIAL1
|
||||
if (portIndex == SOFTSERIAL1) {
|
||||
softSerial->rxTimerHardware = &(timerHardware[SOFT_SERIAL_1_TIMER_RX_HARDWARE]);
|
||||
softSerial->txTimerHardware = &(timerHardware[SOFT_SERIAL_1_TIMER_TX_HARDWARE]);
|
||||
softSerial->rxTimerHardware = &(timerHardware[SOFTSERIAL_1_TIMER_RX_HARDWARE]);
|
||||
softSerial->txTimerHardware = &(timerHardware[SOFTSERIAL_1_TIMER_TX_HARDWARE]);
|
||||
}
|
||||
#endif
|
||||
|
||||
#ifdef USE_SOFTSERIAL2
|
||||
if (portIndex == SOFTSERIAL2) {
|
||||
softSerial->rxTimerHardware = &(timerHardware[SOFT_SERIAL_2_TIMER_RX_HARDWARE]);
|
||||
softSerial->txTimerHardware = &(timerHardware[SOFT_SERIAL_2_TIMER_TX_HARDWARE]);
|
||||
softSerial->rxTimerHardware = &(timerHardware[SOFTSERIAL_2_TIMER_RX_HARDWARE]);
|
||||
softSerial->txTimerHardware = &(timerHardware[SOFTSERIAL_2_TIMER_TX_HARDWARE]);
|
||||
}
|
||||
#endif
|
||||
|
||||
softSerial->port.vTable = softSerialVTable;
|
||||
softSerial->port.baudRate = baud;
|
||||
|
|
|
@ -17,7 +17,7 @@
|
|||
|
||||
#pragma once
|
||||
|
||||
#define SOFT_SERIAL_BUFFER_SIZE 256
|
||||
#define SOFTSERIAL_BUFFER_SIZE 256
|
||||
|
||||
typedef enum {
|
||||
SOFTSERIAL1 = 0,
|
||||
|
@ -28,10 +28,10 @@ typedef struct softSerial_s {
|
|||
serialPort_t port;
|
||||
|
||||
const timerHardware_t *rxTimerHardware;
|
||||
volatile uint8_t rxBuffer[SOFT_SERIAL_BUFFER_SIZE];
|
||||
volatile uint8_t rxBuffer[SOFTSERIAL_BUFFER_SIZE];
|
||||
|
||||
const timerHardware_t *txTimerHardware;
|
||||
volatile uint8_t txBuffer[SOFT_SERIAL_BUFFER_SIZE];
|
||||
volatile uint8_t txBuffer[SOFTSERIAL_BUFFER_SIZE];
|
||||
|
||||
uint8_t isSearchingForStartBit;
|
||||
uint8_t rxBitIndex;
|
||||
|
|
|
@ -91,15 +91,13 @@ static const serialPortConstraint_t serialPortConstraints[SERIAL_PORT_COUNT] = {
|
|||
static serialPortFunction_t serialPortFunctions[SERIAL_PORT_COUNT] = {
|
||||
{SERIAL_PORT_USART1, NULL, SCENARIO_UNUSED, FUNCTION_NONE},
|
||||
{SERIAL_PORT_USART3, NULL, SCENARIO_UNUSED, FUNCTION_NONE},
|
||||
{SERIAL_PORT_SOFTSERIAL1, NULL, SCENARIO_UNUSED, FUNCTION_NONE},
|
||||
{SERIAL_PORT_SOFTSERIAL2, NULL, SCENARIO_UNUSED, FUNCTION_NONE}
|
||||
{SERIAL_PORT_SOFTSERIAL1, NULL, SCENARIO_UNUSED, FUNCTION_NONE}
|
||||
};
|
||||
|
||||
static const serialPortConstraint_t serialPortConstraints[SERIAL_PORT_COUNT] = {
|
||||
{SERIAL_PORT_USART1, 9600, 115200, SPF_NONE | SPF_SUPPORTS_SBUS_MODE },
|
||||
{SERIAL_PORT_USART3, 9600, 115200, SPF_SUPPORTS_CALLBACK | SPF_SUPPORTS_SBUS_MODE},
|
||||
{SERIAL_PORT_SOFTSERIAL1, 9600, 19200, SPF_SUPPORTS_CALLBACK | SPF_IS_SOFTWARE_INVERTABLE},
|
||||
{SERIAL_PORT_SOFTSERIAL2, 9600, 19200, SPF_SUPPORTS_CALLBACK | SPF_IS_SOFTWARE_INVERTABLE}
|
||||
{SERIAL_PORT_SOFTSERIAL1, 9600, 19200, SPF_SUPPORTS_CALLBACK | SPF_IS_SOFTWARE_INVERTABLE}
|
||||
};
|
||||
#else
|
||||
|
||||
|
@ -252,7 +250,7 @@ serialPortSearchResult_t *findNextSerialPort(serialPortFunction_e function, cons
|
|||
uint8_t serialPortIndex = lookupSerialPortIndexByIdentifier(serialPortFunction->identifier);
|
||||
const serialPortConstraint_t *serialPortConstraint = &serialPortConstraints[serialPortIndex];
|
||||
|
||||
#ifdef USE_SOFT_SERIAL
|
||||
#if defined(USE_SOFTSERIAL1) ||(defined(USE_SOFTSERIAL2))
|
||||
if (!feature(FEATURE_SOFTSERIAL) && (
|
||||
serialPortConstraint->identifier == SERIAL_PORT_SOFTSERIAL1 ||
|
||||
serialPortConstraint->identifier == SERIAL_PORT_SOFTSERIAL2
|
||||
|
@ -581,7 +579,7 @@ serialPort_t *openSerialPort(serialPortFunction_e function, serialReceiveCallbac
|
|||
serialPort = uartOpen(USART3, callback, baudRate, mode, inversion);
|
||||
break;
|
||||
#endif
|
||||
#ifdef USE_SOFT_SERIAL
|
||||
#ifdef USE_SOFTSERIAL
|
||||
case SERIAL_PORT_SOFTSERIAL1:
|
||||
serialPort = openSoftSerial(SOFTSERIAL1, callback, baudRate, inversion);
|
||||
serialSetMode(serialPort, mode);
|
||||
|
|
|
@ -46,6 +46,8 @@
|
|||
|
||||
#define USE_USART1
|
||||
#define USE_USART3
|
||||
#define USE_SOFTSERIAL1
|
||||
#define SERIAL_PORT_COUNT 3
|
||||
|
||||
#define USART3_RX_PIN Pin_11
|
||||
#define USART3_TX_PIN Pin_10
|
||||
|
@ -53,9 +55,7 @@
|
|||
#define USART3_APB1_PERIPHERALS RCC_APB1Periph_USART3
|
||||
#define USART3_APB2_PERIPHERALS RCC_APB2Periph_GPIOB
|
||||
|
||||
#define USE_SOFT_SERIAL
|
||||
#define SERIAL_PORT_COUNT 4
|
||||
#define SOFT_SERIAL
|
||||
|
||||
|
||||
#define USE_SPI
|
||||
#define USE_SPI_DEVICE_1
|
||||
|
|
|
@ -56,6 +56,5 @@
|
|||
#define GPS
|
||||
#define LED_STRIP
|
||||
#define TELEMETRY
|
||||
#define SOFT_SERIAL
|
||||
#define SERIAL_RX
|
||||
#define AUTOTUNE
|
||||
|
|
|
@ -56,7 +56,8 @@
|
|||
|
||||
#define USE_USART1
|
||||
#define USE_USART2
|
||||
#define USE_SOFT_SERIAL
|
||||
#define USE_SOFTSERIAL1
|
||||
#define USE_SOFTSERIAL2
|
||||
#define SERIAL_PORT_COUNT 4
|
||||
|
||||
#define USE_I2C
|
||||
|
@ -71,7 +72,6 @@
|
|||
#define GPS
|
||||
#define LED_STRIP
|
||||
#define TELEMETRY
|
||||
#define SOFT_SERIAL
|
||||
#define SERIAL_RX
|
||||
#define AUTOTUNE
|
||||
|
||||
|
|
|
@ -82,7 +82,8 @@
|
|||
|
||||
#define USE_USART1
|
||||
#define USE_USART2
|
||||
#define USE_SOFT_SERIAL
|
||||
#define USE_SOFTSERIAL1
|
||||
#define USE_SOFTSERIAL2
|
||||
#define SERIAL_PORT_COUNT 4
|
||||
|
||||
#define USE_I2C
|
||||
|
@ -103,6 +104,5 @@
|
|||
|
||||
#define LED_STRIP
|
||||
#define TELEMETRY
|
||||
#define SOFT_SERIAL
|
||||
#define SERIAL_RX
|
||||
#define AUTOTUNE
|
||||
|
|
|
@ -45,6 +45,5 @@
|
|||
#define GPS
|
||||
#define LED_STRIP
|
||||
#define TELEMETRY
|
||||
#define SOFT_SERIAL
|
||||
#define SERIAL_RX
|
||||
#define AUTOTUNE
|
||||
|
|
|
@ -67,7 +67,8 @@
|
|||
|
||||
#define USE_USART1
|
||||
#define USE_USART2
|
||||
#define USE_SOFT_SERIAL
|
||||
#define USE_SOFTSERIAL1
|
||||
#define USE_SOFTSERIAL2
|
||||
#define SERIAL_PORT_COUNT 4
|
||||
|
||||
#define USE_I2C
|
||||
|
@ -82,7 +83,6 @@
|
|||
#define GPS
|
||||
#define LED_STRIP
|
||||
#define TELEMETRY
|
||||
#define SOFT_SERIAL
|
||||
#define SERIAL_RX
|
||||
#define AUTOTUNE
|
||||
|
||||
|
|
Loading…
Reference in New Issue