summaryrefslogtreecommitdiff
path: root/nuttx/include
diff options
context:
space:
mode:
authorpatacongo <patacongo@42af7a65-404d-4744-a932-0658087f49c3>2011-07-01 22:23:54 +0000
committerpatacongo <patacongo@42af7a65-404d-4744-a932-0658087f49c3>2011-07-01 22:23:54 +0000
commitcdd11552fc1366a0280fe01bfef875344a967b1c (patch)
tree2b71ce05f5afc630b8d7f56719c3691c28400353 /nuttx/include
parent00b2545e9e3cc760255aa7b4fc953ad5ab97ba62 (diff)
downloadpx4-nuttx-cdd11552fc1366a0280fe01bfef875344a967b1c.tar.gz
px4-nuttx-cdd11552fc1366a0280fe01bfef875344a967b1c.tar.bz2
px4-nuttx-cdd11552fc1366a0280fe01bfef875344a967b1c.zip
Add termios header files; add files missed in last commit
git-svn-id: svn://svn.code.sf.net/p/nuttx/code/trunk@3739 42af7a65-404d-4744-a932-0658087f49c3
Diffstat (limited to 'nuttx/include')
-rw-r--r--nuttx/include/nuttx/ioctl.h25
-rw-r--r--nuttx/include/nuttx/tioctl.h197
-rw-r--r--nuttx/include/termios.h236
3 files changed, 446 insertions, 12 deletions
diff --git a/nuttx/include/nuttx/ioctl.h b/nuttx/include/nuttx/ioctl.h
index 30a8bd5f6..a13518a7a 100644
--- a/nuttx/include/nuttx/ioctl.h
+++ b/nuttx/include/nuttx/ioctl.h
@@ -1,7 +1,7 @@
/****************************************************************************
* include/nuttx/ioctl.h
*
- * Copyright (C) 2008, 2009 Gregory Nutt. All rights reserved.
+ * Copyright (C) 2008, 2009, 2011 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <spudmonkey@racsa.co.cr>
*
* Redistribution and use in source and binary forms, with or without
@@ -45,7 +45,7 @@
/****************************************************************************
* Pre-Processor Definitions
****************************************************************************/
-
+/* General ioctl definitions ************************************************/
/* Each NuttX ioctl commands are uint16_t's consisting of an 8-bit type
* identifier and an 8-bit command number. All comman type identifiers are
* defined below:
@@ -68,23 +68,23 @@
#define _IOC(type,nr) ((type)|(nr))
-/* Terminal I/O ioctl commands */
+/* Terminal I/O ioctl commands **********************************************/
#define _TIOCVALID(c) (_IOC_TYPE(c)==_TIOCBASE)
#define _TIOC(nr) _IOC(_TIOCBASE,nr)
-#define TIOCSBRK _TIOC(0x0001) /* BSD compatibility */
-#define TIOCCBRK _TIOC(0x0002) /* " " " " */
-#define TIOCSERGSTRUCT _TIOC(0x0003) /* Get up_dev_t for port */
+/* Terminal I/O IOCTL definitions are retained in tioctl.h */
+
+#include <nuttx/tioctl.h>
-/* Watchdog driver ioctl commands */
+/* Watchdog driver ioctl commands *******************************************/
#define _WDIOCVALID(c) (_IOC_TYPE(c)==_WDIOCBASE)
#define _WDIOC(nr) _IOC(_WDIOCBASE,nr)
#define WDIOC_KEEPALIVE _WDIOC(0x0001) /* Restart the watchdog timer */
-/* NuttX file system ioctl definitions */
+/* NuttX file system ioctl definitions **************************************/
#define _FIOCVALID(c) (_IOC_TYPE(c)==_FIOCBASE)
#define _FIOC(nr) _IOC(_FIOCBASE,nr)
@@ -101,7 +101,7 @@
* OUT: None
*/
-/* NuttX file system ioctl definitions */
+/* NuttX file system ioctl definitions **************************************/
#define _DIOCVALID(c) (_IOC_TYPE(c)==_DIOCBASE)
#define _DIOC(nr) _IOC(_DIOCBASE,nr)
@@ -116,7 +116,7 @@
* FIOC_GETPRIV released.
*/
-/* NuttX block driver ioctl definitions */
+/* NuttX block driver ioctl definitions *************************************/
#define _BIOCVALID(c) (_IOC_TYPE(c)==_BIOCBASE)
#define _BIOC(nr) _IOC(_BIOCBASE,nr)
@@ -136,7 +136,8 @@
* IN: None
* OUT: None (ioctl return value provides
* success/failure indication). */
-/* NuttX MTD driver ioctl definitions */
+
+/* NuttX MTD driver ioctl definitions ***************************************/
#define _MTDIOCVALID(c) (_IOC_TYPE(c)==_MTDIOCBASE)
#define _MTDIOC(nr) _IOC(_MTDIOCBASE,nr)
@@ -154,7 +155,7 @@
#define MTDIOC_BULKERASE _MTDIOC(0x0003) /* IN: None
* OUT: None */
-/* NuttX ARP driver ioctl definitions (see netinet/arp.h) */
+/* NuttX ARP driver ioctl definitions (see netinet/arp.h) *******************/
#define _ARPIOCVALID(c) (_IOC_TYPE(c)==_ARPBASE)
#define _ARPIOC(nr) _IOC(_ARPBASE,nr)
diff --git a/nuttx/include/nuttx/tioctl.h b/nuttx/include/nuttx/tioctl.h
new file mode 100644
index 000000000..c45ebc0b1
--- /dev/null
+++ b/nuttx/include/nuttx/tioctl.h
@@ -0,0 +1,197 @@
+/********************************************************************************************
+ * include/nuttx/tioctl.h
+ *
+ * Copyright (C) 2011 Gregory Nutt. All rights reserved.
+ * Author: Gregory Nutt <spudmonkey@racsa.co.cr>
+ *
+ * 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.
+ *
+ ********************************************************************************************/
+/* This function should not be included directly. Rather, it should be included indirectly
+ * via include/nuttx/ioctl.h.
+ */
+
+#ifndef __INCLUDE_NUTTX_TIOCTL_H
+#define __INCLUDE_NUTTX_TIOCTL_H
+
+/********************************************************************************************
+ * Included Files
+ ********************************************************************************************/
+
+#include <stdint.h>
+
+/********************************************************************************************
+ * Pre-Processor Definitions
+ ********************************************************************************************/
+
+ /* Get and Set Terminal Attributes */
+
+#define TCGETS _TIOC(0x0001) /* Get serial port settings: FAR struct termios* */
+#define TCSETS _TIOC(0x0002) /* Set serial port settings: FAR const struct termios* */
+#define TCSETSW _TIOC(0x0003) /* Drain output and set serial port settings: FAR const struct termios* */
+#define TCSETSF _TIOC(0x0004) /* Drain output, discard intput, and set serial port settings: FAR const struct termios* */
+#define TCGETA _TIOC(0x0005) /* See TCGETS: FAR struct termio* */
+#define TCSETA _TIOC(0x0006) /* See TCSETS: FAR const struct termio* */
+#define TCSETAW _TIOC(0x0007) /* See TCSETSF: FAR const struct termio* */
+#define TCSETAF _TIOC(0x0008) /* See TCSETSF: FAR const struct termio* */
+
+/* Locking the termios structure */
+
+#define TIOCGLCKTRMIOS _TIOC(0x0009) /* Get termios lock status: struct termios* */
+#define TIOCSLCKTRMIOS _TIOC(0x000a) /* Set termios lock status: const struct termios* */
+
+/* Get and Set Window Size */
+
+#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(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(0x0011) /* Control flow control: int */
+
+/* Buffer count and flushing */
+
+#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(0x0015) /* Insert into input: const char* */
+
+/* Re-directing console output */
+
+#define TIOCCONS _TIOC(0x0016) /* Re-direct console output to device: void */
+
+/* Controlling TTY */
+
+#define TIOCSCTTY _TIOC(0x0017) /* Make controlling TTY: int */
+#define TIOCNOTTY _TIOC(0x0018) /* Give up controllinog TTY: void */
+
+/* Exclusive mode */
+
+#define TIOCEXCL _TIOC(0x0019) /* Put TTY in exclusive mode: void */
+#define TIOCNXCL _TIOC(0x001a) /* Disable exclusive mode: void */
+
+/* Line discipline */
+
+#define TIOCGETD _TIOC(0x001b) /* Get line discipline: FAR int* */
+#define TIOCSETD _TIOC(0x001c) /* Set line discipline: FAR const int* */
+
+/* Packet mode */
+
+#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 */
+# define TIOCPKT_STOP (1 << 2) /* Output to the terminal is stopped */
+# define TIOCPKT_START (1 << 3) /* Output to the terminal is restarted */
+# define TIOCPKT_DOSTOP (1 << 4) /* t_stopc is '^S' and t_startc is '^Q' */
+# define TIOCPKT_NOSTOP (1 << 5) /* The start and stop characters are not '^S/^Q' */
+
+/* Modem control */
+
+#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) */
+# define TIOCM_RTS (1 << 2) /* RTS (request to send) */
+# define TIOCM_ST (1 << 3) /* Secondary TXD (transmit) */
+# define TIOCM_SR (1 << 4) /* Secondary RXD (receive) */
+# define TIOCM_CTS (1 << 5) /* CTS (clear to send) */
+# define TIOCM_CAR (1 << 6) /* DCD (data carrier detect) */
+# define TIOCM_CD TIOCM_CAR
+# define TIOCM_RNG (1 << 7) /* RNG (ring) */
+# define TIOCM_RI TIOCM_RNG
+# define TIOCM_DSR (1 << 8) /* DSR (data set ready) */
+
+/* TTY shutdown */
+
+#define TIOCVHANGUP _TIOC(0x0022) /* Shutdown TTY: void */
+
+/* Marking a line as local */
+
+#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(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(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* */
+
+/* Debugging */
+
+#define TIOCSERGSTRUCT _TIOC(0x002a) /* Get device TTY structure */
+
+/********************************************************************************************
+ * Public Type Definitions
+ ********************************************************************************************/
+
+/* Used with TTY ioctls */
+
+struct winsize
+{
+ uint16_t ws_row;
+ uint16_t ws_col;
+/* uint16_t ws_xpixel; unused */
+/* uint16_t ws_ypixel; unused */
+};
+
+/********************************************************************************************
+ * Public Function Prototypes
+ ********************************************************************************************/
+
+#ifdef __cplusplus
+#define EXTERN extern "C"
+extern "C" {
+#else
+#define EXTERN extern
+#endif
+
+#undef EXTERN
+#ifdef __cplusplus
+}
+#endif
+
+#endif /* __INCLUDE_NUTTX_TIOCTL_H */
diff --git a/nuttx/include/termios.h b/nuttx/include/termios.h
new file mode 100644
index 000000000..9e87e72a8
--- /dev/null
+++ b/nuttx/include/termios.h
@@ -0,0 +1,236 @@
+/****************************************************************************
+ * include/termios.h
+ *
+ * Copyright (C) 2011 Gregory Nutt. All rights reserved.
+ * Author: Gregory Nutt <spudmonkey@racsa.co.cr>
+ *
+ * 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_TERMIOS_H
+#define __INCLUDE_TERMIOS_H
+
+/****************************************************************************
+ * Included Files
+ ****************************************************************************/
+
+#include <nuttx/config.h>
+#include <sys/types.h>
+#include <stdint.h>
+
+/****************************************************************************
+ * Pre-Processor Definitions
+ ****************************************************************************/
+
+/* Terminal input modes (c_iflag in the termios structure) */
+
+#define BRKINT (1 << 0) /* Signal interrupt on break */
+#define ICRNL (1 << 1) /* Map CR to NL on input */
+#define IGNBRK (1 << 2) /* Ignore break condition */
+#define IGNCR (1 << 3) /* Ignore CR */
+#define IGNPAR (1 << 4) /* Ignore characters with parity errors */
+#define INLCR (1 << 5) /* Map NL to CR on input */
+#define INPCK (1 << 6) /* Enable input parity check */
+#define ISTRIP (1 << 7) /* Strip character */
+#define IUCLC (1 << 8) /* Map upper-case to lower-case on input (LEGACY) */
+#define IXANY (1 << 9) /* Enable any character to restart output */
+#define IXOFF (1 << 10) /* Enable start/stop input control */
+#define IXON (1 << 11) /* Enable start/stop output control */
+#define PARMRK (1 << 12) /* Mark parity errors */
+
+/* Terminal output modes (c_oflag in the termios structure) */
+
+#define OPOST (1 << 0) /* Post-process output */
+#define OLCUC (1 << 1) /* Map lower-case to upper-case on output (LEGACY) */
+#define ONLCR (1 << 2) /* Map NL to CR-NL on output */
+#define OCRNL (1 << 3) /* Map CR to NL on output */
+#define ONOCR (1 << 4) /* No CR output at column 0 */
+#define ONLRET (1 << 5) /* NL performs CR function */
+#define OFILL (1 << 6) /* Use fill characters for delay */
+#define NLDLY (1 << 7) /* Select newline delays: */
+# define NL0 (0 << 7) /* Newline character type 0 */
+# define NL1 (1 << 7) /* Newline character type 1 */
+#define CRDLY (3 << 8) /* Select carriage-return delays: */
+# define CR0 (0 << 8) /* Carriage-return delay type 0 */
+# define CR1 (1 << 8) /* Carriage-return delay type 1 */
+# define CR2 (2 << 8) /* Carriage-return delay type 2 */
+# define CR3 (3 << 8) /* Carriage-return delay type 3 */
+#define TABDLY (3 << 10) /* Select horizontal-tab delays: */
+# define TAB0 (0 << 10) /* Horizontal-tab delay type 0 */
+# define TAB1 (1 << 10) /* Horizontal-tab delay type 1 */
+# define TAB2 (2 << 10) /* Horizontal-tab delay type 2 */
+# define TAB3 (3 << 10) /* Expand tabs to spaces */
+#define BSDLY (1 << 12) /* Select backspace delays: */
+# define BS0 (0 << 12) /* Backspace-delay type 0 */
+# define BS1 (1 << 12) /* Backspace-delay type 1 */
+#define VTDLY (1 << 13) /* Select vertical-tab delays: */
+# define VT0 (0 << 13) /* Vertical-tab delay type 0 */
+# define VT1 (1 << 13) /* Vertical-tab delay type 1 */
+#define FFDLY (1 << 14) /* Select form-feed delays: */
+# define FF0 (0 << 14) /* Form-feed delay type 0 */
+# define FF1 (1 << 14) /* Form-feed delay type 1 */
+
+/* Control Modes (c_cflag in the termios structure) */
+
+#define CSIZE (3 << 0) /* Character size: */
+# define CS5 (0 << 0) /* 5 bits */
+# define CS6 (1 << 0) /* 6 bits */
+# define CS7 (2 << 0) /* 7 bits */
+# define CS8 (3 << 0) /* 8 bits */
+#define CSTOPB (1 << 2) /* Send two stop bits, else one */
+#define CREAD (1 << 3) /* Enable receiver */
+#define PARENB (1 << 4) /* Parity enable */
+#define PARODD (1 << 5) /* Odd parity, else even */
+#define HUPCL (1 << 6) /* Hang up on last close */
+#define CLOCAL (1 << 7) /* Ignore modem status lines */
+
+/* Local Modes (c_lflag in the termios structure) */
+
+#define ECHO (1 << 0) /* Enable echo */
+#define ECHOE (1 << 1) /* Echo erase character as error-correcting backspace */
+#define ECHOK (1 << 2) /* Echo KILL */
+#define ECHONL (1 << 3) /* Echo NL */
+#define ICANON (1 << 4) /* Canonical input (erase and kill processing) */
+#define IEXTEN (1 << 5) /* Enable extended input character processing */
+#define ISIG (1 << 6) /* Enable signals */
+#define NOFLSH (1 << 7) /* Disable flush after interrupt or quit */
+#define TOSTOP (1 << 8) /* Send SIGTTOU for background output */
+#define XCASE (1 << 9) /* Canonical upper/lower presentation (LEGACY) */
+
+/* The following are subscript names for the termios c_cc array */
+
+#define VEOF 0 /* EOF character (canonical mode) */
+#define VMIN VEOF /* MIN value (Non-canonical mode) */
+#define VEOL 1 /* EOL character (canonical mode) */
+#define VTIME VEOL /* TIME value (Non-canonical mode) */
+#define VERASE 2 /* ERASE character (canonical mode) */
+#define VINTR 3 /* INTR character */
+#define VKILL 4 /* KILL character (canonical mode) */
+#define VQUIT 5 /* QUIT character */
+#define VSTART 6 /* START character */
+#define VSTOP 7 /* STOP character */
+#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 */
+
+/* Attribute Selection (used with tcsetattr()) */
+
+#define TCSANOW 0 /* Change attributes immediately */
+#define TCSADRAIN 1 /* Change attributes when output has drained */
+#define TCSAFLUSH 2 /* Change attributes when output has drained; also flush pending input */
+
+/* Line Control (used with tcflush()) */
+
+#define TCIFLUSH 0 /* Flush pending input. Flush untransmitted output */
+#define TCIOFLUSH 1 /* Flush both pending input and untransmitted output */
+#define TCOFLUSH 2 /* Flush untransmitted output */
+
+/* Constants for use with tcflow() */
+
+#define TCIOFF 0 /* Transmit a STOP character, intended to suspend input data */
+#define TCION 1 /* Transmit a START character, intended to restart input data */
+#define TCOOFF 2 /* Suspend output */
+#define TCOON 3 /* Restart output */
+
+/****************************************************************************
+ * Public Type Definitions
+ ****************************************************************************/
+
+/* Baud rate selection */
+
+typedef uint8_t speed_t; /* Used for terminal baud rates */
+
+/* Types used within the termios structure */
+
+typedef uint16_t tcflag_t; /* Used for terminal modes */
+typedef int cc_t; /* Used for terminal special characters */
+
+/* The termios structure */
+
+struct termios
+{
+ 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 */
+};
+
+/****************************************************************************
+ * Public Function Prototypes
+ ****************************************************************************/
+
+#ifdef __cplusplus
+#define EXTERN extern "C"
+extern "C" {
+#else
+#define EXTERN extern
+#endif
+
+EXTERN speed_t cfgetispeed(const struct termios *);
+EXTERN speed_t cfgetospeed(const struct termios *);
+EXTERN int cfsetispeed(struct termios *, speed_t);
+EXTERN int cfsetospeed(struct termios *, speed_t);
+EXTERN int tcdrain(int);
+EXTERN int tcflow(int, int);
+EXTERN int tcflush(int, int);
+EXTERN int tcgetattr(int, struct termios *);
+EXTERN pid_t tcgetsid(int);
+EXTERN int tcsendbreak(int, int);
+EXTERN int tcsetattr(int, int, struct termios *);
+
+#undef EXTERN
+#ifdef __cplusplus
+}
+#endif
+
+#endif /* __INCLUDE_TERMIOS_H */