Merge pull request #690 from ledvinap/fix-sparky-smartport
Fix sparky smartport
This commit is contained in:
commit
27ea92f36c
|
@ -52,19 +52,12 @@ static void usartConfigurePinInversion(uartPort_t *uartPort) {
|
||||||
#ifdef STM32F303xC
|
#ifdef STM32F303xC
|
||||||
uint32_t inversionPins = 0;
|
uint32_t inversionPins = 0;
|
||||||
|
|
||||||
// Inversion when using OPTION_BIDIR not supported yet.
|
|
||||||
if (uartPort->port.options & SERIAL_BIDIR) {
|
|
||||||
// Clear inversion on both Tx and Rx
|
|
||||||
inversionPins |= USART_InvPin_Tx | USART_InvPin_Rx;
|
|
||||||
inverted = false;
|
|
||||||
} else {
|
|
||||||
if (uartPort->port.mode & MODE_TX) {
|
if (uartPort->port.mode & MODE_TX) {
|
||||||
inversionPins |= USART_InvPin_Tx;
|
inversionPins |= USART_InvPin_Tx;
|
||||||
}
|
}
|
||||||
if (uartPort->port.mode & MODE_RX) {
|
if (uartPort->port.mode & MODE_RX) {
|
||||||
inversionPins |= USART_InvPin_Rx;
|
inversionPins |= USART_InvPin_Rx;
|
||||||
}
|
}
|
||||||
}
|
|
||||||
|
|
||||||
USART_InvPinCmd(uartPort->USARTx, inversionPins, inverted ? ENABLE : DISABLE);
|
USART_InvPinCmd(uartPort->USARTx, inversionPins, inverted ? ENABLE : DISABLE);
|
||||||
#endif
|
#endif
|
||||||
|
@ -93,6 +86,11 @@ static void uartReconfigure(uartPort_t *uartPort)
|
||||||
|
|
||||||
usartConfigurePinInversion(uartPort);
|
usartConfigurePinInversion(uartPort);
|
||||||
|
|
||||||
|
if(uartPort->port.options & SERIAL_BIDIR)
|
||||||
|
USART_HalfDuplexCmd(uartPort->USARTx, ENABLE);
|
||||||
|
else
|
||||||
|
USART_HalfDuplexCmd(uartPort->USARTx, DISABLE);
|
||||||
|
|
||||||
USART_Cmd(uartPort->USARTx, ENABLE);
|
USART_Cmd(uartPort->USARTx, ENABLE);
|
||||||
}
|
}
|
||||||
|
|
||||||
|
@ -182,11 +180,6 @@ serialPort_t *uartOpen(USART_TypeDef *USARTx, serialReceiveCallbackPtr callback,
|
||||||
|
|
||||||
USART_Cmd(s->USARTx, ENABLE);
|
USART_Cmd(s->USARTx, ENABLE);
|
||||||
|
|
||||||
if (options & SERIAL_BIDIR)
|
|
||||||
USART_HalfDuplexCmd(s->USARTx, ENABLE);
|
|
||||||
else
|
|
||||||
USART_HalfDuplexCmd(s->USARTx, DISABLE);
|
|
||||||
|
|
||||||
return (serialPort_t *)s;
|
return (serialPort_t *)s;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
|
@ -116,13 +116,15 @@ uartPort_t *serialUSART1(uint32_t baudRate, portMode_t mode, portOptions_t optio
|
||||||
GPIO_InitStructure.GPIO_Mode = GPIO_Mode_AF;
|
GPIO_InitStructure.GPIO_Mode = GPIO_Mode_AF;
|
||||||
GPIO_InitStructure.GPIO_Speed = GPIO_Speed_50MHz;
|
GPIO_InitStructure.GPIO_Speed = GPIO_Speed_50MHz;
|
||||||
GPIO_InitStructure.GPIO_OType = GPIO_OType_PP;
|
GPIO_InitStructure.GPIO_OType = GPIO_OType_PP;
|
||||||
GPIO_InitStructure.GPIO_PuPd = GPIO_PuPd_UP;
|
GPIO_InitStructure.GPIO_PuPd = (options & SERIAL_INVERTED) ? GPIO_PuPd_DOWN : GPIO_PuPd_UP;
|
||||||
|
|
||||||
if (options & SERIAL_BIDIR) {
|
if (options & SERIAL_BIDIR) {
|
||||||
GPIO_InitStructure.GPIO_Pin = UART1_TX_PIN;
|
GPIO_InitStructure.GPIO_Pin = UART1_TX_PIN;
|
||||||
GPIO_InitStructure.GPIO_OType = GPIO_OType_OD;
|
GPIO_InitStructure.GPIO_OType = (options & SERIAL_INVERTED) ? GPIO_OType_PP : GPIO_OType_OD;
|
||||||
GPIO_PinAFConfig(UART1_GPIO, UART1_TX_PINSOURCE, UART1_GPIO_AF);
|
GPIO_PinAFConfig(UART1_GPIO, UART1_TX_PINSOURCE, UART1_GPIO_AF);
|
||||||
GPIO_Init(UART1_GPIO, &GPIO_InitStructure);
|
GPIO_Init(UART1_GPIO, &GPIO_InitStructure);
|
||||||
|
if(!(options & SERIAL_INVERTED))
|
||||||
|
GPIO_SetBits(UART1_GPIO, UART1_TX_PIN); // OpenDrain output should be inactive
|
||||||
} else {
|
} else {
|
||||||
if (mode & MODE_TX) {
|
if (mode & MODE_TX) {
|
||||||
GPIO_InitStructure.GPIO_Pin = UART1_TX_PIN;
|
GPIO_InitStructure.GPIO_Pin = UART1_TX_PIN;
|
||||||
|
@ -195,13 +197,15 @@ uartPort_t *serialUSART2(uint32_t baudRate, portMode_t mode, portOptions_t optio
|
||||||
GPIO_InitStructure.GPIO_Mode = GPIO_Mode_AF;
|
GPIO_InitStructure.GPIO_Mode = GPIO_Mode_AF;
|
||||||
GPIO_InitStructure.GPIO_Speed = GPIO_Speed_50MHz;
|
GPIO_InitStructure.GPIO_Speed = GPIO_Speed_50MHz;
|
||||||
GPIO_InitStructure.GPIO_OType = GPIO_OType_PP;
|
GPIO_InitStructure.GPIO_OType = GPIO_OType_PP;
|
||||||
GPIO_InitStructure.GPIO_PuPd = GPIO_PuPd_UP;
|
GPIO_InitStructure.GPIO_PuPd = (options & SERIAL_INVERTED) ? GPIO_PuPd_DOWN : GPIO_PuPd_UP;
|
||||||
|
|
||||||
if (options & SERIAL_BIDIR) {
|
if (options & SERIAL_BIDIR) {
|
||||||
GPIO_InitStructure.GPIO_Pin = UART2_TX_PIN;
|
GPIO_InitStructure.GPIO_Pin = UART2_TX_PIN;
|
||||||
GPIO_InitStructure.GPIO_OType = GPIO_OType_OD;
|
GPIO_InitStructure.GPIO_OType = (options & SERIAL_INVERTED) ? GPIO_OType_PP : GPIO_OType_OD;
|
||||||
GPIO_PinAFConfig(UART2_GPIO, UART2_TX_PINSOURCE, UART2_GPIO_AF);
|
GPIO_PinAFConfig(UART2_GPIO, UART2_TX_PINSOURCE, UART2_GPIO_AF);
|
||||||
GPIO_Init(UART2_GPIO, &GPIO_InitStructure);
|
GPIO_Init(UART2_GPIO, &GPIO_InitStructure);
|
||||||
|
if(!(options & SERIAL_INVERTED))
|
||||||
|
GPIO_SetBits(UART2_GPIO, UART2_TX_PIN); // OpenDrain output should be inactive
|
||||||
} else {
|
} else {
|
||||||
if (mode & MODE_TX) {
|
if (mode & MODE_TX) {
|
||||||
GPIO_InitStructure.GPIO_Pin = UART2_TX_PIN;
|
GPIO_InitStructure.GPIO_Pin = UART2_TX_PIN;
|
||||||
|
@ -276,13 +280,15 @@ uartPort_t *serialUSART3(uint32_t baudRate, portMode_t mode, portOptions_t optio
|
||||||
GPIO_InitStructure.GPIO_Mode = GPIO_Mode_AF;
|
GPIO_InitStructure.GPIO_Mode = GPIO_Mode_AF;
|
||||||
GPIO_InitStructure.GPIO_Speed = GPIO_Speed_50MHz;
|
GPIO_InitStructure.GPIO_Speed = GPIO_Speed_50MHz;
|
||||||
GPIO_InitStructure.GPIO_OType = GPIO_OType_PP;
|
GPIO_InitStructure.GPIO_OType = GPIO_OType_PP;
|
||||||
GPIO_InitStructure.GPIO_PuPd = GPIO_PuPd_UP;
|
GPIO_InitStructure.GPIO_PuPd = (options & SERIAL_INVERTED) ? GPIO_PuPd_DOWN : GPIO_PuPd_UP;
|
||||||
|
|
||||||
if (options & SERIAL_BIDIR) {
|
if (options & SERIAL_BIDIR) {
|
||||||
GPIO_InitStructure.GPIO_Pin = UART3_TX_PIN;
|
GPIO_InitStructure.GPIO_Pin = UART3_TX_PIN;
|
||||||
GPIO_InitStructure.GPIO_OType = GPIO_OType_OD;
|
GPIO_InitStructure.GPIO_OType = (options & SERIAL_INVERTED) ? GPIO_OType_PP : GPIO_OType_OD;
|
||||||
GPIO_PinAFConfig(UART3_GPIO, UART3_TX_PINSOURCE, UART3_GPIO_AF);
|
GPIO_PinAFConfig(UART3_GPIO, UART3_TX_PINSOURCE, UART3_GPIO_AF);
|
||||||
GPIO_Init(UART3_GPIO, &GPIO_InitStructure);
|
GPIO_Init(UART3_GPIO, &GPIO_InitStructure);
|
||||||
|
if(!(options & SERIAL_INVERTED))
|
||||||
|
GPIO_SetBits(UART3_GPIO, UART3_TX_PIN); // OpenDrain output should be inactive
|
||||||
} else {
|
} else {
|
||||||
if (mode & MODE_TX) {
|
if (mode & MODE_TX) {
|
||||||
GPIO_InitStructure.GPIO_Pin = UART3_TX_PIN;
|
GPIO_InitStructure.GPIO_Pin = UART3_TX_PIN;
|
||||||
|
|
|
@ -106,6 +106,7 @@
|
||||||
#define GPS
|
#define GPS
|
||||||
#define DISPLAY
|
#define DISPLAY
|
||||||
#define USE_SERVOS
|
#define USE_SERVOS
|
||||||
|
#define TELEMETRY
|
||||||
|
|
||||||
#define LED_STRIP
|
#define LED_STRIP
|
||||||
#if 1
|
#if 1
|
||||||
|
|
|
@ -162,10 +162,7 @@ static void smartPortDataReceive(uint16_t c)
|
||||||
if (lastChar == FSSP_START_STOP) {
|
if (lastChar == FSSP_START_STOP) {
|
||||||
smartPortState = SPSTATE_WORKING;
|
smartPortState = SPSTATE_WORKING;
|
||||||
smartPortLastRequestTime = now;
|
smartPortLastRequestTime = now;
|
||||||
if ((c == FSSP_SENSOR_ID1) ||
|
if (c == FSSP_SENSOR_ID1) {
|
||||||
(c == FSSP_SENSOR_ID2) ||
|
|
||||||
(c == FSSP_SENSOR_ID3) ||
|
|
||||||
(c == FSSP_SENSOR_ID4)) {
|
|
||||||
smartPortHasRequest = 1;
|
smartPortHasRequest = 1;
|
||||||
// we only responde to these IDs
|
// we only responde to these IDs
|
||||||
// the X4R-SB does send other IDs, we ignore them, but take note of the time
|
// the X4R-SB does send other IDs, we ignore them, but take note of the time
|
||||||
|
|
Loading…
Reference in New Issue