Skip to content

Commit

Permalink
[BACKPORT] arch/arm/src/stm32f7/stm32_serial.c: This adds the ability…
Browse files Browse the repository at this point in the history
… to invert and swap RX/TX on STM32F7 UARTs. I added the TIOCGINVERT as well to reserve the IOCTL number, but did not implement it. This is the same as for TIOCGSINGLEWIRE.
  • Loading branch information
bkueng authored and dagar committed Jul 4, 2019
1 parent 423371c commit 54a0897
Show file tree
Hide file tree
Showing 3 changed files with 138 additions and 6 deletions.
16 changes: 16 additions & 0 deletions arch/arm/src/stm32f7/Kconfig
Original file line number Diff line number Diff line change
Expand Up @@ -1940,6 +1940,22 @@ config STM32F7_USART_SINGLEWIRE
Enable single wire UART support. The option enables support for the
TIOCSSINGLEWIRE ioctl in the STM32F7 serial driver.

config STM32F7_USART_INVERT
bool "Signal Invert Support"
default n
depends on STM32F7_USART
---help---
Enable signal inversion UART support. The option enables support for the
TIOCSINVERT ioctl in the STM32F7 serial driver.

config STM32F7_USART_SWAP
bool "Swap RX/TX pins support"
default n
depends on STM32F7_USART
---help---
Enable RX/TX pin swapping support. The option enables support for the
TIOCSSWAP ioctl in the STM32F7 serial driver.

if PM

config STM32F7_PM_SERIAL_ACTIVITY
Expand Down
113 changes: 107 additions & 6 deletions arch/arm/src/stm32f7/stm32_serial.c
Original file line number Diff line number Diff line change
Expand Up @@ -76,7 +76,9 @@
/****************************************************************************
* Pre-processor Definitions
****************************************************************************/

/* Some sanity checks *******************************************************/

/* Total number of possible serial devices */

#define STM32_NSERIAL (STM32F7_NUSART + STM32F7_NUART)
Expand Down Expand Up @@ -1260,12 +1262,13 @@ static void up_set_format(struct uart_dev_s *dev)

/* Get the original state of UE */

cr1 = up_serialin(priv, STM32_USART_CR1_OFFSET);
cr1 = up_serialin(priv, STM32_USART_CR1_OFFSET);
cr1_ue = cr1 & USART_CR1_UE;
cr1 &= ~USART_CR1_UE;
cr1 &= ~USART_CR1_UE;

/* Disable UE as the format bits and baud rate registers can not be
* updated while UE = 1 */
* updated while UE = 1
*/

up_serialout(priv, STM32_USART_CR1_OFFSET, cr1);

Expand Down Expand Up @@ -1356,7 +1359,7 @@ static void up_set_format(struct uart_dev_s *dev)

/* Configure STOP bits */

regval = up_serialin(priv, STM32_USART_CR2_OFFSET);
regval = up_serialin(priv, STM32_USART_CR2_OFFSET);
regval &= ~(USART_CR2_STOP_MASK);

if (priv->stopbits2)
Expand Down Expand Up @@ -1685,6 +1688,7 @@ static int up_setup(struct uart_dev_s *dev)
#endif

/* Configure CR2 */

/* Clear STOP, CLKEN, CPOL, CPHA, LBCL, and interrupt enable bits */

regval = up_serialin(priv, STM32_USART_CR2_OFFSET);
Expand All @@ -1701,6 +1705,7 @@ static int up_setup(struct uart_dev_s *dev)
up_serialout(priv, STM32_USART_CR2_OFFSET, regval);

/* Configure CR1 */

/* Clear TE, REm and all interrupt enable bits */

regval = up_serialin(priv, STM32_USART_CR1_OFFSET);
Expand All @@ -1709,6 +1714,7 @@ static int up_setup(struct uart_dev_s *dev)
up_serialout(priv, STM32_USART_CR1_OFFSET, regval);

/* Configure CR3 */

/* Clear CTSE, RTSE, and all interrupt enable bits */

regval = up_serialin(priv, STM32_USART_CR3_OFFSET);
Expand Down Expand Up @@ -2150,6 +2156,99 @@ static int up_ioctl(struct file *filep, int cmd, unsigned long arg)
break;
#endif

#ifdef CONFIG_STM32F7_USART_INVERT
case TIOCSINVERT:
{
uint32_t cr1;
uint32_t cr1_ue;
irqstate_t flags;

flags = enter_critical_section();

/* Get the original state of UE */

cr1 = up_serialin(priv, STM32_USART_CR1_OFFSET);
cr1_ue = cr1 & USART_CR1_UE;
cr1 &= ~USART_CR1_UE;

/* Disable UE, {R,T}XINV can only be written when UE=0 */

up_serialout(priv, STM32_USART_CR1_OFFSET, cr1);

/* Enable/disable signal inversion. */

uint32_t cr = up_serialin(priv, STM32_USART_CR2_OFFSET);

if (arg & SER_INVERT_ENABLED_RX)
{
cr |= USART_CR2_RXINV;
}
else
{
cr &= ~USART_CR2_RXINV;
}

if (arg & SER_INVERT_ENABLED_TX)
{
cr |= USART_CR2_TXINV;
}
else
{
cr &= ~USART_CR2_TXINV;
}

up_serialout(priv, STM32_USART_CR2_OFFSET, cr);

/* Re-enable UE if appropriate */

up_serialout(priv, STM32_USART_CR1_OFFSET, cr1 | cr1_ue);
leave_critical_section(flags);
}
break;
#endif

#ifdef CONFIG_STM32F7_USART_SWAP
case TIOCSSWAP:
{
uint32_t cr1;
uint32_t cr1_ue;
irqstate_t flags;

flags = enter_critical_section();

/* Get the original state of UE */

cr1 = up_serialin(priv, STM32_USART_CR1_OFFSET);
cr1_ue = cr1 & USART_CR1_UE;
cr1 &= ~USART_CR1_UE;

/* Disable UE, SWAP can only be written when UE=0 */

up_serialout(priv, STM32_USART_CR1_OFFSET, cr1);

/* Enable/disable Swap mode. */

uint32_t cr = up_serialin(priv, STM32_USART_CR2_OFFSET);

if (arg == SER_SWAP_ENABLED)
{
cr |= USART_CR2_SWAP;
}
else
{
cr &= ~USART_CR2_SWAP;
}

up_serialout(priv, STM32_USART_CR2_OFFSET, cr);

/* Re-enable UE if appropriate */

up_serialout(priv, STM32_USART_CR1_OFFSET, cr1 | cr1_ue);
leave_critical_section(flags);
}
break;
#endif

#ifdef CONFIG_SERIAL_TERMIOS
case TCGETS:
{
Expand Down Expand Up @@ -2260,9 +2359,10 @@ static int up_ioctl(struct file *filep, int cmd, unsigned long arg)

up_txint(dev, false);

/* Configure TX as a GPIO output pin and Send a break signal*/
/* Configure TX as a GPIO output pin and Send a break signal */

tx_break = GPIO_OUTPUT | (~(GPIO_MODE_MASK|GPIO_OUTPUT_SET) & priv->tx_gpio);
tx_break = GPIO_OUTPUT |
(~(GPIO_MODE_MASK | GPIO_OUTPUT_SET) & priv->tx_gpio);
stm32_configgpio(tx_break);

leave_critical_section(flags);
Expand Down Expand Up @@ -3000,6 +3100,7 @@ static int up_pm_prepare(struct pm_callback_s *cb, int domain,

default:
/* Should not get here */

break;
}

Expand Down
15 changes: 15 additions & 0 deletions include/nuttx/serial/tioctl.h
Original file line number Diff line number Diff line change
Expand Up @@ -190,6 +190,21 @@

#define TIOCSERGSTRUCT _TIOC(0x0032) /* Get device TTY structure */

/* Inversion Support */

#define TIOCSINVERT _TIOC(0x0033) /* Set Singal Inversion */
#define TIOCGINVERT _TIOC(0x0034) /* Get Singal Inversion */

#define SER_INVERT_ENABLED_RX (1 << 0) /* Enable/disable signal inversion for RX */
#define SER_INVERT_ENABLED_TX (1 << 1) /* Enable/disable signal inversion for TX */

/* RX/TX Swap Support */

#define TIOCSSWAP _TIOC(0x0035) /* Set RX/TX Swap */
#define TIOCGSWAP _TIOC(0x0036) /* Get RX/TX Swap */

#define SER_SWAP_ENABLED (1 << 0) /* Enable/disable RX/TX swap */

/********************************************************************************************
* Public Type Definitions
********************************************************************************************/
Expand Down

0 comments on commit 54a0897

Please sign in to comment.