@ -185,11 +185,15 @@ struct up_dev_s
@@ -185,11 +185,15 @@ struct up_dev_s
uint8_t parity ; /* 0=none, 1=odd, 2=even */
uint8_t bits ; /* Number of bits (7 or 8) */
bool stopbits2 ; /* True: Configure with 2 stop bits instead of 1 */
bool iflow ; /* input flow control (RTS) enabled */
bool oflow ; /* output flow control (CTS) enabled */
uint32_t baud ; /* Configured baud */
# else
const uint8_t parity ; /* 0=none, 1=odd, 2=even */
const uint8_t bits ; /* Number of bits (7 or 8) */
const bool stopbits2 ; /* True: Configure with 2 stop bits instead of 1 */
const bool iflow ; /* input flow control (RTS) enabled */
const bool oflow ; /* output flow control (CTS) enabled */
const uint32_t baud ; /* Configured baud */
# endif
@ -221,7 +225,7 @@ struct up_dev_s
@@ -221,7 +225,7 @@ struct up_dev_s
* Private Function Prototypes
* * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * */
static void up_setspeed ( struct uart_dev_s * dev ) ;
static void up_set_format ( struct uart_dev_s * dev ) ;
static int up_setup ( struct uart_dev_s * dev ) ;
static void up_shutdown ( struct uart_dev_s * dev ) ;
static int up_attach ( struct uart_dev_s * dev ) ;
@ -393,6 +397,8 @@ static struct up_dev_s g_usart1priv =
@@ -393,6 +397,8 @@ static struct up_dev_s g_usart1priv =
. parity = CONFIG_USART1_PARITY ,
. bits = CONFIG_USART1_BITS ,
. stopbits2 = CONFIG_USART1_2STOP ,
. iflow = false ,
. oflow = false ,
. baud = CONFIG_USART1_BAUD ,
. apbclock = STM32_PCLK2_FREQUENCY ,
. usartbase = STM32_USART1_BASE ,
@ -444,6 +450,8 @@ static struct up_dev_s g_usart2priv =
@@ -444,6 +450,8 @@ static struct up_dev_s g_usart2priv =
. parity = CONFIG_USART2_PARITY ,
. bits = CONFIG_USART2_BITS ,
. stopbits2 = CONFIG_USART2_2STOP ,
. iflow = false ,
. oflow = false ,
. baud = CONFIG_USART2_BAUD ,
. apbclock = STM32_PCLK1_FREQUENCY ,
. usartbase = STM32_USART2_BASE ,
@ -495,6 +503,8 @@ static struct up_dev_s g_usart3priv =
@@ -495,6 +503,8 @@ static struct up_dev_s g_usart3priv =
. parity = CONFIG_USART3_PARITY ,
. bits = CONFIG_USART3_BITS ,
. stopbits2 = CONFIG_USART3_2STOP ,
. iflow = false ,
. oflow = false ,
. baud = CONFIG_USART3_BAUD ,
. apbclock = STM32_PCLK1_FREQUENCY ,
. usartbase = STM32_USART3_BASE ,
@ -546,17 +556,15 @@ static struct up_dev_s g_uart4priv =
@@ -546,17 +556,15 @@ static struct up_dev_s g_uart4priv =
. parity = CONFIG_UART4_PARITY ,
. bits = CONFIG_UART4_BITS ,
. stopbits2 = CONFIG_UART4_2STOP ,
. iflow = false ,
. oflow = false ,
. baud = CONFIG_UART4_BAUD ,
. apbclock = STM32_PCLK1_FREQUENCY ,
. usartbase = STM32_UART4_BASE ,
. tx_gpio = GPIO_UART4_TX ,
. rx_gpio = GPIO_UART4_RX ,
# ifdef GPIO_UART4_CTS
. cts_gpio = GPIO_UART4_CTS ,
# endif
# ifdef GPIO_UART4_RTS
. rts_gpio = GPIO_UART4_RTS ,
# endif
. cts_gpio = 0 , /* flow control not supported on this port */
. rts_gpio = 0 , /* flow control not supported on this port */
# ifdef CONFIG_UART4_RXDMA
. rxdma_channel = DMAMAP_UART4_RX ,
. rxfifo = g_uart4rxfifo ,
@ -597,17 +605,15 @@ static struct up_dev_s g_uart5priv =
@@ -597,17 +605,15 @@ static struct up_dev_s g_uart5priv =
. parity = CONFIG_UART5_PARITY ,
. bits = CONFIG_UART5_BITS ,
. stopbits2 = CONFIG_UART5_2STOP ,
. iflow = false ,
. oflow = false ,
. baud = CONFIG_UART5_BAUD ,
. apbclock = STM32_PCLK1_FREQUENCY ,
. usartbase = STM32_UART5_BASE ,
. tx_gpio = GPIO_UART5_TX ,
. rx_gpio = GPIO_UART5_RX ,
# ifdef GPIO_UART5_CTS
. cts_gpio = GPIO_UART5_CTS ,
# endif
# ifdef GPIO_UART5_RTS
. rts_gpio = GPIO_UART5_RTS ,
# endif
. cts_gpio = 0 , /* flow control not supported on this port */
. rts_gpio = 0 , /* flow control not supported on this port */
# ifdef CONFIG_UART5_RXDMA
. rxdma_channel = DMAMAP_UART5_RX ,
. rxfifo = g_uart5rxfifo ,
@ -648,6 +654,8 @@ static struct up_dev_s g_usart6priv =
@@ -648,6 +654,8 @@ static struct up_dev_s g_usart6priv =
. parity = CONFIG_USART6_PARITY ,
. bits = CONFIG_USART6_BITS ,
. stopbits2 = CONFIG_USART6_2STOP ,
. iflow = false ,
. oflow = false ,
. baud = CONFIG_USART6_BAUD ,
. apbclock = STM32_PCLK2_FREQUENCY ,
. usartbase = STM32_USART6_BASE ,
@ -812,21 +820,22 @@ static int up_dma_nextrx(struct up_dev_s *priv)
@@ -812,21 +820,22 @@ static int up_dma_nextrx(struct up_dev_s *priv)
# endif
/****************************************************************************
* Name : up_setspeed
* Name : up_set_format
*
* Description :
* Set the serial line speed .
* Set the serial line format and speed .
*
* * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * * */
# ifndef CONFIG_SUPPRESS_UART_CONFIG
static void up_setspeed ( struct uart_dev_s * dev )
static void up_set_format ( struct uart_dev_s * dev )
{
struct up_dev_s * priv = ( struct up_dev_s * ) dev - > priv ;
uint32_t usartdiv32 ;
uint32_t mantissa ;
uint32_t fraction ;
uint32_t brr ;
uint32_t regval ;
/* Configure the USART Baud Rate. The baud rate for the receiver and
* transmitter ( Rx and Tx ) are both set to the same value as programmed
@ -844,20 +853,64 @@ static void up_setspeed(struct uart_dev_s *dev)
@@ -844,20 +853,64 @@ static void up_setspeed(struct uart_dev_s *dev)
* usartdiv32 = 32 * usartdiv = fCK / ( baud / 2 )
*/
usartdiv32 = priv - > apbclock / ( priv - > baud > > 1 ) ;
usartdiv32 = priv - > apbclock / ( priv - > baud > > 1 ) ;
/* The mantissa part is then */
mantissa = usartdiv32 > > 5 ;
brr = mantissa < < USART_BRR_MANT_SHIFT ;
/* The fractional remainder (with rounding) */
fraction = ( usartdiv32 - ( mantissa < < 5 ) + 1 ) > > 1 ;
brr | = fraction < < USART_BRR_FRAC_SHIFT ;
up_serialout ( priv , STM32_USART_BRR_OFFSET , brr ) ;
/* Configure parity mode */
/* The mantissa part is then */
regval = up_serialin ( priv , STM32_USART_CR1_OFFSET ) ;
regval & = ~ ( USART_CR1_PCE | USART_CR1_PS ) ;
mantissa = usartdiv32 > > 5 ;
brr = mantissa < < USART_BRR_MANT_SHIFT ;
if ( priv - > parity = = 1 ) /* Odd parity */
{
regval | = ( USART_CR1_PCE | USART_CR1_PS ) ;
}
else if ( priv - > parity = = 2 ) /* Even parity */
{
regval | = USART_CR1_PCE ;
}
/* The fractional remainder (with rounding) */
up_serialout ( priv , STM32_USART_CR1_OFFSET , regval ) ;
/* Configure STOP bits */
regval = up_serialin ( priv , STM32_USART_CR2_OFFSET ) ;
regval & = ~ ( USART_CR2_STOP_MASK ) ;
if ( priv - > stopbits2 )
{
regval | = USART_CR2_STOP2 ;
}
up_serialout ( priv , STM32_USART_CR2_OFFSET , regval ) ;
/* Configure hardware flow control */
regval = up_serialin ( priv , STM32_USART_CR3_OFFSET ) ;
regval & = ~ ( USART_CR3_CTSE | USART_CR3_RTSE ) ;
if ( priv - > iflow & & ( priv - > rts_gpio ! = 0 ) )
{
regval | = USART_CR3_RTSE ;
}
if ( priv - > oflow & & ( priv - > cts_gpio ! = 0 ) )
{
regval | = USART_CR3_CTSE ;
}
up_serialout ( priv , STM32_USART_CR3_OFFSET , regval ) ;
fraction = ( usartdiv32 - ( mantissa < < 5 ) + 1 ) > > 1 ;
brr | = fraction < < USART_BRR_FRAC_SHIFT ;
up_serialout ( priv , STM32_USART_BRR_OFFSET , brr ) ;
}
# endif
# endif /* CONFIG_SUPPRESS_UART_CONFIG */
/****************************************************************************
* Name : up_setup
@ -894,43 +947,28 @@ static int up_setup(struct uart_dev_s *dev)
@@ -894,43 +947,28 @@ static int up_setup(struct uart_dev_s *dev)
}
/* Configure CR2 */
/* Clear STOP, CLKEN, CPOL, CPHA, LBCL, and interrupt enable bits */
/* Clear CLKEN, CPOL, CPHA, LBCL, and interrupt enable bits */
regval = up_serialin ( priv , STM32_USART_CR2_OFFSET ) ;
regval & = ~ ( USART_CR2_STOP_MASK | USART_CR2_ CLKEN | USART_CR2_CPOL |
regval & = ~ ( USART_CR2_CLKEN | USART_CR2_CPOL |
USART_CR2_CPHA | USART_CR2_LBCL | USART_CR2_LBDIE ) ;
/* Configure STOP bits */
if ( priv - > stopbits2 )
{
regval | = USART_CR2_STOP2 ;
}
up_serialout ( priv , STM32_USART_CR2_OFFSET , regval ) ;
/* Configure CR1 */
/* Clear M, PCE, PS, TE, REm and all interrupt enable bits */
/* Clear M, TE, REm and all interrupt enable bits */
regval = up_serialin ( priv , STM32_USART_CR1_OFFSET ) ;
regval & = ~ ( USART_CR1_M | USART_CR1_PCE | USART_CR1_PS | USART_CR1_ TE |
regval & = ~ ( USART_CR1_M | USART_CR1_TE |
USART_CR1_RE | USART_CR1_ALLINTS ) ;
/* Configure word length and parity mode */
/* Configure word length */
if ( priv - > bits = = 9 ) /* Default: 1 start, 8 data, n stop */
{
regval | = USART_CR1_M ; /* 1 start, 9 data, n stop */
}
if ( priv - > parity = = 1 ) /* Odd parity */
{
regval | = ( USART_CR1_PCE | USART_CR1_PS ) ;
}
else if ( priv - > parity = = 2 ) /* Even parity */
{
regval | = USART_CR1_PCE ;
}
up_serialout ( priv , STM32_USART_CR1_OFFSET , regval ) ;
/* Configure CR3 */
@ -943,16 +981,17 @@ static int up_setup(struct uart_dev_s *dev)
@@ -943,16 +981,17 @@ static int up_setup(struct uart_dev_s *dev)
up_serialout ( priv , STM32_USART_CR3_OFFSET , regval ) ;
/* Configure the USART Baud Rate . */
/* Configure the USART line format and speed . */
up_setspeed ( dev ) ;
up_set_format ( dev ) ;
/* Enable Rx, Tx, and the USART */
regval = up_serialin ( priv , STM32_USART_CR1_OFFSET ) ;
regval | = ( USART_CR1_UE | USART_CR1_TE | USART_CR1_RE ) ;
up_serialout ( priv , STM32_USART_CR1_OFFSET , regval ) ;
# endif
# endif /* CONFIG_SUPPRESS_UART_CONFIG */
/* Set up the cached interrupt enables value */
@ -1279,12 +1318,21 @@ static int up_ioctl(struct file *filep, int cmd, unsigned long arg)
@@ -1279,12 +1318,21 @@ static int up_ioctl(struct file *filep, int cmd, unsigned long arg)
break ;
}
/* TODO: Other termios fields are not yet returned.
* Note that only cfsetospeed is not necessary because we have
* knowledge that only one speed is supported .
cfsetispeed ( termiosp , priv - > baud ) ;
/* Note that since we only support 8/9 bit modes and
* there is no way to report 9 - bit mode , we always claim 8.
*/
cfsetispeed ( termiosp , priv - > baud ) ;
termiosp - > c_cflag =
( ( priv - > parity ! = 0 ) ? PARENB : 0 ) |
( ( priv - > parity = = 1 ) ? PARODD : 0 ) |
( ( priv - > stopbits2 ) ? CSTOPB : 0 ) |
( ( priv - > oflow ) ? CCTS_OFLOW : 0 ) |
( ( priv - > iflow ) ? CRTS_IFLOW : 0 ) |
CS8 ;
/* TODO: CCTS_IFLOW, CCTS_OFLOW */
}
break ;
@ -1298,16 +1346,48 @@ static int up_ioctl(struct file *filep, int cmd, unsigned long arg)
@@ -1298,16 +1346,48 @@ static int up_ioctl(struct file *filep, int cmd, unsigned long arg)
break ;
}
/* TODO: Handle other termios settings.
* Note that only cfgetispeed is used besued we have knowledge
/* Perform some sanity checks before accepting any changes */
if ( ( ( termiosp - > c_cflag & CSIZE ) ! = CS8 ) | |
( ( termiosp - > c_cflag & CCTS_OFLOW ) & & ( priv - > cts_gpio = = 0 ) ) | |
( ( termiosp - > c_cflag & CRTS_IFLOW ) & & ( priv - > rts_gpio = = 0 ) ) )
{
ret = - EINVAL ;
break ;
}
if ( termiosp - > c_cflag & PARENB )
{
priv - > parity = ( termiosp - > c_cflag & PARODD ) ? 1 : 2 ;
}
else
{
priv - > parity = 0 ;
}
priv - > stopbits2 = ( termiosp - > c_cflag & CSTOPB ) ! = 0 ;
priv - > oflow = ( termiosp - > c_cflag & CCTS_OFLOW ) ! = 0 ;
priv - > iflow = ( termiosp - > c_cflag & CRTS_IFLOW ) ! = 0 ;
/* Note that since there is no way to request 9-bit mode
* and no way to support 5 / 6 / 7 - bit modes , we ignore them
* all here .
*/
/* Note that only cfgetispeed is used because we have knowledge
* that only one speed is supported .
*/
priv - > baud = cfgetispeed ( termiosp ) ;
up_setspeed ( dev ) ;
/* effect the changes immediately - note that we do not implement
* TCSADRAIN / TCSAFLUSH
*/
up_set_format ( dev ) ;
}
break ;
# endif
# endif /* CONFIG_SERIAL_TERMIOS */
# ifdef CONFIG_USART_BREAKS
case TIOCSBRK : /* BSD compatibility: Turn break on, unconditionally */
@ -1945,10 +2025,10 @@ void stm32_serial_dma_poll(void)
@@ -1945,10 +2025,10 @@ void stm32_serial_dma_poll(void)
int up_putc ( int ch )
{
# if CONSOLE_UART > 0
// struct up_dev_s *priv = uart_devs[CONSOLE_UART - 1];
// uint16_t ie;
struct up_dev_s * priv = uart_devs [ CONSOLE_UART - 1 ] ;
uint16_t ie ;
// up_disableusartint(priv, &ie);
up_disableusartint ( priv , & ie ) ;
/* Check for LF */
@ -1960,7 +2040,7 @@ int up_putc(int ch)
@@ -1960,7 +2040,7 @@ int up_putc(int ch)
}
up_lowputc ( ch ) ;
// up_restoreusartint(priv, ie);
up_restoreusartint ( priv , ie ) ;
# endif
return ch ;
}