aboutsummaryrefslogtreecommitdiff
path: root/nuttx/drivers
diff options
context:
space:
mode:
Diffstat (limited to 'nuttx/drivers')
-rw-r--r--nuttx/drivers/serial/serial.c54
1 files changed, 51 insertions, 3 deletions
diff --git a/nuttx/drivers/serial/serial.c b/nuttx/drivers/serial/serial.c
index 9ffcd75dc..b289bb80b 100644
--- a/nuttx/drivers/serial/serial.c
+++ b/nuttx/drivers/serial/serial.c
@@ -40,6 +40,7 @@
#include <nuttx/config.h>
#include <sys/types.h>
+#include <sys/ioctl.h>
#include <stdint.h>
#include <stdbool.h>
#include <unistd.h>
@@ -324,10 +325,10 @@ static ssize_t uart_write(FAR struct file *filep, FAR const char *buffer, size_t
{
int ch = *buffer++;
- /* If this is the console, then we should replace LF with CR-LF */
+ /* If the ONLCR flag is set, we should translate \n to \r\n */
ret = OK;
- if (dev->isconsole && ch == '\n')
+ if ((ch == '\n') && (dev->termios_s.c_oflag && ONLCR))
{
ret = uart_putxmitchar(dev, '\r');
}
@@ -570,7 +571,47 @@ static int uart_ioctl(FAR struct file *filep, int cmd, unsigned long arg)
FAR struct inode *inode = filep->f_inode;
FAR uart_dev_t *dev = inode->i_private;
- return dev->ops->ioctl(filep, cmd, arg);
+ /* Handle TTY-level IOCTLs here */
+ /* Let low-level driver handle the call first */
+ int ret = dev->ops->ioctl(filep, cmd, arg);
+ /* Append any higher level TTY flags */
+ switch (cmd)
+ {
+ case TCGETS:
+ {
+ struct termios *termiosp = (struct termios*)arg;
+
+ if (!termiosp)
+ {
+ ret = -EINVAL;
+ break;
+ }
+
+ /* Fetch the out flags */
+ termiosp->c_oflag = dev->termios_s.c_oflag;
+ /* Fetch the in flags */
+ termiosp->c_iflag = dev->termios_s.c_iflag;
+ }
+ break;
+
+ case TCSETS:
+ {
+ struct termios *termiosp = (struct termios*)arg;
+
+ if (!termiosp)
+ {
+ ret = -EINVAL;
+ break;
+ }
+
+ /* Set the out flags */
+ dev->termios_s.c_oflag = termiosp->c_oflag;
+ /* Set the in flags */
+ dev->termios_s.c_iflag = termiosp->c_iflag;
+ }
+ break;
+ }
+ return ret;
}
/****************************************************************************
@@ -896,6 +937,13 @@ int uart_register(FAR const char *path, FAR uart_dev_t *dev)
#ifndef CONFIG_DISABLE_POLL
sem_init(&dev->pollsem, 0, 1);
#endif
+ /* Setup termios flags */
+ memset(&dev->termios_s, 0, sizeof(dev->termios_s));
+ if (dev->isconsole == true)
+ {
+ /* Device is console, set up termios flags */
+ dev->termios_s.c_oflag |= ONLCR;
+ }
dbg("Registering %s\n", path);
return register_driver(path, &g_serialops, 0666, dev);