aboutsummaryrefslogtreecommitdiff
path: root/nuttx/include
diff options
context:
space:
mode:
authorpatacongo <patacongo@7fd9a85b-ad96-42d3-883c-3090e2eb8679>2012-07-22 18:56:50 +0000
committerpatacongo <patacongo@7fd9a85b-ad96-42d3-883c-3090e2eb8679>2012-07-22 18:56:50 +0000
commitfce36677c1495e988ba118f4721d45de5c2f42d6 (patch)
tree3031e9ab44fcd5d158aa160ee01517a0eb409a94 /nuttx/include
parentad37fa6505876fcfeb569ebd25b0971d5badde08 (diff)
downloadpx4-firmware-fce36677c1495e988ba118f4721d45de5c2f42d6.tar.gz
px4-firmware-fce36677c1495e988ba118f4721d45de5c2f42d6.tar.bz2
px4-firmware-fce36677c1495e988ba118f4721d45de5c2f42d6.zip
Loosen up termios interfaces to allow more flexible baud settings; remove AIX-like interfaces of last check-in
git-svn-id: https://nuttx.svn.sourceforge.net/svnroot/nuttx/trunk@4969 7fd9a85b-ad96-42d3-883c-3090e2eb8679
Diffstat (limited to 'nuttx/include')
-rw-r--r--nuttx/include/nuttx/serial/tioctl.h74
-rw-r--r--nuttx/include/sys/str_tty.h100
-rw-r--r--nuttx/include/termios.h76
3 files changed, 82 insertions, 168 deletions
diff --git a/nuttx/include/nuttx/serial/tioctl.h b/nuttx/include/nuttx/serial/tioctl.h
index 6862d7453..b309ff37c 100644
--- a/nuttx/include/nuttx/serial/tioctl.h
+++ b/nuttx/include/nuttx/serial/tioctl.h
@@ -65,60 +65,54 @@
#define TIOCGLCKTRMIOS _TIOC(0x0009) /* Get termios lock status: FAR struct termios* */
#define TIOCSLCKTRMIOS _TIOC(0x000a) /* Set termios lock status: FAR const struct termios* */
-/* Support for AIX-style get_speed, set_speed, and reset_speed operations (see sys/str_tty.h) */
-
-#define TIOCSETSPEED _TIOC(0x000b) /* Set speed, enter extended speed mode: int32_t */
-#define TIOCGETSPEED _TIOC(0x000c) /* Get speed: int32_t* */
-#define TIOCRESETSPEED _TIOC(0x000d) /* Exit extended speed mode: None */
-
/* Get and Set Window Size */
-#define TIOCGWINSZ _TIOC(0x000e) /* Get window size: FAR struct winsize */
-#define TIOCSWINSZ _TIOC(0x000f) /* Set window size: FAR const struct winsize */
+#define TIOCGWINSZ _TIOC(0x000b) /* Get window size: FAR struct winsize */
+#define TIOCSWINSZ _TIOC(0x000c) /* Set window size: FAR const struct winsize */
/* Send a break */
-#define TCSBRK _TIOC(0x0010) /* Send a break: int */
-#define TCSBRKP _TIOC(0x0011) /* Send a POSIX break: int */
-#define TIOCSBRK _TIOC(0x0012) /* Turn break on: void */
-#define TIOCCBRK _TIOC(0x0013) /* Turn break off: void */
+#define TCSBRK _TIOC(0x000d) /* Send a break: int */
+#define TCSBRKP _TIOC(0x000e) /* Send a POSIX break: int */
+#define TIOCSBRK _TIOC(0x000f) /* Turn break on: void */
+#define TIOCCBRK _TIOC(0x0010) /* Turn break off: void */
/* Software flow control */
-#define TCXONC _TIOC(0x0014) /* Control flow control: int */
+#define TCXONC _TIOC(0x0011) /* Control flow control: int */
/* Buffer count and flushing */
-#define TIOCINQ _TIOC(0x0015) /* Bytes in input buffer: int */
-#define TIOCOUTQ _TIOC(0x0016) /* Bytes in output buffer: int */
-#define TCFLSH _TIOC(0x0017) /* Flush: int */
+#define TIOCINQ _TIOC(0x0012) /* Bytes in input buffer: int */
+#define TIOCOUTQ _TIOC(0x0013) /* Bytes in output buffer: int */
+#define TCFLSH _TIOC(0x0014) /* Flush: int */
/* Faking input */
-#define TIOCSTI _TIOC(0x0018) /* Insert into input: const char */
+#define TIOCSTI _TIOC(0x0015) /* Insert into input: const char */
/* Re-directing console output */
-#define TIOCCONS _TIOC(0x0019) /* Re-direct console output to device: void */
+#define TIOCCONS _TIOC(0x0016) /* Re-direct console output to device: void */
/* Controlling TTY */
-#define TIOCSCTTY _TIOC(0x001a) /* Make controlling TTY: int */
-#define TIOCNOTTY _TIOC(0x001b) /* Give up controllinog TTY: void */
+#define TIOCSCTTY _TIOC(0x0017) /* Make controlling TTY: int */
+#define TIOCNOTTY _TIOC(0x0018) /* Give up controllinog TTY: void */
/* Exclusive mode */
-#define TIOCEXCL _TIOC(0x001c) /* Put TTY in exclusive mode: void */
-#define TIOCNXCL _TIOC(0x001d) /* Disable exclusive mode: void */
+#define TIOCEXCL _TIOC(0x0019) /* Put TTY in exclusive mode: void */
+#define TIOCNXCL _TIOC(0x001a) /* Disable exclusive mode: void */
/* Line discipline */
-#define TIOCGETD _TIOC(0x001e) /* Get line discipline: FAR int */
-#define TIOCSETD _TIOC(0x001f) /* Set line discipline: FAR const int */
+#define TIOCGETD _TIOC(0x001b) /* Get line discipline: FAR int */
+#define TIOCSETD _TIOC(0x001c) /* Set line discipline: FAR const int */
/* Packet mode */
-#define TIOCPKT _TIOC(0x0020) /* Control packet mode: FAR const int */
+#define TIOCPKT _TIOC(0x001d) /* Control packet mode: FAR const int */
# define TIOCPKT_FLUSHREAD (1 << 0) /* The read queue for the terminal is flushed */
# define TIOCPKT_FLUSHWRITE (1 << 1) /* The write queue for the terminal is flushed */
@@ -129,10 +123,10 @@
/* Modem control */
-#define TIOCMGET _TIOC(0x0021) /* Get modem status bits: FAR int */
-#define TIOCMSET _TIOC(0x0022) /* Set modem status bits: FAR const int */
-#define TIOCMBIC _TIOC(0x0023) /* Clear modem bits: FAR const int */
-#define TIOCMBIS _TIOC(0x0024) /* Set modem bits: FAR const int */
+#define TIOCMGET _TIOC(0x001e) /* Get modem status bits: FAR int */
+#define TIOCMSET _TIOC(0x001f) /* Set modem status bits: FAR const int */
+#define TIOCMBIC _TIOC(0x0020) /* Clear modem bits: FAR const int */
+#define TIOCMBIS _TIOC(0x0021) /* Set modem bits: FAR const int */
# define TIOCM_LE (1 << 0) /* DSR (data set ready/line enable) */
# define TIOCM_DTR (1 << 1) /* DTR (data terminal ready) */
@@ -148,32 +142,32 @@
/* TTY shutdown */
-#define TIOCVHANGUP _TIOC(0x0025) /* Shutdown TTY: void */
+#define TIOCVHANGUP _TIOC(0x0022) /* Shutdown TTY: void */
/* Marking a line as local */
-#define TIOCGSOFTCAR _TIOC(0x0026) /* Get software carrier flag: FAR int */
-#define TIOCSSOFTCAR _TIOC(0x0027) /* Set software carrier flag: FAR const int */
+#define TIOCGSOFTCAR _TIOC(0x0023) /* Get software carrier flag: FAR int */
+#define TIOCSSOFTCAR _TIOC(0x0024) /* Set software carrier flag: FAR const int */
/* Get/set serial line info */
-#define TIOCGSERIAL _TIOC(0x0028) /* Get serial line info: FAR struct serial_struct */
-#define TIOCSSERIAL _TIOC(0x0029) /* Set serial line info: FAR const struct serial_struct */
-#define TIOCSERGETLSR _TIOC(0x002a) /* Get line status register: FAR int */
+#define TIOCGSERIAL _TIOC(0x0025) /* Get serial line info: FAR struct serial_struct */
+#define TIOCSSERIAL _TIOC(0x0026) /* Set serial line info: FAR const struct serial_struct */
+#define TIOCSERGETLSR _TIOC(0x0027) /* Get line status register: FAR int */
/* Serial events */
-#define TIOCMIWAIT _TIOC(0x002b) /* Wait for a change on serial input line(s): void */
-#define TIOCGICOUNT _TIOC(0x002c) /* Read serial port interrupt count: FAR struct serial_icounter_struct */
+#define TIOCMIWAIT _TIOC(0x0028) /* Wait for a change on serial input line(s): void */
+#define TIOCGICOUNT _TIOC(0x0029) /* Read serial port interrupt count: FAR struct serial_icounter_struct */
/* RS-485 Support */
-#define TIOCSRS485 _TIOC(0x002d) /* Set RS485 mode, arg: pointer to struct serial_rs485 */
-#define TIOCGRS485 _TIOC(0x002e) /* Get RS485 mode, arg: pointer to struct serial_rs485 */
+#define TIOCSRS485 _TIOC(0x002a) /* Set RS485 mode, arg: pointer to struct serial_rs485 */
+#define TIOCGRS485 _TIOC(0x002b) /* Get RS485 mode, arg: pointer to struct serial_rs485 */
/* Debugging */
-#define TIOCSERGSTRUCT _TIOC(0x002f) /* Get device TTY structure */
+#define TIOCSERGSTRUCT _TIOC(0x002c) /* Get device TTY structure */
/* Definitions used in struct serial_rs485 (Linux compatible) */
diff --git a/nuttx/include/sys/str_tty.h b/nuttx/include/sys/str_tty.h
deleted file mode 100644
index 2ae17ef95..000000000
--- a/nuttx/include/sys/str_tty.h
+++ /dev/null
@@ -1,100 +0,0 @@
-/****************************************************************************
- * include/sys/str_tty.h
- *
- * Copyright (C) 2012 Gregory Nutt. All rights reserved.
- * Author: Gregory Nutt <gnutt@nuttx.org>
- *
- * Redistribution and use in source and binary forms, with or without
- * modification, are permitted provided that the following conditions
- * are met:
- *
- * 1. Redistributions of source code must retain the above copyright
- * notice, this list of conditions and the following disclaimer.
- * 2. Redistributions in binary form must reproduce the above copyright
- * notice, this list of conditions and the following disclaimer in
- * the documentation and/or other materials provided with the
- * distribution.
- * 3. Neither the name NuttX nor the names of its contributors may be
- * used to endorse or promote products derived from this software
- * without specific prior written permission.
- *
- * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
- * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
- * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
- * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
- * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
- * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
- * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
- * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
- * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
- * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
- * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
- * POSSIBILITY OF SUCH DAMAGE.
- *
- ****************************************************************************/
-
-#ifndef __INCLUDE_SYS_STR_TTY_H
-#define __INCLUDE_SYS_STR_TTY_H
-
-/****************************************************************************
- * Included Files
- ****************************************************************************/
-
-#include <stdint.h>
-
-/****************************************************************************
- * Pre-Processor Definitions
- ****************************************************************************/
-
-/****************************************************************************
- * Type Definitions
- ****************************************************************************/
-
-/****************************************************************************
- * Public Function Prototypes
- ****************************************************************************/
-
-#undef EXTERN
-#if defined(__cplusplus)
-#define EXTERN extern "C"
-extern "C" {
-#else
-#define EXTERN extern
-#endif
-
-/* These are non-standard AIX-like interfaces to simplify TTY baud rate
- * operations.
- *
- * The baud rate functions set_speed() and get_speed() are provided to
- * allow the applications to program any value of the baud rate that is
- * supported by the serial driver, but that cannot be expressed using
- * the termios subroutines cfsetospeed, cfsetispeed, cfgetospeed,
- * and cfsgetispeed. Those subroutines are limited to the set of values
- * defined termios.h.
- *
- * Normal mode: This is the default mode, in which a termios supported
- * speed is in use.
- *
- * Speed-extended mode: This mode is entered by calling set_speed() with
- * a non-termios supported speed at the configuration of the line. In this
- * mode, all the calls to tcgetattr subroutine or TCGETS ioctl subroutine
- * will have B50 in the returned termios structure.
- *
- * If tcsetattr() or TCSETS, TCSETAF, or TCSETAW ioctl calls the driver
- * and attempts to set B50, the actual baud rate is not changed. If it
- * attempts to set any other termios-supported speed, will switch back
- * to the normal mode and the requested baud rate is set. Calling
- * reset_speed subroutine is another way to switch back to the
- * normal mode.
- */
-
-EXTERN int32_t get_speed(int fd);
-EXTERN int set_speed(int fd, int32_t speed);
-EXTERN int reset_speed(int fd);
-
-#undef EXTERN
-#if defined(__cplusplus)
-}
-#endif
-
-#endif /* __INCLUDE_SYS_STR_TTY_H */
diff --git a/nuttx/include/termios.h b/nuttx/include/termios.h
index 705a89c0f..0a4a13b45 100644
--- a/nuttx/include/termios.h
+++ b/nuttx/include/termios.h
@@ -110,10 +110,6 @@
#define HUPCL (1 << 6) /* Hang up on last close */
#define CLOCAL (1 << 7) /* Ignore modem status lines */
-#define CBAUD (0x1f << 8) /* Baud mask (not POSIX) */
-#define CBAUDEX (0x10 << 8) /* Extra speed mask (not POSIX) */
-#define _CBAUD_SHIFT 8 /* So that we all agree where the baud code is stored */
-
/* Local Modes (c_lflag in the termios structure) */
#define ECHO (1 << 0) /* Enable echo */
@@ -142,29 +138,43 @@
#define VSUSP 8 /* SUSP character */
#define NCCS 9 /* Size of the array c_cc for control characters */
-/* Baud Rate Selection (objects of type speed_t) */
-
-#define B0 0 /* Hang up */
-#define B50 1 /* 50 baud */
-#define B75 2 /* 75 baud */
-#define B110 3 /* 110 baud */
-#define B134 4 /* 134.5 baud */
-#define B150 5 /* 150 baud */
-#define B200 6 /* 200 baud */
-#define B300 7 /* 300 baud */
-#define B600 8 /* 600 baud */
-#define B1200 9 /* 1,200 baud */
-#define B1800 10 /* 1,800 baud */
-#define B2400 11 /* 2,400 baud */
-#define B4800 12 /* 4,800 baud */
-#define B9600 13 /* 9,600 baud */
-#define B19200 14 /* 19,200 baud */
-#define B38400 15 /* 38,400 baud */
-#define B57600 16 /* 57,600 baud */
-#define B115200 17 /* 115,200 baud */
-#define B230400 18 /* 230,400 baud */
-#define B460800 19 /* 460,800 baud */
-#define B921600 20 /* 921,600 baud */
+/* Baud Rate Selection (objects of type speed_t). NOTE that as a simplification
+ * in NuttX, the value of the baud symbol is the buad rate itself; not an encoded
+ * value as you will see in most implementations of termios.h.
+ */
+
+#define B0 0 /* Hang up */
+#define B50 50 /* 50 baud */
+#define B75 75 /* 75 baud */
+#define B110 110 /* 110 baud */
+#define B134 134 /* 134.5 baud */
+#define B150 150 /* 150 baud */
+#define B200 200 /* 200 baud */
+#define B300 300 /* 300 baud */
+#define B600 600 /* 600 baud */
+#define B1200 1200 /* 1,200 baud */
+#define B1800 1800 /* 1,800 baud */
+#define B2400 2400 /* 2,400 baud */
+#define B4800 4800 /* 4,800 baud */
+#define B9600 9600 /* 9,600 baud */
+#define B19200 19200 /* 19,200 baud */
+#define B38400 38400 /* 38,400 baud */
+
+#define B57600 57600 /* 57,600 baud */
+#define B115200 115200 /* 115,200 baud */
+#define B128000 128000 /* 128,000 baud */
+#define B230400 230400 /* 230,400 baud */
+#define B256000 256000 /* 256,000 baud */
+#define B460800 460800 /* 460,800 baud */
+#define B500000 500000 /* 500,000 baud */
+#define B576000 576000 /* 576,000 baud */
+#define B921600 921600 /* 921,600 baud */
+#define B1000000 1000000 /* 1,000,000 baud */
+#define B1152000 1152000 /* 1,152,000 baud */
+#define B1500000 1500000 /* 1,500,000 baud */
+#define B2000000 2000000 /* 2,000,000 baud */
+#define B2500000 2500000 /* 2,500,000 baud */
+#define B3000000 3000000 /* 3,000,000 baud */
/* Attribute Selection (used with tcsetattr()) */
@@ -191,7 +201,7 @@
/* Baud rate selection */
-typedef uint8_t speed_t; /* Used for terminal baud rates */
+typedef uint32_t speed_t; /* Used for terminal baud rates */
/* Types used within the termios structure */
@@ -202,11 +212,21 @@ typedef int cc_t; /* Used for terminal special characters */
struct termios
{
+ /* Exposed fields defined by POSIX */
+
tcflag_t c_iflag; /* Input modes */
tcflag_t c_oflag; /* Output modes */
tcflag_t c_cflag; /* Control modes */
tcflag_t c_lflag; /* Local modes */
cc_t c_cc[NCCS]; /* Control chars */
+
+ /* Implementation specific fields. For portability reasons, these fields
+ * should not be accessed directly, but rather through only through the
+ * cf[set|get][o|i]speed() POSIX interfaces.
+ */
+
+ speed_t c_ispeed; /* Input speed */
+ speed_t c_ospeed; /* Output speed */
};
/****************************************************************************