summaryrefslogtreecommitdiff
diff options
context:
space:
mode:
authorpatacongo <patacongo@42af7a65-404d-4744-a932-0658087f49c3>2012-07-22 17:01:25 +0000
committerpatacongo <patacongo@42af7a65-404d-4744-a932-0658087f49c3>2012-07-22 17:01:25 +0000
commit107fe46fc6359ec1b5169c960fa8bd4fc619b23b (patch)
treec354a0def4a0d161c44db903e32314b76d88f901
parent4b91bbe4ddedd7090ccbe8a93b9f5075de7bdd6a (diff)
downloadpx4-nuttx-107fe46fc6359ec1b5169c960fa8bd4fc619b23b.tar.gz
px4-nuttx-107fe46fc6359ec1b5169c960fa8bd4fc619b23b.tar.bz2
px4-nuttx-107fe46fc6359ec1b5169c960fa8bd4fc619b23b.zip
Add support for extended BAUD settings
git-svn-id: svn://svn.code.sf.net/p/nuttx/code/trunk@4967 42af7a65-404d-4744-a932-0658087f49c3
-rw-r--r--nuttx/ChangeLog5
-rw-r--r--nuttx/include/nuttx/serial/tioctl.h120
-rw-r--r--nuttx/include/sys/str_tty.h100
-rw-r--r--nuttx/lib/termios/Make.defs8
-rw-r--r--nuttx/lib/termios/lib_getspeed.c118
-rw-r--r--nuttx/lib/termios/lib_resetspeed.c109
-rw-r--r--nuttx/lib/termios/lib_setspeed.c110
-rw-r--r--nuttx/lib/termios/lib_tcflush.c2
8 files changed, 513 insertions, 59 deletions
diff --git a/nuttx/ChangeLog b/nuttx/ChangeLog
index 24085859e..c92f581c0 100644
--- a/nuttx/ChangeLog
+++ b/nuttx/ChangeLog
@@ -3035,4 +3035,9 @@
* arch/arm/src/lpc43xx/lpc43_serial.c: Add support for certain RS-485 features
* lib/termios/lib_cfsetispeed.c, lib_cfsetospeed.c, lib_tcflush.c: Add
simple implementations of cfsetispeed(), cfsetospeed(), and tcflush().
+ * include/sys/str_tty.h, lib/lib_setspeed.c, lib_getspeed.c, and lib_resetspeed.c:
+ Add APIs to support setting non-standard BAUD values not supported by POSIX
+ termios. These are non-standard interfaces but have a precedence: There are
+ similar interfaces in AIX.
+
diff --git a/nuttx/include/nuttx/serial/tioctl.h b/nuttx/include/nuttx/serial/tioctl.h
index bae2f2c8d..6862d7453 100644
--- a/nuttx/include/nuttx/serial/tioctl.h
+++ b/nuttx/include/nuttx/serial/tioctl.h
@@ -49,70 +49,76 @@
* Pre-Processor Definitions
********************************************************************************************/
-/* Get and Set Terminal Attributes */
+/* Get and Set Terminal Attributes (see termios.h) */
-#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 */
+#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 */
+#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(0x000b) /* Get window size: FAR struct winsize */
-#define TIOCSWINSZ _TIOC(0x000c) /* Set window size: FAR const struct winsize */
+#define TIOCGWINSZ _TIOC(0x000e) /* Get window size: FAR struct winsize */
+#define TIOCSWINSZ _TIOC(0x000f) /* 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 */
+#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 */
/* Software flow control */
-#define TCXONC _TIOC(0x0011) /* Control flow control: int */
+#define TCXONC _TIOC(0x0014) /* 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 */
+#define TIOCINQ _TIOC(0x0015) /* Bytes in input buffer: int */
+#define TIOCOUTQ _TIOC(0x0016) /* Bytes in output buffer: int */
+#define TCFLSH _TIOC(0x0017) /* Flush: int */
/* Faking input */
-#define TIOCSTI _TIOC(0x0015) /* Insert into input: const char */
+#define TIOCSTI _TIOC(0x0018) /* Insert into input: const char */
/* Re-directing console output */
-#define TIOCCONS _TIOC(0x0016) /* Re-direct console output to device: void */
+#define TIOCCONS _TIOC(0x0019) /* 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 */
+#define TIOCSCTTY _TIOC(0x001a) /* Make controlling TTY: int */
+#define TIOCNOTTY _TIOC(0x001b) /* 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 */
+#define TIOCEXCL _TIOC(0x001c) /* Put TTY in exclusive mode: void */
+#define TIOCNXCL _TIOC(0x001d) /* 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 */
+#define TIOCGETD _TIOC(0x001e) /* Get line discipline: FAR int */
+#define TIOCSETD _TIOC(0x001f) /* Set line discipline: FAR const int */
/* Packet mode */
-#define TIOCPKT _TIOC(0x001d) /* Control packet mode: FAR const int */
+#define TIOCPKT _TIOC(0x0020) /* 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 */
@@ -123,51 +129,51 @@
/* 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) */
+#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 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 */
+#define TIOCVHANGUP _TIOC(0x0025) /* 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 */
+#define TIOCGSOFTCAR _TIOC(0x0026) /* Get software carrier flag: FAR int */
+#define TIOCSSOFTCAR _TIOC(0x0027) /* 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 */
+#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 */
/* 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 */
+#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 */
/* RS-485 Support */
-#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 */
+#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 */
/* Debugging */
-#define TIOCSERGSTRUCT _TIOC(0x002c) /* Get device TTY structure */
+#define TIOCSERGSTRUCT _TIOC(0x002f) /* 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
new file mode 100644
index 000000000..2ae17ef95
--- /dev/null
+++ b/nuttx/include/sys/str_tty.h
@@ -0,0 +1,100 @@
+/****************************************************************************
+ * 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/lib/termios/Make.defs b/nuttx/lib/termios/Make.defs
index 645b6459d..b16231004 100644
--- a/nuttx/lib/termios/Make.defs
+++ b/nuttx/lib/termios/Make.defs
@@ -36,7 +36,15 @@
TERMIOS_SRCS =
ifneq ($(CONFIG_NFILE_DESCRIPTORS),0)
+
+# POSIX standard interfaces
+
TERMIOS_SRCS += lib_cfgetispeed.c lib_cfgetospeed.c lib_cfsetispeed.c
TERMIOS_SRCS += lib_cfsetospeed.c lib_tcflush.c lib_tcgetattr.c
TERMIOS_SRCS += lib_tcsetattr.c
+
+# Non-standard AIX-like interfaces
+
+TERMIOS_SRCS += lib_getspeed.c lib_resetspeed.c lib_setspeed.c
+
endif
diff --git a/nuttx/lib/termios/lib_getspeed.c b/nuttx/lib/termios/lib_getspeed.c
new file mode 100644
index 000000000..dbc3686b3
--- /dev/null
+++ b/nuttx/lib/termios/lib_getspeed.c
@@ -0,0 +1,118 @@
+/****************************************************************************
+ * lib/termios/lib_getspeed.c
+ *
+ * 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.
+ *
+ ****************************************************************************/
+
+/****************************************************************************
+ * Included Files
+ ****************************************************************************/
+
+#include <nuttx/config.h>
+
+#include <sys/str_tty.h>
+#include <sys/ioctl.h>
+
+#include <nuttx/serial/tioctl.h>
+
+/****************************************************************************
+ * Pre-processor Definitions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Variables
+ ****************************************************************************/
+
+/****************************************************************************
+ * Public Variables
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Public Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Name: get_speed
+ *
+ * Descripton:
+ * set_speed(), get_speed(), and reset_speed 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.
+ *
+ * Input Parameters:
+ * fd - The 'fd' argument is an open file descriptor associated with a
+ * terminal.
+ *
+ * Returned Value:
+ * Upon successful completion, the extended baud is returned. Otherwise,
+ * -1 is returned and errno is set to indicate the error.
+ *
+ ****************************************************************************/
+
+int32_t get_speed(int fd)
+{
+ int32_t speed;
+ int ret;
+
+ ret = ioctl(fd, TIOCGETSPEED, (unsigned long)((uintptr_t)&speed));
+ if (ret < 0)
+ {
+ return (int32_t)ret;
+ }
+
+ return speed;
+}
diff --git a/nuttx/lib/termios/lib_resetspeed.c b/nuttx/lib/termios/lib_resetspeed.c
new file mode 100644
index 000000000..8da9cdc78
--- /dev/null
+++ b/nuttx/lib/termios/lib_resetspeed.c
@@ -0,0 +1,109 @@
+/****************************************************************************
+ * lib/termios/lib_resetspeed.c
+ *
+ * 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.
+ *
+ ****************************************************************************/
+
+/****************************************************************************
+ * Included Files
+ ****************************************************************************/
+
+#include <nuttx/config.h>
+
+#include <sys/str_tty.h>
+#include <sys/ioctl.h>
+
+#include <nuttx/serial/tioctl.h>
+
+/****************************************************************************
+ * Pre-processor Definitions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Variables
+ ****************************************************************************/
+
+/****************************************************************************
+ * Public Variables
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Public Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Name: reset_speed
+ *
+ * Descripton:
+ * set_speed(), get_speed(), and reset_speed 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.
+ *
+ * Input Parameters:
+ * fd - The 'fd' argument is an open file descriptor associated with a terminal.
+ * cmd - The TCFLSH ioctl argument.
+ *
+ * Returned Value:
+ * Upon successful completion, 0 is returned. Otherwise, -1 is returned and
+ * errno is set to indicate the error.
+ *
+ ****************************************************************************/
+
+int reset_speed(int fd)
+{
+ return ioctl(fd, TIOCRESETSPEED, 0L);
+}
diff --git a/nuttx/lib/termios/lib_setspeed.c b/nuttx/lib/termios/lib_setspeed.c
new file mode 100644
index 000000000..13a0cc57a
--- /dev/null
+++ b/nuttx/lib/termios/lib_setspeed.c
@@ -0,0 +1,110 @@
+/****************************************************************************
+ * lib/termios/lib_setspeed.c
+ *
+ * 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.
+ *
+ ****************************************************************************/
+
+/****************************************************************************
+ * Included Files
+ ****************************************************************************/
+
+#include <nuttx/config.h>
+
+#include <sys/str_tty.h>
+#include <sys/ioctl.h>
+
+#include <nuttx/serial/tioctl.h>
+
+/****************************************************************************
+ * Pre-processor Definitions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Variables
+ ****************************************************************************/
+
+/****************************************************************************
+ * Public Variables
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Public Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Name: set_speed
+ *
+ * Descripton:
+ * set_speed(), get_speed(), and reset_speed 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.
+ *
+ * Input Parameters:
+ * fd - The 'fd' argument is an open file descriptor associated with a
+ * terminal.
+ * speed - The new, extended baud
+ *
+ * Returned Value:
+ * Upon successful completion, 0 is returned. Otherwise, -1 is returned and
+ * errno is set to indicate the error.
+ *
+ ****************************************************************************/
+
+int set_speed(int fd, int32_t speed)
+{
+ return ioctl(fd, TIOCSETSPEED, (unsigned long)speed);
+}
diff --git a/nuttx/lib/termios/lib_tcflush.c b/nuttx/lib/termios/lib_tcflush.c
index abe3b936b..338524bdd 100644
--- a/nuttx/lib/termios/lib_tcflush.c
+++ b/nuttx/lib/termios/lib_tcflush.c
@@ -84,7 +84,5 @@
int tcflush(int fd, int cmd)
{
- /* Not yet implemented */
-
return ioctl(fd, TCFLSH, (unsigned long)cmd);
}