summaryrefslogtreecommitdiff
path: root/nuttx/lib
diff options
context:
space:
mode:
authorpatacongo <patacongo@42af7a65-404d-4744-a932-0658087f49c3>2012-07-22 18:56:50 +0000
committerpatacongo <patacongo@42af7a65-404d-4744-a932-0658087f49c3>2012-07-22 18:56:50 +0000
commit92ee042ea3f2cd97bcca3f1d752ec68dac919d85 (patch)
tree3031e9ab44fcd5d158aa160ee01517a0eb409a94 /nuttx/lib
parent60375dcc5d9c24b5919f66f63ac70879e653c350 (diff)
downloadpx4-nuttx-92ee042ea3f2cd97bcca3f1d752ec68dac919d85.tar.gz
px4-nuttx-92ee042ea3f2cd97bcca3f1d752ec68dac919d85.tar.bz2
px4-nuttx-92ee042ea3f2cd97bcca3f1d752ec68dac919d85.zip
Loosen up termios interfaces to allow more flexible baud settings; remove AIX-like interfaces of last check-in
git-svn-id: svn://svn.code.sf.net/p/nuttx/code/trunk@4969 42af7a65-404d-4744-a932-0658087f49c3
Diffstat (limited to 'nuttx/lib')
-rw-r--r--nuttx/lib/termios/Make.defs6
-rw-r--r--nuttx/lib/termios/lib_cfgetispeed.c11
-rw-r--r--nuttx/lib/termios/lib_cfgetospeed.c11
-rw-r--r--nuttx/lib/termios/lib_cfsetispeed.c13
-rw-r--r--nuttx/lib/termios/lib_cfsetospeed.c13
-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
8 files changed, 32 insertions, 359 deletions
diff --git a/nuttx/lib/termios/Make.defs b/nuttx/lib/termios/Make.defs
index b16231004..194482a55 100644
--- a/nuttx/lib/termios/Make.defs
+++ b/nuttx/lib/termios/Make.defs
@@ -37,14 +37,8 @@ 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_cfgetispeed.c b/nuttx/lib/termios/lib_cfgetispeed.c
index 9c57b094f..d7ca5f5a5 100644
--- a/nuttx/lib/termios/lib_cfgetispeed.c
+++ b/nuttx/lib/termios/lib_cfgetispeed.c
@@ -70,8 +70,13 @@
* This function shall return exactly the value in the termios data
* structure, without interpretation.
*
- * NOTE: NuttX does not no control input/output baud rates independently
- * This function is *identical* to cfgetospeed
+ * NON STANDARD BEHAVIOR. In Nuttx, the speed_t is defined to be uint32_t
+ * and the baud encodings of termios.h are the actual baud values
+ * themselves. Therefore, any baud value can be provided as the speed
+ * argument here. However, if you do so, your code will *NOT* be portable
+ * to other environments where speed_t is smaller and where the termios.h
+ * baud values are encoded! To avoid portability issues, use the baud
+ * definitions in termios.h!
*
* Input Parameters:
* termiosp - The termiosp argument is a pointer to a termios structure.
@@ -84,5 +89,5 @@
speed_t cfgetispeed(const struct termios *termios_p)
{
DEBUGASSERT(termios_p);
- return (speed_t)((termios_p->c_cflag & CBAUD) >> _CBAUD_SHIFT);
+ return termios_p->c_ispeed;
}
diff --git a/nuttx/lib/termios/lib_cfgetospeed.c b/nuttx/lib/termios/lib_cfgetospeed.c
index bc6a47bb0..89b4d619c 100644
--- a/nuttx/lib/termios/lib_cfgetospeed.c
+++ b/nuttx/lib/termios/lib_cfgetospeed.c
@@ -70,8 +70,13 @@
* This function shall return exactly the value in the termios data
* structure, without interpretation.
*
- * NOTE: NuttX does not no control input/output baud rates independently
- * This function is *identical* to cfgetispeed
+ * NON STANDARD BEHAVIOR. In Nuttx, the speed_t is defined to be uint32_t
+ * and the baud encodings of termios.h are the actual baud values
+ * themselves. Therefore, any baud value can be provided as the speed
+ * argument here. However, if you do so, your code will *NOT* be portable
+ * to other environments where speed_t is smaller and where the termios.h
+ * baud values are encoded! To avoid portability issues, use the baud
+ * definitions in termios.h!
*
* Input Parameters:
* termiosp - The termiosp argument is a pointer to a termios structure.
@@ -84,5 +89,5 @@
speed_t cfgetospeed(const struct termios *termios_p)
{
DEBUGASSERT(termios_p);
- return (speed_t)((termios_p->c_cflag & CBAUD) >> _CBAUD_SHIFT);
+ return termios_p->c_ospeed;
}
diff --git a/nuttx/lib/termios/lib_cfsetispeed.c b/nuttx/lib/termios/lib_cfsetispeed.c
index c1e3607cc..20a05e501 100644
--- a/nuttx/lib/termios/lib_cfsetispeed.c
+++ b/nuttx/lib/termios/lib_cfsetispeed.c
@@ -71,8 +71,13 @@
* There is no effect on the baud rates set in the hardware until a
* subsequent successful call to tcsetattr() on the same termios structure.
*
- * NOTE: NuttX does not no control input/output baud rates independently
- * This function is *identical* to cfsetospeed
+ * NON STANDARD BEHAVIOR. In Nuttx, the speed_t is defined to be uint32_t
+ * and the baud encodings of termios.h are the actual baud values
+ * themselves. Therefore, any baud value can be provided as the speed
+ * argument here. However, if you do so, your code will *NOT* be portable
+ * to other environments where speed_t is smaller and where the termios.h
+ * baud values are encoded! To avoid portability issues, use the baud
+ * definitions in termios.h!
*
* Input Parameters:
* termiosp - The termiosp argument is a pointer to a termios structure.
@@ -86,8 +91,6 @@
int cfsetispeed(struct termios *termios_p, speed_t speed)
{
DEBUGASSERT(termios_p);
-
- termios_p->c_cflag &= ~CBAUD;
- termios_p->c_cflag |= ((tcflag_t)speed << _CBAUD_SHIFT);
+ termios_p->c_ispeed = speed;
return OK;
}
diff --git a/nuttx/lib/termios/lib_cfsetospeed.c b/nuttx/lib/termios/lib_cfsetospeed.c
index 662de7382..4a30699e9 100644
--- a/nuttx/lib/termios/lib_cfsetospeed.c
+++ b/nuttx/lib/termios/lib_cfsetospeed.c
@@ -71,8 +71,13 @@
* There is no effect on the baud rates set in the hardware until a
* subsequent successful call to tcsetattr() on the same termios structure.
*
- * NOTE: NuttX does not no control input/output baud rates independently
- * This function is *identical* to cfsetispeed
+ * NON STANDARD BEHAVIOR. In Nuttx, the speed_t is defined to be uint32_t
+ * and the baud encodings of termios.h are the actual baud values
+ * themselves. Therefore, any baud value can be provided as the speed
+ * argument here. However, if you do so, your code will *NOT* be portable
+ * to other environments where speed_t is smaller and where the termios.h
+ * baud values are encoded! To avoid portability issues, use the baud
+ * definitions in termios.h!
*
* Input Parameters:
* termiosp - The termiosp argument is a pointer to a termios structure.
@@ -86,8 +91,6 @@
int cfsetospeed(struct termios *termios_p, speed_t speed)
{
DEBUGASSERT(termios_p);
-
- termios_p->c_cflag &= ~CBAUD;
- termios_p->c_cflag |= ((tcflag_t)speed << _CBAUD_SHIFT);
+ termios_p->c_ospeed = speed;
return OK;
}
diff --git a/nuttx/lib/termios/lib_getspeed.c b/nuttx/lib/termios/lib_getspeed.c
deleted file mode 100644
index dbc3686b3..000000000
--- a/nuttx/lib/termios/lib_getspeed.c
+++ /dev/null
@@ -1,118 +0,0 @@
-/****************************************************************************
- * 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
deleted file mode 100644
index 8da9cdc78..000000000
--- a/nuttx/lib/termios/lib_resetspeed.c
+++ /dev/null
@@ -1,109 +0,0 @@
-/****************************************************************************
- * 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
deleted file mode 100644
index 13a0cc57a..000000000
--- a/nuttx/lib/termios/lib_setspeed.c
+++ /dev/null
@@ -1,110 +0,0 @@
-/****************************************************************************
- * 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);
-}