forked from Archive/PX4-Autopilot
0001-RS-485-support-for-STM32-serial-driver.patch from Freddi Chopin
git-svn-id: http://svn.code.sf.net/p/nuttx/code/trunk@5371 42af7a65-404d-4744-a932-0658087f49c3
This commit is contained in:
parent
7a68d93999
commit
2754c39e6e
|
@ -1831,6 +1831,27 @@ config STM32_TIM14_DAC2
|
|||
|
||||
endchoice
|
||||
|
||||
menu "U[S]ART Configuration"
|
||||
depends on STM32_USART1 || STM32_USART2 || STM32_USART3 || STM32_USART4 || STM32_USART5 || STM32_USART6
|
||||
|
||||
config USART1_RS485
|
||||
bool "RS-485 on USART1"
|
||||
default n
|
||||
depends on STM32_USART1
|
||||
---help---
|
||||
Enable RS-485 interface on USART1. Your board config will have to
|
||||
provide GPIO_USART1_RS485_DIR pin definition. Currently it cannot be
|
||||
used with USART1_RXDMA.
|
||||
|
||||
config USART1_RS485_DIR_POLARITY
|
||||
int "USART1 RS-485 DIR pin polarity"
|
||||
default 1
|
||||
range 0 1
|
||||
depends on USART1_RS485
|
||||
---help---
|
||||
Polarity of DIR pin for RS-485 on USART1. Set to state on DIR pin which
|
||||
enables TX (0 - low / nTXEN, 1 - high / TXEN).
|
||||
|
||||
config USART1_RXDMA
|
||||
bool "USART1 Rx DMA"
|
||||
default n
|
||||
|
@ -1838,6 +1859,24 @@ config USART1_RXDMA
|
|||
---help---
|
||||
In high data rate usage, Rx DMA may eliminate Rx overrun errors
|
||||
|
||||
config USART2_RS485
|
||||
bool "RS-485 on USART2"
|
||||
default n
|
||||
depends on STM32_USART2
|
||||
---help---
|
||||
Enable RS-485 interface on USART2. Your board config will have to
|
||||
provide GPIO_USART2_RS485_DIR pin definition. Currently it cannot be
|
||||
used with USART2_RXDMA.
|
||||
|
||||
config USART2_RS485_DIR_POLARITY
|
||||
int "USART2 RS-485 DIR pin polarity"
|
||||
default 1
|
||||
range 0 1
|
||||
depends on USART2_RS485
|
||||
---help---
|
||||
Polarity of DIR pin for RS-485 on USART2. Set to state on DIR pin which
|
||||
enables TX (0 - low / nTXEN, 1 - high / TXEN).
|
||||
|
||||
config USART2_RXDMA
|
||||
bool "USART2 Rx DMA"
|
||||
default n
|
||||
|
@ -1845,6 +1884,24 @@ config USART2_RXDMA
|
|||
---help---
|
||||
In high data rate usage, Rx DMA may eliminate Rx overrun errors
|
||||
|
||||
config USART3_RS485
|
||||
bool "RS-485 on USART3"
|
||||
default n
|
||||
depends on STM32_USART3
|
||||
---help---
|
||||
Enable RS-485 interface on USART3. Your board config will have to
|
||||
provide GPIO_USART3_RS485_DIR pin definition. Currently it cannot be
|
||||
used with USART3_RXDMA.
|
||||
|
||||
config USART3_RS485_DIR_POLARITY
|
||||
int "USART3 RS-485 DIR pin polarity"
|
||||
default 1
|
||||
range 0 1
|
||||
depends on USART3_RS485
|
||||
---help---
|
||||
Polarity of DIR pin for RS-485 on USART3. Set to state on DIR pin which
|
||||
enables TX (0 - low / nTXEN, 1 - high / TXEN).
|
||||
|
||||
config USART3_RXDMA
|
||||
bool "USART3 Rx DMA"
|
||||
default n
|
||||
|
@ -1852,6 +1909,24 @@ config USART3_RXDMA
|
|||
---help---
|
||||
In high data rate usage, Rx DMA may eliminate Rx overrun errors
|
||||
|
||||
config UART4_RS485
|
||||
bool "RS-485 on UART4"
|
||||
default n
|
||||
depends on STM32_UART4
|
||||
---help---
|
||||
Enable RS-485 interface on UART4. Your board config will have to
|
||||
provide GPIO_UART4_RS485_DIR pin definition. Currently it cannot be
|
||||
used with UART4_RXDMA.
|
||||
|
||||
config UART4_RS485_DIR_POLARITY
|
||||
int "UART4 RS-485 DIR pin polarity"
|
||||
default 1
|
||||
range 0 1
|
||||
depends on UART4_RS485
|
||||
---help---
|
||||
Polarity of DIR pin for RS-485 on UART4. Set to state on DIR pin which
|
||||
enables TX (0 - low / nTXEN, 1 - high / TXEN).
|
||||
|
||||
config UART4_RXDMA
|
||||
bool "UART4 Rx DMA"
|
||||
default n
|
||||
|
@ -1859,6 +1934,24 @@ config UART4_RXDMA
|
|||
---help---
|
||||
In high data rate usage, Rx DMA may eliminate Rx overrun errors
|
||||
|
||||
config UART5_RS485
|
||||
bool "RS-485 on UART5"
|
||||
default n
|
||||
depends on STM32_UART5
|
||||
---help---
|
||||
Enable RS-485 interface on UART5. Your board config will have to
|
||||
provide GPIO_UART5_RS485_DIR pin definition. Currently it cannot be
|
||||
used with UART5_RXDMA.
|
||||
|
||||
config UART5_RS485_DIR_POLARITY
|
||||
int "UART5 RS-485 DIR pin polarity"
|
||||
default 1
|
||||
range 0 1
|
||||
depends on UART5_RS485
|
||||
---help---
|
||||
Polarity of DIR pin for RS-485 on UART5. Set to state on DIR pin which
|
||||
enables TX (0 - low / nTXEN, 1 - high / TXEN).
|
||||
|
||||
config UART5_RXDMA
|
||||
bool "UART5 Rx DMA"
|
||||
default n
|
||||
|
@ -1866,6 +1959,24 @@ config UART5_RXDMA
|
|||
---help---
|
||||
In high data rate usage, Rx DMA may eliminate Rx overrun errors
|
||||
|
||||
config USART6_RS485
|
||||
bool "RS-485 on USART6"
|
||||
default n
|
||||
depends on STM32_USART6
|
||||
---help---
|
||||
Enable RS-485 interface on USART6. Your board config will have to
|
||||
provide GPIO_USART6_RS485_DIR pin definition. Currently it cannot be
|
||||
used with USART6_RXDMA.
|
||||
|
||||
config USART6_RS485_DIR_POLARITY
|
||||
int "USART6 RS-485 DIR pin polarity"
|
||||
default 1
|
||||
range 0 1
|
||||
depends on USART6_RS485
|
||||
---help---
|
||||
Polarity of DIR pin for RS-485 on USART6. Set to state on DIR pin which
|
||||
enables TX (0 - low / nTXEN, 1 - high / TXEN).
|
||||
|
||||
config USART6_RXDMA
|
||||
bool "USART6 Rx DMA"
|
||||
default n
|
||||
|
@ -1882,6 +1993,8 @@ config SERIAL_TERMIOS
|
|||
If this is not defined, then the terminal settings (baud, parity, etc).
|
||||
are not configurable at runtime; serial streams cannot be flushed, etc..
|
||||
|
||||
endmenu
|
||||
|
||||
menu "SPI Configuration"
|
||||
depends on STM32_SPI
|
||||
|
||||
|
|
|
@ -67,6 +67,14 @@
|
|||
# define STM32_CONSOLE_2STOP CONFIG_USART1_2STOP
|
||||
# define STM32_CONSOLE_TX GPIO_USART1_TX
|
||||
# define STM32_CONSOLE_RX GPIO_USART1_RX
|
||||
# ifdef CONFIG_USART1_RS485
|
||||
# define STM32_CONSOLE_RS485_DIR GPIO_USART1_RS485_DIR
|
||||
# if (CONFIG_USART1_RS485_DIR_POLARITY == 0)
|
||||
# define STM32_CONSOLE_RS485_DIR_POLARITY false
|
||||
# else
|
||||
# define STM32_CONSOLE_RS485_DIR_POLARITY true
|
||||
# endif
|
||||
# endif
|
||||
#elif defined(CONFIG_USART2_SERIAL_CONSOLE)
|
||||
# define STM32_CONSOLE_BASE STM32_USART2_BASE
|
||||
# define STM32_APBCLOCK STM32_PCLK1_FREQUENCY
|
||||
|
@ -76,6 +84,14 @@
|
|||
# define STM32_CONSOLE_2STOP CONFIG_USART2_2STOP
|
||||
# define STM32_CONSOLE_TX GPIO_USART2_TX
|
||||
# define STM32_CONSOLE_RX GPIO_USART2_RX
|
||||
# ifdef CONFIG_USART2_RS485
|
||||
# define STM32_CONSOLE_RS485_DIR GPIO_USART2_RS485_DIR
|
||||
# if (CONFIG_USART2_RS485_DIR_POLARITY == 0)
|
||||
# define STM32_CONSOLE_RS485_DIR_POLARITY false
|
||||
# else
|
||||
# define STM32_CONSOLE_RS485_DIR_POLARITY true
|
||||
# endif
|
||||
# endif
|
||||
#elif defined(CONFIG_USART3_SERIAL_CONSOLE)
|
||||
# define STM32_CONSOLE_BASE STM32_USART3_BASE
|
||||
# define STM32_APBCLOCK STM32_PCLK1_FREQUENCY
|
||||
|
@ -85,6 +101,14 @@
|
|||
# define STM32_CONSOLE_2STOP CONFIG_USART3_2STOP
|
||||
# define STM32_CONSOLE_TX GPIO_USART3_TX
|
||||
# define STM32_CONSOLE_RX GPIO_USART3_RX
|
||||
# ifdef CONFIG_USART3_RS485
|
||||
# define STM32_CONSOLE_RS485_DIR GPIO_USART3_RS485_DIR
|
||||
# if (CONFIG_USART3_RS485_DIR_POLARITY == 0)
|
||||
# define STM32_CONSOLE_RS485_DIR_POLARITY false
|
||||
# else
|
||||
# define STM32_CONSOLE_RS485_DIR_POLARITY true
|
||||
# endif
|
||||
# endif
|
||||
#elif defined(CONFIG_UART4_SERIAL_CONSOLE)
|
||||
# define STM32_CONSOLE_BASE STM32_UART4_BASE
|
||||
# define STM32_APBCLOCK STM32_PCLK1_FREQUENCY
|
||||
|
@ -94,6 +118,14 @@
|
|||
# define STM32_CONSOLE_2STOP CONFIG_UART4_2STOP
|
||||
# define STM32_CONSOLE_TX GPIO_UART4_TX
|
||||
# define STM32_CONSOLE_RX GPIO_UART4_RX
|
||||
# ifdef CONFIG_UART4_RS485
|
||||
# define STM32_CONSOLE_RS485_DIR GPIO_UART4_RS485_DIR
|
||||
# if (CONFIG_UART4_RS485_DIR_POLARITY == 0)
|
||||
# define STM32_CONSOLE_RS485_DIR_POLARITY false
|
||||
# else
|
||||
# define STM32_CONSOLE_RS485_DIR_POLARITY true
|
||||
# endif
|
||||
# endif
|
||||
#elif defined(CONFIG_UART5_SERIAL_CONSOLE)
|
||||
# define STM32_CONSOLE_BASE STM32_UART5_BASE
|
||||
# define STM32_APBCLOCK STM32_PCLK1_FREQUENCY
|
||||
|
@ -103,6 +135,14 @@
|
|||
# define STM32_CONSOLE_2STOP CONFIG_UART5_2STOP
|
||||
# define STM32_CONSOLE_TX GPIO_UART5_TX
|
||||
# define STM32_CONSOLE_RX GPIO_UART5_RX
|
||||
# ifdef CONFIG_UART5_RS485
|
||||
# define STM32_CONSOLE_RS485_DIR GPIO_UART5_RS485_DIR
|
||||
# if (CONFIG_UART5_RS485_DIR_POLARITY == 0)
|
||||
# define STM32_CONSOLE_RS485_DIR_POLARITY false
|
||||
# else
|
||||
# define STM32_CONSOLE_RS485_DIR_POLARITY true
|
||||
# endif
|
||||
# endif
|
||||
#elif defined(CONFIG_USART6_SERIAL_CONSOLE)
|
||||
# define STM32_CONSOLE_BASE STM32_USART6_BASE
|
||||
# define STM32_APBCLOCK STM32_PCLK2_FREQUENCY
|
||||
|
@ -112,6 +152,14 @@
|
|||
# define STM32_CONSOLE_2STOP CONFIG_USART6_2STOP
|
||||
# define STM32_CONSOLE_TX GPIO_USART6_TX
|
||||
# define STM32_CONSOLE_RX GPIO_USART6_RX
|
||||
# ifdef CONFIG_USART6_RS485
|
||||
# define STM32_CONSOLE_RS485_DIR GPIO_USART6_RS485_DIR
|
||||
# if (CONFIG_USART6_RS485_DIR_POLARITY == 0)
|
||||
# define STM32_CONSOLE_RS485_DIR_POLARITY false
|
||||
# else
|
||||
# define STM32_CONSOLE_RS485_DIR_POLARITY true
|
||||
# endif
|
||||
# endif
|
||||
#endif
|
||||
|
||||
/* CR1 settings */
|
||||
|
@ -230,10 +278,19 @@ void up_lowputc(char ch)
|
|||
/* Wait until the TX data register is empty */
|
||||
|
||||
while ((getreg32(STM32_CONSOLE_BASE + STM32_USART_SR_OFFSET) & USART_SR_TXE) == 0);
|
||||
#if STM32_CONSOLE_RS485_DIR
|
||||
stm32_gpiowrite(STM32_CONSOLE_RS485_DIR, STM32_CONSOLE_RS485_DIR_POLARITY);
|
||||
#endif
|
||||
|
||||
/* Then send the character */
|
||||
|
||||
putreg32((uint32_t)ch, STM32_CONSOLE_BASE + STM32_USART_DR_OFFSET);
|
||||
|
||||
#if STM32_CONSOLE_RS485_DIR
|
||||
while ((getreg32(STM32_CONSOLE_BASE + STM32_USART_SR_OFFSET) & USART_SR_TC) == 0);
|
||||
stm32_gpiowrite(STM32_CONSOLE_RS485_DIR, !STM32_CONSOLE_RS485_DIR_POLARITY);
|
||||
#endif
|
||||
|
||||
#endif
|
||||
}
|
||||
|
||||
|
@ -328,7 +385,14 @@ void stm32_lowsetup(void)
|
|||
|
||||
#ifdef STM32_CONSOLE_TX
|
||||
stm32_configgpio(STM32_CONSOLE_TX);
|
||||
stm32_configgpio(STM32_CONSOLE_TX);
|
||||
#endif
|
||||
#ifdef STM32_CONSOLE_RX
|
||||
stm32_configgpio(STM32_CONSOLE_RX);
|
||||
#endif
|
||||
|
||||
#if STM32_CONSOLE_RS485_DIR
|
||||
stm32_configgpio(STM32_CONSOLE_RS485_DIR);
|
||||
stm32_gpiowrite(STM32_CONSOLE_RS485_DIR, !STM32_CONSOLE_RS485_DIR_POLARITY);
|
||||
#endif
|
||||
|
||||
/* Enable and configure the selected console device */
|
||||
|
@ -382,7 +446,14 @@ void stm32_lowsetup(void)
|
|||
|
||||
#ifdef STM32_CONSOLE_TX
|
||||
stm32_configgpio(STM32_CONSOLE_TX);
|
||||
stm32_configgpio(STM32_CONSOLE_TX);
|
||||
#endif
|
||||
#ifdef STM32_CONSOLE_RX
|
||||
stm32_configgpio(STM32_CONSOLE_RX);
|
||||
#endif
|
||||
|
||||
#if STM32_CONSOLE_RS485_DIR
|
||||
stm32_configgpio(STM32_CONSOLE_RS485_DIR);
|
||||
stm32_gpiowrite(STM32_CONSOLE_RS485_DIR, !STM32_CONSOLE_RS485_DIR_POLARITY);
|
||||
#endif
|
||||
|
||||
/* Enable and configure the selected console device */
|
||||
|
|
|
@ -96,6 +96,19 @@
|
|||
# endif
|
||||
# endif
|
||||
|
||||
/* Currently RS-485 support cannot be enabled when RXDMA is in use due to lack
|
||||
* of testing - RS-485 support was developed on STM32F1x
|
||||
*/
|
||||
|
||||
# if (defined(CONFIG_USART1_RXDMA) && defined(CONFIG_USART1_RS485)) || \
|
||||
(defined(CONFIG_USART2_RXDMA) && defined(CONFIG_USART2_RS485)) || \
|
||||
(defined(CONFIG_USART3_RXDMA) && defined(CONFIG_USART3_RS485)) || \
|
||||
(defined(CONFIG_UART4_RXDMA) && defined(CONFIG_UART4_RS485)) || \
|
||||
(defined(CONFIG_UART5_RXDMA) && defined(CONFIG_UART5_RS485)) || \
|
||||
(defined(CONFIG_USART6_RXDMA) && defined(CONFIG_USART6_RS485)) \
|
||||
# error "RXDMA and RS-485 cannot be enabled at the same time for the same U[S]ART"
|
||||
# endif
|
||||
|
||||
/* For the F4, there are alternate DMA channels for USART1 and 6.
|
||||
* Logic in the board.h file make the DMA channel selection by defining
|
||||
* the following in the board.h file.
|
||||
|
@ -215,6 +228,11 @@ struct up_dev_s
|
|||
uint32_t rxdmanext; /* Next byte in the DMA buffer to be read */
|
||||
char *const rxfifo; /* Receive DMA buffer */
|
||||
#endif
|
||||
|
||||
#ifdef HAVE_RS485
|
||||
const uint32_t rs485_dir_gpio; /* U[S]ART RS-485 DIR GPIO pin configuration */
|
||||
const bool rs485_dir_polarity; /* U[S]ART RS-485 DIR pin state for TX enabled */
|
||||
#endif
|
||||
};
|
||||
|
||||
/****************************************************************************
|
||||
|
@ -409,6 +427,15 @@ static struct up_dev_s g_usart1priv =
|
|||
.rxfifo = g_usart1rxfifo,
|
||||
#endif
|
||||
.vector = up_interrupt_usart1,
|
||||
|
||||
#ifdef CONFIG_USART1_RS485
|
||||
.rs485_dir_gpio = GPIO_USART1_RS485_DIR,
|
||||
# if (CONFIG_USART1_RS485_DIR_POLARITY == 0)
|
||||
.rs485_dir_polarity = false,
|
||||
# else
|
||||
.rs485_dir_polarity = true,
|
||||
# endif
|
||||
#endif
|
||||
};
|
||||
#endif
|
||||
|
||||
|
@ -460,6 +487,15 @@ static struct up_dev_s g_usart2priv =
|
|||
.rxfifo = g_usart2rxfifo,
|
||||
#endif
|
||||
.vector = up_interrupt_usart2,
|
||||
|
||||
#ifdef CONFIG_USART2_RS485
|
||||
.rs485_dir_gpio = GPIO_USART2_RS485_DIR,
|
||||
# if (CONFIG_USART2_RS485_DIR_POLARITY == 0)
|
||||
.rs485_dir_polarity = false,
|
||||
# else
|
||||
.rs485_dir_polarity = true,
|
||||
# endif
|
||||
#endif
|
||||
};
|
||||
#endif
|
||||
|
||||
|
@ -511,6 +547,15 @@ static struct up_dev_s g_usart3priv =
|
|||
.rxfifo = g_usart3rxfifo,
|
||||
#endif
|
||||
.vector = up_interrupt_usart3,
|
||||
|
||||
#ifdef CONFIG_USART3_RS485
|
||||
.rs485_dir_gpio = GPIO_USART3_RS485_DIR,
|
||||
# if (CONFIG_USART3_RS485_DIR_POLARITY == 0)
|
||||
.rs485_dir_polarity = false,
|
||||
# else
|
||||
.rs485_dir_polarity = true,
|
||||
# endif
|
||||
#endif
|
||||
};
|
||||
#endif
|
||||
|
||||
|
@ -562,6 +607,15 @@ static struct up_dev_s g_uart4priv =
|
|||
.rxfifo = g_uart4rxfifo,
|
||||
#endif
|
||||
.vector = up_interrupt_uart4,
|
||||
|
||||
#ifdef CONFIG_UART4_RS485
|
||||
.rs485_dir_gpio = GPIO_UART4_RS485_DIR,
|
||||
# if (CONFIG_UART4_RS485_DIR_POLARITY == 0)
|
||||
.rs485_dir_polarity = false,
|
||||
# else
|
||||
.rs485_dir_polarity = true,
|
||||
# endif
|
||||
#endif
|
||||
};
|
||||
#endif
|
||||
|
||||
|
@ -613,6 +667,15 @@ static struct up_dev_s g_uart5priv =
|
|||
.rxfifo = g_uart5rxfifo,
|
||||
#endif
|
||||
.vector = up_interrupt_uart5,
|
||||
|
||||
#ifdef CONFIG_UART5_RS485
|
||||
.rs485_dir_gpio = GPIO_UART5_RS485_DIR,
|
||||
# if (CONFIG_UART5_RS485_DIR_POLARITY == 0)
|
||||
.rs485_dir_polarity = false,
|
||||
# else
|
||||
.rs485_dir_polarity = true,
|
||||
# endif
|
||||
#endif
|
||||
};
|
||||
#endif
|
||||
|
||||
|
@ -664,6 +727,15 @@ static struct up_dev_s g_usart6priv =
|
|||
.rxfifo = g_usart6rxfifo,
|
||||
#endif
|
||||
.vector = up_interrupt_usart6,
|
||||
|
||||
#ifdef CONFIG_USART6_RS485
|
||||
.rs485_dir_gpio = GPIO_USART6_RS485_DIR,
|
||||
# if (CONFIG_USART6_RS485_DIR_POLARITY == 0)
|
||||
.rs485_dir_polarity = false,
|
||||
# else
|
||||
.rs485_dir_polarity = true,
|
||||
# endif
|
||||
#endif
|
||||
};
|
||||
#endif
|
||||
|
||||
|
@ -736,8 +808,8 @@ static void up_restoreusartint(struct up_dev_s *priv, uint16_t ie)
|
|||
/* And restore the interrupt state (see the interrupt enable/usage table above) */
|
||||
|
||||
cr = up_serialin(priv, STM32_USART_CR1_OFFSET);
|
||||
cr &= ~(USART_CR1_RXNEIE|USART_CR1_TXEIE|USART_CR1_PEIE);
|
||||
cr |= (ie & (USART_CR1_RXNEIE|USART_CR1_TXEIE|USART_CR1_PEIE));
|
||||
cr &= ~(USART_CR1_USED_INTS);
|
||||
cr |= (ie & (USART_CR1_USED_INTS));
|
||||
up_serialout(priv, STM32_USART_CR1_OFFSET, cr);
|
||||
|
||||
cr = up_serialin(priv, STM32_USART_CR3_OFFSET);
|
||||
|
@ -764,7 +836,7 @@ static inline void up_disableusartint(struct up_dev_s *priv, uint16_t *ie)
|
|||
* USART_CR1_IDLEIE 4 USART_SR_IDLE Idle Line Detected (not used)
|
||||
* USART_CR1_RXNEIE 5 USART_SR_RXNE Received Data Ready to be Read
|
||||
* " " USART_SR_ORE Overrun Error Detected
|
||||
* USART_CR1_TCIE 6 USART_SR_TC Transmission Complete (not used)
|
||||
* USART_CR1_TCIE 6 USART_SR_TC Transmission Complete (used only for RS-485)
|
||||
* USART_CR1_TXEIE 7 USART_SR_TXE Transmit Data Register Empty
|
||||
* USART_CR1_PEIE 8 USART_SR_PE Parity Error
|
||||
*
|
||||
|
@ -783,7 +855,7 @@ static inline void up_disableusartint(struct up_dev_s *priv, uint16_t *ie)
|
|||
* overlap. This logic would fail if we needed the break interrupt!
|
||||
*/
|
||||
|
||||
*ie = (cr1 & (USART_CR1_RXNEIE|USART_CR1_TXEIE|USART_CR1_PEIE)) | (cr3 & USART_CR3_EIE);
|
||||
*ie = (cr1 & (USART_CR1_USED_INTS)) | (cr3 & USART_CR3_EIE);
|
||||
}
|
||||
|
||||
/* Disable all interrupts */
|
||||
|
@ -893,6 +965,14 @@ static int up_setup(struct uart_dev_s *dev)
|
|||
stm32_configgpio(priv->rts_gpio);
|
||||
}
|
||||
|
||||
#if HAVE_RS485
|
||||
if (priv->rs485_dir_gpio != 0)
|
||||
{
|
||||
stm32_configgpio(priv->rs485_dir_gpio);
|
||||
stm32_gpiowrite(priv->rs485_dir_gpio, !priv->rs485_dir_polarity);
|
||||
}
|
||||
#endif
|
||||
|
||||
/* Configure CR2 */
|
||||
/* Clear STOP, CLKEN, CPOL, CPHA, LBCL, and interrupt enable bits */
|
||||
|
||||
|
@ -1174,7 +1254,7 @@ static int up_interrupt_common(struct up_dev_s *priv)
|
|||
* USART_CR1_IDLEIE 4 USART_SR_IDLE Idle Line Detected (not used)
|
||||
* USART_CR1_RXNEIE 5 USART_SR_RXNE Received Data Ready to be Read
|
||||
* " " USART_SR_ORE Overrun Error Detected
|
||||
* USART_CR1_TCIE 6 USART_SR_TC Transmission Complete (not used)
|
||||
* USART_CR1_TCIE 6 USART_SR_TC Transmission Complete (used only for RS-485)
|
||||
* USART_CR1_TXEIE 7 USART_SR_TXE Transmit Data Register Empty
|
||||
* USART_CR1_PEIE 8 USART_SR_PE Parity Error
|
||||
*
|
||||
|
@ -1189,6 +1269,21 @@ static int up_interrupt_common(struct up_dev_s *priv)
|
|||
* being used.
|
||||
*/
|
||||
|
||||
#ifdef HAVE_RS485
|
||||
/* Transmission of whole buffer is over - TC is set, TXEIE is cleared.
|
||||
* Note - this should be first, to have the most recent TC bit value from
|
||||
* SR register - sending data affects TC, but without refresh we will not
|
||||
* know that...
|
||||
*/
|
||||
|
||||
if ((priv->sr & USART_SR_TC) != 0 && (priv->ie & USART_CR1_TCIE) != 0 &&
|
||||
(priv->ie & USART_CR1_TXEIE) == 0)
|
||||
{
|
||||
stm32_gpiowrite(priv->rs485_dir_gpio, !priv->rs485_dir_polarity);
|
||||
up_restoreusartint(priv, priv->ie & ~USART_CR1_TCIE);
|
||||
}
|
||||
#endif
|
||||
|
||||
/* Handle incoming, receive bytes. */
|
||||
|
||||
if ((priv->sr & USART_SR_RXNE) != 0 && (priv->ie & USART_CR1_RXNEIE) != 0)
|
||||
|
@ -1222,13 +1317,14 @@ static int up_interrupt_common(struct up_dev_s *priv)
|
|||
|
||||
if ((priv->sr & USART_SR_TXE) != 0 && (priv->ie & USART_CR1_TXEIE) != 0)
|
||||
{
|
||||
/* Transmit data regiser empty ... process outgoing bytes */
|
||||
/* Transmit data register empty ... process outgoing bytes */
|
||||
|
||||
uart_xmitchars(&priv->dev);
|
||||
handled = true;
|
||||
}
|
||||
}
|
||||
return OK;
|
||||
|
||||
return OK;
|
||||
}
|
||||
|
||||
/****************************************************************************
|
||||
|
@ -1527,6 +1623,10 @@ static bool up_dma_rxavailable(struct uart_dev_s *dev)
|
|||
static void up_send(struct uart_dev_s *dev, int ch)
|
||||
{
|
||||
struct up_dev_s *priv = (struct up_dev_s*)dev->priv;
|
||||
#ifdef HAVE_RS485
|
||||
if (priv->rs485_dir_gpio != 0)
|
||||
stm32_gpiowrite(priv->rs485_dir_gpio, priv->rs485_dir_polarity);
|
||||
#endif
|
||||
up_serialout(priv, STM32_USART_DR_OFFSET, (uint32_t)ch);
|
||||
}
|
||||
|
||||
|
@ -1547,7 +1647,7 @@ static void up_txint(struct uart_dev_s *dev, bool enable)
|
|||
*
|
||||
* Enable Bit Status Meaning Usage
|
||||
* ------------------ --- --------------- ---------------------------- ----------
|
||||
* USART_CR1_TCIE 6 USART_SR_TC Transmission Complete (not used)
|
||||
* USART_CR1_TCIE 6 USART_SR_TC Transmission Complete (used only for RS-485)
|
||||
* USART_CR1_TXEIE 7 USART_SR_TXE Transmit Data Register Empty
|
||||
* USART_CR3_CTSIE 10 USART_SR_CTS CTS flag (not used)
|
||||
*/
|
||||
|
@ -1558,7 +1658,20 @@ static void up_txint(struct uart_dev_s *dev, bool enable)
|
|||
/* Set to receive an interrupt when the TX data register is empty */
|
||||
|
||||
#ifndef CONFIG_SUPPRESS_SERIAL_INTS
|
||||
up_restoreusartint(priv, priv->ie | USART_CR1_TXEIE);
|
||||
uint16_t ie = priv->ie | USART_CR1_TXEIE;
|
||||
|
||||
/* If RS-485 is supported on this U[S]ART, then also enable the
|
||||
* transmission complete interrupt.
|
||||
*/
|
||||
|
||||
# ifdef HAVE_RS485
|
||||
if (priv->rs485_dir_gpio != 0)
|
||||
{
|
||||
ie |= USART_CR1_TCIE;
|
||||
}
|
||||
# endif
|
||||
|
||||
up_restoreusartint(priv, ie);
|
||||
|
||||
/* Fake a TX interrupt here by just calling uart_xmitchars() with
|
||||
* interrupts disabled (note this may recurse).
|
||||
|
@ -1573,6 +1686,7 @@ static void up_txint(struct uart_dev_s *dev, bool enable)
|
|||
|
||||
up_restoreusartint(priv, priv->ie & ~USART_CR1_TXEIE);
|
||||
}
|
||||
|
||||
irqrestore(flags);
|
||||
}
|
||||
|
||||
|
|
|
@ -223,6 +223,20 @@
|
|||
# undef SERIAL_HAVE_ONLY_DMA
|
||||
#endif
|
||||
|
||||
/* Is RS-485 used? */
|
||||
|
||||
#if defined(CONFIG_USART1_RS485) || defined(CONFIG_USART2_RS485) || \
|
||||
defined(CONFIG_USART3_RS485) || defined(CONFIG_UART4_RS485) || \
|
||||
defined(CONFIG_UART5_RS485) || defined(CONFIG_USART6_RS485)
|
||||
# define HAVE_RS485 1
|
||||
#endif
|
||||
|
||||
#ifdef HAVE_RS485
|
||||
# define USART_CR1_USED_INTS (USART_CR1_RXNEIE | USART_CR1_TXEIE | USART_CR1_PEIE | USART_CR1_TCIE)
|
||||
#else
|
||||
# define USART_CR1_USED_INTS (USART_CR1_RXNEIE | USART_CR1_TXEIE | USART_CR1_PEIE)
|
||||
#endif
|
||||
|
||||
/************************************************************************************
|
||||
* Public Types
|
||||
************************************************************************************/
|
||||
|
|
|
@ -65,6 +65,12 @@
|
|||
# endif
|
||||
#endif
|
||||
|
||||
/* Can't support MMC/SD features if MMC/SD driver support is not selected */
|
||||
|
||||
#ifndef CONFIG_MMCSD
|
||||
# undef HAVE_MMCSD
|
||||
#endif
|
||||
|
||||
/* Can't support MMC/SD features if mountpoints are disabled */
|
||||
|
||||
#ifdef CONFIG_DISABLE_MOUNTPOINT
|
||||
|
|
Loading…
Reference in New Issue