forked from Archive/PX4-Autopilot
Merge branch '#69-stm32-termios' of github.com:PX4/Firmware into sbus
This commit is contained in:
commit
20973d603c
|
@ -185,11 +185,15 @@ struct up_dev_s
|
||||||
uint8_t parity; /* 0=none, 1=odd, 2=even */
|
uint8_t parity; /* 0=none, 1=odd, 2=even */
|
||||||
uint8_t bits; /* Number of bits (7 or 8) */
|
uint8_t bits; /* Number of bits (7 or 8) */
|
||||||
bool stopbits2; /* True: Configure with 2 stop bits instead of 1 */
|
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 */
|
uint32_t baud; /* Configured baud */
|
||||||
#else
|
#else
|
||||||
const uint8_t parity; /* 0=none, 1=odd, 2=even */
|
const uint8_t parity; /* 0=none, 1=odd, 2=even */
|
||||||
const uint8_t bits; /* Number of bits (7 or 8) */
|
const uint8_t bits; /* Number of bits (7 or 8) */
|
||||||
const bool stopbits2; /* True: Configure with 2 stop bits instead of 1 */
|
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 */
|
const uint32_t baud; /* Configured baud */
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
@ -221,7 +225,7 @@ struct up_dev_s
|
||||||
* Private Function Prototypes
|
* 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 int up_setup(struct uart_dev_s *dev);
|
||||||
static void up_shutdown(struct uart_dev_s *dev);
|
static void up_shutdown(struct uart_dev_s *dev);
|
||||||
static int up_attach(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 =
|
||||||
.parity = CONFIG_USART1_PARITY,
|
.parity = CONFIG_USART1_PARITY,
|
||||||
.bits = CONFIG_USART1_BITS,
|
.bits = CONFIG_USART1_BITS,
|
||||||
.stopbits2 = CONFIG_USART1_2STOP,
|
.stopbits2 = CONFIG_USART1_2STOP,
|
||||||
|
.iflow = false,
|
||||||
|
.oflow = false,
|
||||||
.baud = CONFIG_USART1_BAUD,
|
.baud = CONFIG_USART1_BAUD,
|
||||||
.apbclock = STM32_PCLK2_FREQUENCY,
|
.apbclock = STM32_PCLK2_FREQUENCY,
|
||||||
.usartbase = STM32_USART1_BASE,
|
.usartbase = STM32_USART1_BASE,
|
||||||
|
@ -444,6 +450,8 @@ static struct up_dev_s g_usart2priv =
|
||||||
.parity = CONFIG_USART2_PARITY,
|
.parity = CONFIG_USART2_PARITY,
|
||||||
.bits = CONFIG_USART2_BITS,
|
.bits = CONFIG_USART2_BITS,
|
||||||
.stopbits2 = CONFIG_USART2_2STOP,
|
.stopbits2 = CONFIG_USART2_2STOP,
|
||||||
|
.iflow = false,
|
||||||
|
.oflow = false,
|
||||||
.baud = CONFIG_USART2_BAUD,
|
.baud = CONFIG_USART2_BAUD,
|
||||||
.apbclock = STM32_PCLK1_FREQUENCY,
|
.apbclock = STM32_PCLK1_FREQUENCY,
|
||||||
.usartbase = STM32_USART2_BASE,
|
.usartbase = STM32_USART2_BASE,
|
||||||
|
@ -495,6 +503,8 @@ static struct up_dev_s g_usart3priv =
|
||||||
.parity = CONFIG_USART3_PARITY,
|
.parity = CONFIG_USART3_PARITY,
|
||||||
.bits = CONFIG_USART3_BITS,
|
.bits = CONFIG_USART3_BITS,
|
||||||
.stopbits2 = CONFIG_USART3_2STOP,
|
.stopbits2 = CONFIG_USART3_2STOP,
|
||||||
|
.iflow = false,
|
||||||
|
.oflow = false,
|
||||||
.baud = CONFIG_USART3_BAUD,
|
.baud = CONFIG_USART3_BAUD,
|
||||||
.apbclock = STM32_PCLK1_FREQUENCY,
|
.apbclock = STM32_PCLK1_FREQUENCY,
|
||||||
.usartbase = STM32_USART3_BASE,
|
.usartbase = STM32_USART3_BASE,
|
||||||
|
@ -546,17 +556,15 @@ static struct up_dev_s g_uart4priv =
|
||||||
.parity = CONFIG_UART4_PARITY,
|
.parity = CONFIG_UART4_PARITY,
|
||||||
.bits = CONFIG_UART4_BITS,
|
.bits = CONFIG_UART4_BITS,
|
||||||
.stopbits2 = CONFIG_UART4_2STOP,
|
.stopbits2 = CONFIG_UART4_2STOP,
|
||||||
|
.iflow = false,
|
||||||
|
.oflow = false,
|
||||||
.baud = CONFIG_UART4_BAUD,
|
.baud = CONFIG_UART4_BAUD,
|
||||||
.apbclock = STM32_PCLK1_FREQUENCY,
|
.apbclock = STM32_PCLK1_FREQUENCY,
|
||||||
.usartbase = STM32_UART4_BASE,
|
.usartbase = STM32_UART4_BASE,
|
||||||
.tx_gpio = GPIO_UART4_TX,
|
.tx_gpio = GPIO_UART4_TX,
|
||||||
.rx_gpio = GPIO_UART4_RX,
|
.rx_gpio = GPIO_UART4_RX,
|
||||||
#ifdef GPIO_UART4_CTS
|
.cts_gpio = 0, /* flow control not supported on this port */
|
||||||
.cts_gpio = GPIO_UART4_CTS,
|
.rts_gpio = 0, /* flow control not supported on this port */
|
||||||
#endif
|
|
||||||
#ifdef GPIO_UART4_RTS
|
|
||||||
.rts_gpio = GPIO_UART4_RTS,
|
|
||||||
#endif
|
|
||||||
#ifdef CONFIG_UART4_RXDMA
|
#ifdef CONFIG_UART4_RXDMA
|
||||||
.rxdma_channel = DMAMAP_UART4_RX,
|
.rxdma_channel = DMAMAP_UART4_RX,
|
||||||
.rxfifo = g_uart4rxfifo,
|
.rxfifo = g_uart4rxfifo,
|
||||||
|
@ -597,17 +605,15 @@ static struct up_dev_s g_uart5priv =
|
||||||
.parity = CONFIG_UART5_PARITY,
|
.parity = CONFIG_UART5_PARITY,
|
||||||
.bits = CONFIG_UART5_BITS,
|
.bits = CONFIG_UART5_BITS,
|
||||||
.stopbits2 = CONFIG_UART5_2STOP,
|
.stopbits2 = CONFIG_UART5_2STOP,
|
||||||
|
.iflow = false,
|
||||||
|
.oflow = false,
|
||||||
.baud = CONFIG_UART5_BAUD,
|
.baud = CONFIG_UART5_BAUD,
|
||||||
.apbclock = STM32_PCLK1_FREQUENCY,
|
.apbclock = STM32_PCLK1_FREQUENCY,
|
||||||
.usartbase = STM32_UART5_BASE,
|
.usartbase = STM32_UART5_BASE,
|
||||||
.tx_gpio = GPIO_UART5_TX,
|
.tx_gpio = GPIO_UART5_TX,
|
||||||
.rx_gpio = GPIO_UART5_RX,
|
.rx_gpio = GPIO_UART5_RX,
|
||||||
#ifdef GPIO_UART5_CTS
|
.cts_gpio = 0, /* flow control not supported on this port */
|
||||||
.cts_gpio = GPIO_UART5_CTS,
|
.rts_gpio = 0, /* flow control not supported on this port */
|
||||||
#endif
|
|
||||||
#ifdef GPIO_UART5_RTS
|
|
||||||
.rts_gpio = GPIO_UART5_RTS,
|
|
||||||
#endif
|
|
||||||
#ifdef CONFIG_UART5_RXDMA
|
#ifdef CONFIG_UART5_RXDMA
|
||||||
.rxdma_channel = DMAMAP_UART5_RX,
|
.rxdma_channel = DMAMAP_UART5_RX,
|
||||||
.rxfifo = g_uart5rxfifo,
|
.rxfifo = g_uart5rxfifo,
|
||||||
|
@ -648,6 +654,8 @@ static struct up_dev_s g_usart6priv =
|
||||||
.parity = CONFIG_USART6_PARITY,
|
.parity = CONFIG_USART6_PARITY,
|
||||||
.bits = CONFIG_USART6_BITS,
|
.bits = CONFIG_USART6_BITS,
|
||||||
.stopbits2 = CONFIG_USART6_2STOP,
|
.stopbits2 = CONFIG_USART6_2STOP,
|
||||||
|
.iflow = false,
|
||||||
|
.oflow = false,
|
||||||
.baud = CONFIG_USART6_BAUD,
|
.baud = CONFIG_USART6_BAUD,
|
||||||
.apbclock = STM32_PCLK2_FREQUENCY,
|
.apbclock = STM32_PCLK2_FREQUENCY,
|
||||||
.usartbase = STM32_USART6_BASE,
|
.usartbase = STM32_USART6_BASE,
|
||||||
|
@ -812,21 +820,22 @@ static int up_dma_nextrx(struct up_dev_s *priv)
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
/****************************************************************************
|
/****************************************************************************
|
||||||
* Name: up_setspeed
|
* Name: up_set_format
|
||||||
*
|
*
|
||||||
* Description:
|
* Description:
|
||||||
* Set the serial line speed.
|
* Set the serial line format and speed.
|
||||||
*
|
*
|
||||||
****************************************************************************/
|
****************************************************************************/
|
||||||
|
|
||||||
#ifndef CONFIG_SUPPRESS_UART_CONFIG
|
#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;
|
struct up_dev_s *priv = (struct up_dev_s*)dev->priv;
|
||||||
uint32_t usartdiv32;
|
uint32_t usartdiv32;
|
||||||
uint32_t mantissa;
|
uint32_t mantissa;
|
||||||
uint32_t fraction;
|
uint32_t fraction;
|
||||||
uint32_t brr;
|
uint32_t brr;
|
||||||
|
uint32_t regval;
|
||||||
|
|
||||||
/* Configure the USART Baud Rate. The baud rate for the receiver and
|
/* 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
|
* 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)
|
||||||
* usartdiv32 = 32 * usartdiv = fCK / (baud/2)
|
* usartdiv32 = 32 * usartdiv = fCK / (baud/2)
|
||||||
*/
|
*/
|
||||||
|
|
||||||
usartdiv32 = priv->apbclock / (priv->baud >> 1);
|
usartdiv32 = priv->apbclock / (priv->baud >> 1);
|
||||||
|
|
||||||
/* The mantissa part is then */
|
/* The mantissa part is then */
|
||||||
|
|
||||||
mantissa = usartdiv32 >> 5;
|
mantissa = usartdiv32 >> 5;
|
||||||
brr = mantissa << USART_BRR_MANT_SHIFT;
|
brr = mantissa << USART_BRR_MANT_SHIFT;
|
||||||
|
|
||||||
/* The fractional remainder (with rounding) */
|
/* 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 */
|
||||||
|
|
||||||
|
regval = up_serialin(priv, STM32_USART_CR1_OFFSET);
|
||||||
|
regval &= ~(USART_CR1_PCE|USART_CR1_PS);
|
||||||
|
|
||||||
|
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 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
|
* Name: up_setup
|
||||||
|
@ -894,43 +947,28 @@ static int up_setup(struct uart_dev_s *dev)
|
||||||
}
|
}
|
||||||
|
|
||||||
/* Configure CR2 */
|
/* 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 = 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);
|
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);
|
up_serialout(priv, STM32_USART_CR2_OFFSET, regval);
|
||||||
|
|
||||||
/* Configure CR1 */
|
/* 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 = 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);
|
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 */
|
if (priv->bits == 9) /* Default: 1 start, 8 data, n stop */
|
||||||
{
|
{
|
||||||
regval |= USART_CR1_M; /* 1 start, 9 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);
|
up_serialout(priv, STM32_USART_CR1_OFFSET, regval);
|
||||||
|
|
||||||
/* Configure CR3 */
|
/* Configure CR3 */
|
||||||
|
@ -943,16 +981,17 @@ static int up_setup(struct uart_dev_s *dev)
|
||||||
|
|
||||||
up_serialout(priv, STM32_USART_CR3_OFFSET, regval);
|
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 */
|
/* Enable Rx, Tx, and the USART */
|
||||||
|
|
||||||
regval = up_serialin(priv, STM32_USART_CR1_OFFSET);
|
regval = up_serialin(priv, STM32_USART_CR1_OFFSET);
|
||||||
regval |= (USART_CR1_UE|USART_CR1_TE|USART_CR1_RE);
|
regval |= (USART_CR1_UE|USART_CR1_TE|USART_CR1_RE);
|
||||||
up_serialout(priv, STM32_USART_CR1_OFFSET, regval);
|
up_serialout(priv, STM32_USART_CR1_OFFSET, regval);
|
||||||
#endif
|
|
||||||
|
#endif /* CONFIG_SUPPRESS_UART_CONFIG */
|
||||||
|
|
||||||
/* Set up the cached interrupt enables value */
|
/* Set up the cached interrupt enables value */
|
||||||
|
|
||||||
|
@ -1279,12 +1318,21 @@ static int up_ioctl(struct file *filep, int cmd, unsigned long arg)
|
||||||
break;
|
break;
|
||||||
}
|
}
|
||||||
|
|
||||||
/* TODO: Other termios fields are not yet returned.
|
cfsetispeed(termiosp, priv->baud);
|
||||||
* Note that only cfsetospeed is not necessary because we have
|
|
||||||
* knowledge that only one speed is supported.
|
/* 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;
|
break;
|
||||||
|
|
||||||
|
@ -1298,16 +1346,48 @@ static int up_ioctl(struct file *filep, int cmd, unsigned long arg)
|
||||||
break;
|
break;
|
||||||
}
|
}
|
||||||
|
|
||||||
/* TODO: Handle other termios settings.
|
/* Perform some sanity checks before accepting any changes */
|
||||||
* Note that only cfgetispeed is used besued we have knowledge
|
|
||||||
|
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.
|
* that only one speed is supported.
|
||||||
*/
|
*/
|
||||||
|
|
||||||
priv->baud = cfgetispeed(termiosp);
|
priv->baud = cfgetispeed(termiosp);
|
||||||
up_setspeed(dev);
|
|
||||||
|
/* effect the changes immediately - note that we do not implement
|
||||||
|
* TCSADRAIN / TCSAFLUSH
|
||||||
|
*/
|
||||||
|
|
||||||
|
up_set_format(dev);
|
||||||
}
|
}
|
||||||
break;
|
break;
|
||||||
#endif
|
#endif /* CONFIG_SERIAL_TERMIOS */
|
||||||
|
|
||||||
#ifdef CONFIG_USART_BREAKS
|
#ifdef CONFIG_USART_BREAKS
|
||||||
case TIOCSBRK: /* BSD compatibility: Turn break on, unconditionally */
|
case TIOCSBRK: /* BSD compatibility: Turn break on, unconditionally */
|
||||||
|
@ -1945,10 +2025,10 @@ void stm32_serial_dma_poll(void)
|
||||||
int up_putc(int ch)
|
int up_putc(int ch)
|
||||||
{
|
{
|
||||||
#if CONSOLE_UART > 0
|
#if CONSOLE_UART > 0
|
||||||
// struct up_dev_s *priv = uart_devs[CONSOLE_UART - 1];
|
struct up_dev_s *priv = uart_devs[CONSOLE_UART - 1];
|
||||||
// uint16_t ie;
|
uint16_t ie;
|
||||||
|
|
||||||
// up_disableusartint(priv, &ie);
|
up_disableusartint(priv, &ie);
|
||||||
|
|
||||||
/* Check for LF */
|
/* Check for LF */
|
||||||
|
|
||||||
|
@ -1960,7 +2040,7 @@ int up_putc(int ch)
|
||||||
}
|
}
|
||||||
|
|
||||||
up_lowputc(ch);
|
up_lowputc(ch);
|
||||||
// up_restoreusartint(priv, ie);
|
up_restoreusartint(priv, ie);
|
||||||
#endif
|
#endif
|
||||||
return ch;
|
return ch;
|
||||||
}
|
}
|
||||||
|
|
|
@ -252,7 +252,7 @@ static inline ssize_t uart_irqwrite(FAR uart_dev_t *dev, FAR const char *buffer,
|
||||||
{
|
{
|
||||||
int ch = *buffer++;
|
int ch = *buffer++;
|
||||||
|
|
||||||
/* If this is the console, then we should replace LF with CR-LF */
|
/* assume that this is console text output and always do \n -> \r\n conversion */
|
||||||
|
|
||||||
if (ch == '\n')
|
if (ch == '\n')
|
||||||
{
|
{
|
||||||
|
@ -277,6 +277,7 @@ static ssize_t uart_write(FAR struct file *filep, FAR const char *buffer, size_t
|
||||||
FAR uart_dev_t *dev = inode->i_private;
|
FAR uart_dev_t *dev = inode->i_private;
|
||||||
ssize_t nread = buflen;
|
ssize_t nread = buflen;
|
||||||
int ret;
|
int ret;
|
||||||
|
char ch;
|
||||||
|
|
||||||
/* We may receive console writes through this path from interrupt handlers and
|
/* We may receive console writes through this path from interrupt handlers and
|
||||||
* from debug output in the IDLE task! In these cases, we will need to do things
|
* from debug output in the IDLE task! In these cases, we will need to do things
|
||||||
|
@ -308,8 +309,7 @@ static ssize_t uart_write(FAR struct file *filep, FAR const char *buffer, size_t
|
||||||
if (ret < 0)
|
if (ret < 0)
|
||||||
{
|
{
|
||||||
/* A signal received while waiting for access to the xmit.head will
|
/* A signal received while waiting for access to the xmit.head will
|
||||||
* abort the transfer. After the transfer has started, we are committed
|
* abort the transfer.
|
||||||
* and signals will be ignored.
|
|
||||||
*/
|
*/
|
||||||
|
|
||||||
return ret;
|
return ret;
|
||||||
|
@ -323,53 +323,64 @@ static ssize_t uart_write(FAR struct file *filep, FAR const char *buffer, size_t
|
||||||
uart_disabletxint(dev);
|
uart_disabletxint(dev);
|
||||||
for (; buflen; buflen--)
|
for (; buflen; buflen--)
|
||||||
{
|
{
|
||||||
int ch = *buffer++;
|
ch = *buffer++;
|
||||||
|
|
||||||
/* If the ONLCR flag is set, we should translate \n to \r\n */
|
/* Do output post-processing */
|
||||||
|
|
||||||
ret = OK;
|
#ifdef CONFIG_SERIAL_TERMIOS
|
||||||
if ((ch == '\n') && (dev->termios_s.c_oflag & ONLCR))
|
|
||||||
|
if (dev->tc_oflag & OPOST)
|
||||||
|
{
|
||||||
|
|
||||||
|
/* Mapping CR to NL? */
|
||||||
|
|
||||||
|
if ((ch == '\r') && (dev->tc_oflag & OCRNL))
|
||||||
|
{
|
||||||
|
ch = '\n';
|
||||||
|
}
|
||||||
|
|
||||||
|
/* Are we interested in newline processing? */
|
||||||
|
|
||||||
|
if ((ch == '\n') && (dev->tc_oflag & (ONLCR | ONLRET)))
|
||||||
|
{
|
||||||
|
ret = uart_putxmitchar(dev, '\r');
|
||||||
|
|
||||||
|
if (ret != OK)
|
||||||
|
{
|
||||||
|
break;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
/* Specifically not handled:
|
||||||
|
*
|
||||||
|
* OXTABS - primarily a full-screen terminal optimisation
|
||||||
|
* ONOEOT - Unix interoperability hack
|
||||||
|
* OLCUC - Not specified by Posix
|
||||||
|
* ONOCR - low-speed interactive optimisation
|
||||||
|
*/
|
||||||
|
|
||||||
|
}
|
||||||
|
|
||||||
|
#else /* !CONFIG_SERIAL_TERMIOS */
|
||||||
|
|
||||||
|
/* If this is the console, convert \n -> \r\n */
|
||||||
|
|
||||||
|
if (dev->isconsole && ch == '\n')
|
||||||
{
|
{
|
||||||
ret = uart_putxmitchar(dev, '\r');
|
ret = uart_putxmitchar(dev, '\r');
|
||||||
}
|
}
|
||||||
|
|
||||||
|
#endif
|
||||||
|
|
||||||
/* Put the character into the transmit buffer */
|
/* Put the character into the transmit buffer */
|
||||||
|
|
||||||
if (ret == OK)
|
ret = uart_putxmitchar(dev, ch);
|
||||||
{
|
|
||||||
ret = uart_putxmitchar(dev, ch);
|
|
||||||
}
|
|
||||||
|
|
||||||
/* Were we awakened by a signal? That should be the only condition that
|
|
||||||
* uart_putxmitchar() should return an error.
|
|
||||||
*/
|
|
||||||
|
|
||||||
if (ret < 0)
|
|
||||||
{
|
|
||||||
/* POSIX requires that we return -1 and errno set if no data was
|
|
||||||
* transferred. Otherwise, we return the number of bytes in the
|
|
||||||
* interrupted transfer.
|
|
||||||
*/
|
|
||||||
|
|
||||||
if (buflen < nread)
|
|
||||||
{
|
|
||||||
/* Some data was transferred. Return the number of bytes that were
|
|
||||||
* successfully transferred.
|
|
||||||
*/
|
|
||||||
|
|
||||||
nread -= buflen;
|
|
||||||
}
|
|
||||||
else
|
|
||||||
{
|
|
||||||
/* No data was transferred. Return -EINTR. The VFS layer will
|
|
||||||
* set the errno value appropriately).
|
|
||||||
*/
|
|
||||||
|
|
||||||
nread = -EINTR;
|
|
||||||
}
|
|
||||||
|
|
||||||
|
if (ret != OK)
|
||||||
|
{
|
||||||
break;
|
break;
|
||||||
}
|
}
|
||||||
|
|
||||||
}
|
}
|
||||||
|
|
||||||
if (dev->xmit.head != dev->xmit.tail)
|
if (dev->xmit.head != dev->xmit.tail)
|
||||||
|
@ -378,6 +389,36 @@ static ssize_t uart_write(FAR struct file *filep, FAR const char *buffer, size_t
|
||||||
}
|
}
|
||||||
|
|
||||||
uart_givesem(&dev->xmit.sem);
|
uart_givesem(&dev->xmit.sem);
|
||||||
|
|
||||||
|
/* Were we interrupted by a signal? That should be the only condition that
|
||||||
|
* uart_putxmitchar() should return an error.
|
||||||
|
*/
|
||||||
|
|
||||||
|
if (ret < 0)
|
||||||
|
{
|
||||||
|
/* POSIX requires that we return -1 and errno set if no data was
|
||||||
|
* transferred. Otherwise, we return the number of bytes in the
|
||||||
|
* interrupted transfer.
|
||||||
|
*/
|
||||||
|
|
||||||
|
if (buflen < nread)
|
||||||
|
{
|
||||||
|
/* Some data was transferred. Return the number of bytes that were
|
||||||
|
* successfully transferred.
|
||||||
|
*/
|
||||||
|
|
||||||
|
nread -= buflen;
|
||||||
|
}
|
||||||
|
else
|
||||||
|
{
|
||||||
|
/* No data was transferred. Return -EINTR. The VFS layer will
|
||||||
|
* set the errno value appropriately).
|
||||||
|
*/
|
||||||
|
|
||||||
|
nread = -EINTR;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
return nread;
|
return nread;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
@ -393,6 +434,7 @@ static ssize_t uart_read(FAR struct file *filep, FAR char *buffer, size_t buflen
|
||||||
ssize_t recvd = 0;
|
ssize_t recvd = 0;
|
||||||
int16_t tail;
|
int16_t tail;
|
||||||
int ret;
|
int ret;
|
||||||
|
char ch;
|
||||||
|
|
||||||
/* Only one user can access dev->recv.tail at a time */
|
/* Only one user can access dev->recv.tail at a time */
|
||||||
|
|
||||||
|
@ -430,8 +472,7 @@ static ssize_t uart_read(FAR struct file *filep, FAR char *buffer, size_t buflen
|
||||||
{
|
{
|
||||||
/* Take the next character from the tail of the buffer */
|
/* Take the next character from the tail of the buffer */
|
||||||
|
|
||||||
*buffer++ = dev->recv.buffer[tail];
|
ch = dev->recv.buffer[tail];
|
||||||
recvd++;
|
|
||||||
|
|
||||||
/* Increment the tail index. Most operations are done using the
|
/* Increment the tail index. Most operations are done using the
|
||||||
* local variable 'tail' so that the final dev->recv.tail update
|
* local variable 'tail' so that the final dev->recv.tail update
|
||||||
|
@ -444,6 +485,49 @@ static ssize_t uart_read(FAR struct file *filep, FAR char *buffer, size_t buflen
|
||||||
}
|
}
|
||||||
|
|
||||||
dev->recv.tail = tail;
|
dev->recv.tail = tail;
|
||||||
|
|
||||||
|
#ifdef CONFIG_SERIAL_TERMIOS
|
||||||
|
|
||||||
|
/* Do input processing if any is enabled */
|
||||||
|
|
||||||
|
if (dev->tc_iflag & (INLCR | IGNCR | ICRNL))
|
||||||
|
{
|
||||||
|
|
||||||
|
/* \n -> \r or \r -> \n translation? */
|
||||||
|
|
||||||
|
if ((ch == '\n') && (dev->tc_iflag & INLCR))
|
||||||
|
{
|
||||||
|
ch = '\r';
|
||||||
|
}
|
||||||
|
else if ((ch == '\r') && (dev->tc_iflag & ICRNL))
|
||||||
|
{
|
||||||
|
ch = '\n';
|
||||||
|
}
|
||||||
|
|
||||||
|
/* discarding \r ? */
|
||||||
|
if ((ch == '\r') & (dev->tc_iflag & IGNCR))
|
||||||
|
{
|
||||||
|
continue;
|
||||||
|
}
|
||||||
|
|
||||||
|
}
|
||||||
|
|
||||||
|
/* Specifically not handled:
|
||||||
|
*
|
||||||
|
* All of the local modes; echo, line editing, etc.
|
||||||
|
* Anything to do with break or parity errors.
|
||||||
|
* ISTRIP - we should be 8-bit clean.
|
||||||
|
* IUCLC - Not Posix
|
||||||
|
* IXON/OXOFF - no xon/xoff flow control.
|
||||||
|
*/
|
||||||
|
|
||||||
|
#endif
|
||||||
|
|
||||||
|
/* store the received character */
|
||||||
|
|
||||||
|
*buffer++ = ch;
|
||||||
|
recvd++;
|
||||||
|
|
||||||
}
|
}
|
||||||
|
|
||||||
#ifdef CONFIG_DEV_SERIAL_FULLBLOCKS
|
#ifdef CONFIG_DEV_SERIAL_FULLBLOCKS
|
||||||
|
@ -573,43 +657,77 @@ static int uart_ioctl(FAR struct file *filep, int cmd, unsigned long arg)
|
||||||
|
|
||||||
/* Handle TTY-level IOCTLs here */
|
/* Handle TTY-level IOCTLs here */
|
||||||
/* Let low-level driver handle the call first */
|
/* Let low-level driver handle the call first */
|
||||||
|
|
||||||
int ret = dev->ops->ioctl(filep, cmd, arg);
|
int ret = dev->ops->ioctl(filep, cmd, arg);
|
||||||
|
|
||||||
/* Append any higher level TTY flags */
|
/* Append any higher level TTY flags */
|
||||||
switch (cmd)
|
|
||||||
|
if (ret == OK)
|
||||||
{
|
{
|
||||||
case TCGETS:
|
switch (cmd)
|
||||||
{
|
{
|
||||||
struct termios *termiosp = (struct termios*)arg;
|
|
||||||
|
|
||||||
if (!termiosp)
|
case FIONREAD:
|
||||||
{
|
{
|
||||||
ret = -EINVAL;
|
int count;
|
||||||
break;
|
irqstate_t state = irqsave();
|
||||||
}
|
|
||||||
|
|
||||||
/* Fetch the out flags */
|
/* determine the number of bytes available in the buffer */
|
||||||
termiosp->c_oflag = dev->termios_s.c_oflag;
|
|
||||||
/* Fetch the in flags */
|
|
||||||
termiosp->c_iflag = dev->termios_s.c_iflag;
|
|
||||||
}
|
|
||||||
break;
|
|
||||||
|
|
||||||
case TCSETS:
|
if (dev->recv.tail <= dev->recv.head)
|
||||||
{
|
{
|
||||||
struct termios *termiosp = (struct termios*)arg;
|
count = dev->recv.head - dev->recv.tail;
|
||||||
|
}
|
||||||
|
else
|
||||||
|
{
|
||||||
|
count = dev->recv.size - (dev->recv.tail - dev->recv.head);
|
||||||
|
}
|
||||||
|
|
||||||
if (!termiosp)
|
irqrestore(state);
|
||||||
{
|
|
||||||
ret = -EINVAL;
|
|
||||||
break;
|
|
||||||
}
|
|
||||||
|
|
||||||
/* Set the out flags */
|
*(int *)arg = count;
|
||||||
dev->termios_s.c_oflag = termiosp->c_oflag;
|
}
|
||||||
/* Set the in flags */
|
|
||||||
dev->termios_s.c_iflag = termiosp->c_iflag;
|
#ifdef CONFIG_SERIAL_TERMIOS
|
||||||
}
|
case TCGETS:
|
||||||
break;
|
{
|
||||||
|
struct termios *termiosp = (struct termios*)arg;
|
||||||
|
|
||||||
|
if (!termiosp)
|
||||||
|
{
|
||||||
|
ret = -EINVAL;
|
||||||
|
break;
|
||||||
|
}
|
||||||
|
|
||||||
|
/* and update with flags from this layer */
|
||||||
|
|
||||||
|
termiosp->c_iflag = dev->tc_iflag;
|
||||||
|
termiosp->c_oflag = dev->tc_oflag;
|
||||||
|
termiosp->c_lflag = dev->tc_lflag;
|
||||||
|
}
|
||||||
|
|
||||||
|
break;
|
||||||
|
|
||||||
|
case TCSETS:
|
||||||
|
{
|
||||||
|
struct termios *termiosp = (struct termios*)arg;
|
||||||
|
|
||||||
|
if (!termiosp)
|
||||||
|
{
|
||||||
|
ret = -EINVAL;
|
||||||
|
break;
|
||||||
|
}
|
||||||
|
|
||||||
|
/* update the flags we keep at this layer */
|
||||||
|
|
||||||
|
dev->tc_iflag = termiosp->c_iflag;
|
||||||
|
dev->tc_oflag = termiosp->c_oflag;
|
||||||
|
dev->tc_lflag = termiosp->c_lflag;
|
||||||
|
}
|
||||||
|
|
||||||
|
break;
|
||||||
|
#endif
|
||||||
|
}
|
||||||
}
|
}
|
||||||
return ret;
|
return ret;
|
||||||
}
|
}
|
||||||
|
@ -900,6 +1018,25 @@ static int uart_open(FAR struct file *filep)
|
||||||
dev->recv.head = 0;
|
dev->recv.head = 0;
|
||||||
dev->recv.tail = 0;
|
dev->recv.tail = 0;
|
||||||
|
|
||||||
|
/* initialise termios state */
|
||||||
|
|
||||||
|
#ifdef CONFIG_SERIAL_TERMIOS
|
||||||
|
|
||||||
|
dev->tc_iflag = 0;
|
||||||
|
if (dev->isconsole == true)
|
||||||
|
{
|
||||||
|
|
||||||
|
/* enable \n -> \r\n translation for the console */
|
||||||
|
|
||||||
|
dev->tc_oflag = OPOST | ONLCR;
|
||||||
|
}
|
||||||
|
else
|
||||||
|
{
|
||||||
|
dev->tc_oflag = 0;
|
||||||
|
}
|
||||||
|
|
||||||
|
#endif
|
||||||
|
|
||||||
/* Enable the RX interrupt */
|
/* Enable the RX interrupt */
|
||||||
|
|
||||||
uart_enablerxint(dev);
|
uart_enablerxint(dev);
|
||||||
|
@ -937,14 +1074,22 @@ int uart_register(FAR const char *path, FAR uart_dev_t *dev)
|
||||||
#ifndef CONFIG_DISABLE_POLL
|
#ifndef CONFIG_DISABLE_POLL
|
||||||
sem_init(&dev->pollsem, 0, 1);
|
sem_init(&dev->pollsem, 0, 1);
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
/* Setup termios flags */
|
/* Setup termios flags */
|
||||||
memset(&dev->termios_s, 0, sizeof(dev->termios_s));
|
|
||||||
|
#ifdef CONFIG_SERIAL_TERMIOS
|
||||||
|
|
||||||
if (dev->isconsole == true)
|
if (dev->isconsole == true)
|
||||||
{
|
{
|
||||||
/* Device is console, set up termios flags */
|
|
||||||
dev->termios_s.c_oflag |= ONLCR;
|
/* enable \n -> \r\n translation for the console as early as possible */
|
||||||
|
|
||||||
|
dev->tc_oflag = OPOST | ONLCR;
|
||||||
|
dev->tc_iflag = 0;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
#endif
|
||||||
|
|
||||||
dbg("Registering %s\n", path);
|
dbg("Registering %s\n", path);
|
||||||
return register_driver(path, &g_serialops, 0666, dev);
|
return register_driver(path, &g_serialops, 0666, dev);
|
||||||
}
|
}
|
||||||
|
|
|
@ -106,6 +106,10 @@
|
||||||
* OUT: None
|
* OUT: None
|
||||||
*/
|
*/
|
||||||
|
|
||||||
|
#define FIONREAD _FIOC(0x0004) /* IN: Location to return value (int *)
|
||||||
|
* OUT: Bytes readable from this fd
|
||||||
|
*/
|
||||||
|
|
||||||
/* NuttX file system ioctl definitions **************************************/
|
/* NuttX file system ioctl definitions **************************************/
|
||||||
|
|
||||||
#define _DIOCVALID(c) (_IOC_TYPE(c)==_DIOCBASE)
|
#define _DIOCVALID(c) (_IOC_TYPE(c)==_DIOCBASE)
|
||||||
|
|
|
@ -46,7 +46,9 @@
|
||||||
#include <stdint.h>
|
#include <stdint.h>
|
||||||
#include <stdbool.h>
|
#include <stdbool.h>
|
||||||
#include <semaphore.h>
|
#include <semaphore.h>
|
||||||
#include <termios.h>
|
#ifdef CONFIG_SERIAL_TERMIOS
|
||||||
|
# include <termios.h>
|
||||||
|
#endif
|
||||||
#include <nuttx/fs/fs.h>
|
#include <nuttx/fs/fs.h>
|
||||||
|
|
||||||
/************************************************************************************
|
/************************************************************************************
|
||||||
|
@ -216,7 +218,12 @@ struct uart_dev_s
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
/* Terminal control flags */
|
/* Terminal control flags */
|
||||||
struct termios termios_s;
|
|
||||||
|
#ifdef CONFIG_SERIAL_TERMIOS
|
||||||
|
tcflag_t tc_iflag; /* Input modes */
|
||||||
|
tcflag_t tc_oflag; /* Output modes */
|
||||||
|
tcflag_t tc_lflag; /* Local modes */
|
||||||
|
#endif
|
||||||
|
|
||||||
};
|
};
|
||||||
typedef struct uart_dev_s uart_dev_t;
|
typedef struct uart_dev_s uart_dev_t;
|
||||||
|
|
|
@ -58,7 +58,7 @@
|
||||||
#define INLCR (1 << 5) /* Bit 5: Map NL to CR on input */
|
#define INLCR (1 << 5) /* Bit 5: Map NL to CR on input */
|
||||||
#define INPCK (1 << 6) /* Bit 6: Enable input parity check */
|
#define INPCK (1 << 6) /* Bit 6: Enable input parity check */
|
||||||
#define ISTRIP (1 << 7) /* Bit 7: Strip character */
|
#define ISTRIP (1 << 7) /* Bit 7: Strip character */
|
||||||
#define IUCLC (1 << 8) /* Bit 8: Map upper-case to lower-case on input (LEGACY) */
|
/* Bit 8: unused */
|
||||||
#define IXANY (1 << 9) /* Bit 9: Enable any character to restart output */
|
#define IXANY (1 << 9) /* Bit 9: Enable any character to restart output */
|
||||||
#define IXOFF (1 << 10) /* Bit 10: Enable start/stop input control */
|
#define IXOFF (1 << 10) /* Bit 10: Enable start/stop input control */
|
||||||
#define IXON (1 << 11) /* Bit 11: Enable start/stop output control */
|
#define IXON (1 << 11) /* Bit 11: Enable start/stop output control */
|
||||||
|
@ -67,7 +67,7 @@
|
||||||
/* Terminal output modes (c_oflag in the termios structure) */
|
/* Terminal output modes (c_oflag in the termios structure) */
|
||||||
|
|
||||||
#define OPOST (1 << 0) /* Bit 0: Post-process output */
|
#define OPOST (1 << 0) /* Bit 0: Post-process output */
|
||||||
#define OLCUC (1 << 1) /* Bit 1: Map lower-case to upper-case on output (LEGACY) */
|
/* Bit 1: unused */
|
||||||
#define ONLCR (1 << 2) /* Bit 2: Map NL to CR-NL on output */
|
#define ONLCR (1 << 2) /* Bit 2: Map NL to CR-NL on output */
|
||||||
#define OCRNL (1 << 3) /* Bit 3: Map CR to NL on output */
|
#define OCRNL (1 << 3) /* Bit 3: Map CR to NL on output */
|
||||||
#define ONOCR (1 << 4) /* Bit 4: No CR output at column 0 */
|
#define ONOCR (1 << 4) /* Bit 4: No CR output at column 0 */
|
||||||
|
@ -98,17 +98,20 @@
|
||||||
|
|
||||||
/* Control Modes (c_cflag in the termios structure) */
|
/* Control Modes (c_cflag in the termios structure) */
|
||||||
|
|
||||||
#define CSIZE (3 << 0) /* Bits 0-1: Character size: */
|
#define CSIZE (3 << 0) /* Bits 0-1: Character size: */
|
||||||
# define CS5 (0 << 0) /* 5 bits */
|
# define CS5 (0 << 0) /* 5 bits */
|
||||||
# define CS6 (1 << 0) /* 6 bits */
|
# define CS6 (1 << 0) /* 6 bits */
|
||||||
# define CS7 (2 << 0) /* 7 bits */
|
# define CS7 (2 << 0) /* 7 bits */
|
||||||
# define CS8 (3 << 0) /* 8 bits */
|
# define CS8 (3 << 0) /* 8 bits */
|
||||||
#define CSTOPB (1 << 2) /* Bit 2: Send two stop bits, else one */
|
#define CSTOPB (1 << 2) /* Bit 2: Send two stop bits, else one */
|
||||||
#define CREAD (1 << 3) /* Bit 3: Enable receiver */
|
#define CREAD (1 << 3) /* Bit 3: Enable receiver */
|
||||||
#define PARENB (1 << 4) /* Bit 4: Parity enable */
|
#define PARENB (1 << 4) /* Bit 4: Parity enable */
|
||||||
#define PARODD (1 << 5) /* Bit 5: Odd parity, else even */
|
#define PARODD (1 << 5) /* Bit 5: Odd parity, else even */
|
||||||
#define HUPCL (1 << 6) /* Bit 6: Hang up on last close */
|
#define HUPCL (1 << 6) /* Bit 6: Hang up on last close */
|
||||||
#define CLOCAL (1 << 7) /* Bit 7: Ignore modem status lines */
|
#define CLOCAL (1 << 7) /* Bit 7: Ignore modem status lines */
|
||||||
|
#define CCTS_OFLOW (1 << 8) /* Bit 8: CTS flow control of output */
|
||||||
|
#define CRTSCTS CCTS_OFLOW
|
||||||
|
#define CRTS_IFLOW (1 << 9) /* Bit 9: RTS flow control of input */
|
||||||
|
|
||||||
/* Local Modes (c_lflag in the termios structure) */
|
/* Local Modes (c_lflag in the termios structure) */
|
||||||
|
|
||||||
|
@ -121,7 +124,6 @@
|
||||||
#define ISIG (1 << 6) /* Bit 6: Enable signals */
|
#define ISIG (1 << 6) /* Bit 6: Enable signals */
|
||||||
#define NOFLSH (1 << 7) /* Bit 7: Disable flush after interrupt or quit */
|
#define NOFLSH (1 << 7) /* Bit 7: Disable flush after interrupt or quit */
|
||||||
#define TOSTOP (1 << 8) /* Bit 8: Send SIGTTOU for background output */
|
#define TOSTOP (1 << 8) /* Bit 8: Send SIGTTOU for background output */
|
||||||
#define XCASE (1 << 9) /* Bit 9: Canonical upper/lower presentation (LEGACY) */
|
|
||||||
|
|
||||||
/* The following are subscript names for the termios c_cc array */
|
/* The following are subscript names for the termios c_cc array */
|
||||||
|
|
||||||
|
|
Loading…
Reference in New Issue