Merge pull request #23 from flightng/4.3.2-fix-neutronrcf435aio-dfu-i2cdelay
[Driver]: Swap TXRX to avoid DFU-hijacking and decrease i2c timeout
This commit is contained in:
commit
8ea38b046e
|
@ -38,7 +38,7 @@
|
||||||
#include "drivers/bus_i2c_impl.h"
|
#include "drivers/bus_i2c_impl.h"
|
||||||
|
|
||||||
//#define I2C_TIMEOUT 0x3FFFFF
|
//#define I2C_TIMEOUT 0x3FFFFF
|
||||||
#define I2C_TIMEOUT 0x8700 //about 120 us at 288 mhz
|
#define I2C_TIMEOUT 0x870 //about 7 us at 288 mhz
|
||||||
|
|
||||||
#ifdef USE_I2C_DEVICE_1
|
#ifdef USE_I2C_DEVICE_1
|
||||||
void I2C1_ERR_IRQHandler(void)
|
void I2C1_ERR_IRQHandler(void)
|
||||||
|
@ -287,7 +287,7 @@ bool i2cReadBuffer(I2CDevice device, uint8_t addr_, uint8_t reg_, uint8_t len, u
|
||||||
else
|
else
|
||||||
{
|
{
|
||||||
/* wait for the communication to end */
|
/* wait for the communication to end */
|
||||||
i2c_wait_end(pHandle->i2cx, I2C_TIMEOUT);
|
// i2c_wait_end(pHandle->i2cx, I2C_TIMEOUT);
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
||||||
|
|
|
@ -63,33 +63,32 @@ static void usartConfigurePinInversion(uartPort_t *uartPort) {
|
||||||
#endif
|
#endif
|
||||||
}
|
}
|
||||||
|
|
||||||
|
static uartDevice_t *uartFindDevice(uartPort_t *uartPort)
|
||||||
|
{
|
||||||
|
for (uint32_t i = 0; i < UARTDEV_COUNT_MAX; i++) {
|
||||||
|
uartDevice_t *candidate = uartDevmap[i];
|
||||||
|
|
||||||
|
if (&candidate->port == uartPort) {
|
||||||
|
return candidate;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
return NULL;
|
||||||
|
}
|
||||||
|
|
||||||
|
static void uartConfigurePinSwap(uartPort_t *uartPort)
|
||||||
|
{
|
||||||
|
uartDevice_t *uartDevice = uartFindDevice(uartPort);
|
||||||
|
if (!uartDevice) {
|
||||||
|
return;
|
||||||
|
}
|
||||||
|
|
||||||
|
if (uartDevice->pinSwap) {
|
||||||
|
usart_transmit_receive_pin_swap(uartDevice->port.USARTx,TRUE);
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
void uartReconfigure(uartPort_t *uartPort)
|
void uartReconfigure(uartPort_t *uartPort)
|
||||||
{
|
{
|
||||||
// USART_InitTypeDef USART_InitStructure;
|
|
||||||
// USART_Cmd(uartPort->USARTx, DISABLE);
|
|
||||||
// USART_InitStructure.USART_BaudRate = uartPort->port.baudRate;
|
|
||||||
|
|
||||||
// according to the stm32 documentation wordlen has to be 9 for parity bits
|
|
||||||
// this does not seem to matter for rx but will give bad data on tx!
|
|
||||||
// This seems to cause RX to break on STM32F1, see https://github.com/betaflight/betaflight/pull/1654
|
|
||||||
// if ( (uartPort->port.options & SERIAL_PARITY_EVEN)) {
|
|
||||||
// USART_InitStructure.USART_WordLength = USART_WordLength_9b;
|
|
||||||
// } else {
|
|
||||||
// USART_InitStructure.USART_WordLength = USART_WordLength_8b;
|
|
||||||
// }
|
|
||||||
|
|
||||||
// USART_InitStructure.USART_StopBits = (uartPort->port.options & SERIAL_STOPBITS_2) ? USART_StopBits_2 : USART_StopBits_1;
|
|
||||||
// USART_InitStructure.USART_Parity = (uartPort->port.options & SERIAL_PARITY_EVEN) ? USART_Parity_Even : USART_Parity_No;
|
|
||||||
//
|
|
||||||
// USART_InitStructure.USART_HardwareFlowControl = USART_HardwareFlowControl_None;
|
|
||||||
// USART_InitStructure.USART_Mode = 0;
|
|
||||||
// if (uartPort->port.mode & MODE_RX)
|
|
||||||
// USART_InitStructure.USART_Mode |= USART_Mode_Rx;
|
|
||||||
// if (uartPort->port.mode & MODE_TX)
|
|
||||||
// USART_InitStructure.USART_Mode |= USART_Mode_Tx;
|
|
||||||
//
|
|
||||||
// USART_Init(uartPort->USARTx, &USART_InitStructure);
|
|
||||||
// void usart_init(usart_type* usart_x, uint32_t baud_rate, usart_data_bit_num_type data_bit, usart_stop_bit_num_type stop_bit)
|
|
||||||
|
|
||||||
usart_enable(uartPort->USARTx,DISABLE);
|
usart_enable(uartPort->USARTx,DISABLE);
|
||||||
//init
|
//init
|
||||||
|
@ -111,9 +110,12 @@ void uartReconfigure(uartPort_t *uartPort)
|
||||||
if (uartPort->port.mode & MODE_TX)
|
if (uartPort->port.mode & MODE_TX)
|
||||||
usart_transmitter_enable(uartPort->USARTx,TRUE);
|
usart_transmitter_enable(uartPort->USARTx,TRUE);
|
||||||
|
|
||||||
//config pin swap
|
//config pin inverter
|
||||||
usartConfigurePinInversion(uartPort);
|
usartConfigurePinInversion(uartPort);
|
||||||
|
|
||||||
|
//config pin swap
|
||||||
|
uartConfigurePinSwap(uartPort);
|
||||||
|
|
||||||
if (uartPort->port.options & SERIAL_BIDIR)
|
if (uartPort->port.options & SERIAL_BIDIR)
|
||||||
// USART_HalfDuplexCmd(uartPort->USARTx, ENABLE);
|
// USART_HalfDuplexCmd(uartPort->USARTx, ENABLE);
|
||||||
usart_single_line_halfduplex_select(uartPort->USARTx, TRUE);
|
usart_single_line_halfduplex_select(uartPort->USARTx, TRUE);
|
||||||
|
|
Loading…
Reference in New Issue