From d7280d43821c750e6d8aa35ac6f26f811cc6890b Mon Sep 17 00:00:00 2001 From: patacongo Date: Tue, 24 Jul 2012 22:56:36 +0000 Subject: Combine cfset[o|i]speed to cfsetspeed; combine cfget[o|i]speed for cfgetspeed git-svn-id: https://nuttx.svn.sourceforge.net/svnroot/nuttx/trunk@4975 7fd9a85b-ad96-42d3-883c-3090e2eb8679 --- nuttx/ChangeLog | 3 + nuttx/arch/arm/src/lpc43xx/chip/lpc43_sdmmc.h | 5 +- nuttx/arch/arm/src/lpc43xx/lpc43_serial.c | 7 +- nuttx/arch/arm/src/lpc43xx/lpc43_spifi.c | 8 +- nuttx/arch/arm/src/stm32/stm32_serial.c | 7 +- nuttx/arch/mips/src/pic32mx/pic32mx-serial.c | 7 +- nuttx/configs/lpc4330-xplorer/README.txt | 7 +- nuttx/drivers/mtd/ftl.c | 2 +- nuttx/include/termios.h | 70 +++++++++++++--- nuttx/lib/termios/Make.defs | 5 +- nuttx/lib/termios/lib_cfgetispeed.c | 92 --------------------- nuttx/lib/termios/lib_cfgetospeed.c | 92 --------------------- nuttx/lib/termios/lib_cfgetspeed.c | 93 +++++++++++++++++++++ nuttx/lib/termios/lib_cfsetispeed.c | 103 ----------------------- nuttx/lib/termios/lib_cfsetospeed.c | 103 ----------------------- nuttx/lib/termios/lib_cfsetspeed.c | 112 ++++++++++++++++++++++++++ 16 files changed, 295 insertions(+), 421 deletions(-) delete mode 100644 nuttx/lib/termios/lib_cfgetispeed.c delete mode 100644 nuttx/lib/termios/lib_cfgetospeed.c create mode 100644 nuttx/lib/termios/lib_cfgetspeed.c delete mode 100644 nuttx/lib/termios/lib_cfsetispeed.c delete mode 100644 nuttx/lib/termios/lib_cfsetospeed.c create mode 100644 nuttx/lib/termios/lib_cfsetspeed.c (limited to 'nuttx') diff --git a/nuttx/ChangeLog b/nuttx/ChangeLog index 0d29c3db8..0ec8ffb8f 100644 --- a/nuttx/ChangeLog +++ b/nuttx/ChangeLog @@ -3062,4 +3062,7 @@ BOTHER is gone again. * arch/arm/src/stm32/stm32_sdio.c and chip/stm32f20xx_pinmap.h: STM32 F2 SDIO fixes from Gary Teravskis and Scott Rondestvedt. + * include/termios.h and lib/termios/*: Replace cfsetispeed and cfsetospeed with + cfsetspeed (with definitions for the input/outputs in termios.h). Same for + cfgetispeed and cfgetospeed. diff --git a/nuttx/arch/arm/src/lpc43xx/chip/lpc43_sdmmc.h b/nuttx/arch/arm/src/lpc43xx/chip/lpc43_sdmmc.h index 1368312cc..1236d82f3 100644 --- a/nuttx/arch/arm/src/lpc43xx/chip/lpc43_sdmmc.h +++ b/nuttx/arch/arm/src/lpc43xx/chip/lpc43_sdmmc.h @@ -49,7 +49,7 @@ /* MCI register offsets (with respect to the MCI base) ******************************************/ #define LPC43_SDMMC_CTRL_OFFSET 0x0000 /* Control register */ -#define LPC43_SDMMC_PWREN_OFFSET 0x0004 /* Reserved */ +#define LPC43_SDMMC_PWREN_OFFSET 0x0004 /* Power Enable Register */ #define LPC43_SDMMC_CLKDIV_OFFSET 0x0008 /* Clock-divider register */ #define LPC43_SDMMC_CLKSRC_OFFSET 0x000c /* Clock-source register */ #define LPC43_SDMMC_CLKENA_OFFSET 0x0010 /* Clock-enable register */ @@ -61,7 +61,7 @@ #define LPC43_SDMMC_CMDARG_OFFSET 0x0028 /* Command-argument register */ #define LPC43_SDMMC_CMD_OFFSET 0x002c /* Command register */ #define LPC43_SDMMC_RESP0_OFFSET 0x0030 /* Response-0 register */ -#define LPC43_SDMMC_RESP1_OFFSET 0x0034 /* Response-1register */ +#define LPC43_SDMMC_RESP1_OFFSET 0x0034 /* Response-1 register */ #define LPC43_SDMMC_RESP2_OFFSET 0x0038 /* Response-2 register */ #define LPC43_SDMMC_RESP3_OFFSET 0x003c /* Response-3 register */ #define LPC43_SDMMC_MINTSTS_OFFSET 0x0040 /* Masked interrupt-status register */ @@ -313,6 +313,7 @@ /* Bit 24-31: Reserved */ /* Hardware Reset */ + #define SDMMC_RSTN (1 << 0) /* Bit 0: Hardware reset */ /* Bit 1-31: Reserved */ diff --git a/nuttx/arch/arm/src/lpc43xx/lpc43_serial.c b/nuttx/arch/arm/src/lpc43xx/lpc43_serial.c index c125660e1..525cad01d 100644 --- a/nuttx/arch/arm/src/lpc43xx/lpc43_serial.c +++ b/nuttx/arch/arm/src/lpc43xx/lpc43_serial.c @@ -1125,9 +1125,12 @@ static int up_ioctl(struct file *filep, int cmd, unsigned long arg) break; } - /* TODO: Handle other termios settings. */ + /* TODO: Handle other termios settings. + * Note that only cfgetispeed is used besued we have knowledge + * that only one speed is supported. + */ - priv->baud = termiosp->c_speed; + priv->baud = cfgetispeed(termiosp); lpc43_setbaud(priv->uartbase, priv->basefreq, priv->baud); } break; diff --git a/nuttx/arch/arm/src/lpc43xx/lpc43_spifi.c b/nuttx/arch/arm/src/lpc43xx/lpc43_spifi.c index fe26fabc5..8e633e5d1 100644 --- a/nuttx/arch/arm/src/lpc43xx/lpc43_spifi.c +++ b/nuttx/arch/arm/src/lpc43xx/lpc43_spifi.c @@ -77,6 +77,10 @@ * CONFIG_SPIFI_OFFSET - Offset the beginning of the block driver this many * bytes into the device address space. This offset must be an exact * multiple of the erase block size. Default 0. + * CONFIG_SPIFI_BLKSIZE - The size of one device erase block. If not defined + * then the driver will try to determine the correct erase block size by + * examining that data returned from spifi_initialize (which sometimes + * seems bad). * CONFIG_SPIFI_SECTOR512 - If defined, then the driver will report a more * FAT friendly 512 byte sector size and will manage the read-modify-write * operations on the larger erase block. @@ -1082,7 +1086,7 @@ static inline int lpc43_rominit(FAR struct lpc43_dev_s *priv) priv->blkshift = log2; priv->blksize = (1 << log2); - priv->nblocks = priv->rom.memsize / priv->blksize; + priv->nblocks = (priv->rom.memsize - CONFIG_SPIFI_OFFSET) / priv->blksize; fvdbg("Driver FLASH Geometry:\n"); fvdbg(" blkshift: %d\n", priv->blkshift); @@ -1097,7 +1101,7 @@ static inline int lpc43_rominit(FAR struct lpc43_dev_s *priv) /* Save the digested FLASH geometry info */ - priv->nblocks = (priv->rom.memsize >> SPIFI_BLKSHIFT); + priv->nblocks = ((priv->rom.memsize - CONFIG_SPIFI_OFFSET) >> SPIFI_BLKSHIFT); fvdbg("Driver FLASH Geometry:\n"); fvdbg(" blkshift: %d\n", SPIFI_BLKSHIFT); diff --git a/nuttx/arch/arm/src/stm32/stm32_serial.c b/nuttx/arch/arm/src/stm32/stm32_serial.c index 5572ee662..e1d6e4593 100644 --- a/nuttx/arch/arm/src/stm32/stm32_serial.c +++ b/nuttx/arch/arm/src/stm32/stm32_serial.c @@ -1267,9 +1267,12 @@ static int up_ioctl(struct file *filep, int cmd, unsigned long arg) break; } - /* TODO: Handle other termios settings. */ + /* TODO: Handle other termios settings. + * Note that only cfgetispeed is used besued we have knowledge + * that only one speed is supported. + */ - priv->baud = termiosp->c_speed; + priv->baud = cfgetispeed(termiosp); up_setspeed(dev); } break; diff --git a/nuttx/arch/mips/src/pic32mx/pic32mx-serial.c b/nuttx/arch/mips/src/pic32mx/pic32mx-serial.c index 5fc1512b1..4073c2dc6 100644 --- a/nuttx/arch/mips/src/pic32mx/pic32mx-serial.c +++ b/nuttx/arch/mips/src/pic32mx/pic32mx-serial.c @@ -624,9 +624,12 @@ static int up_ioctl(struct file *filep, int cmd, unsigned long arg) break; } - /* TODO: Handle other termios settings. */ + /* TODO: Handle other termios settings. + * Note that only cfgetispeed is used besued we have knowledge + * that only one speed is supported. + */ - priv->baud = termiosp->c_speed; + priv->baud = cfgetispeed(termiosp); pic32mx_uartconfigure(priv->uartbase, priv->baud, priv->parity, priv->bits, priv->stopbits2); } diff --git a/nuttx/configs/lpc4330-xplorer/README.txt b/nuttx/configs/lpc4330-xplorer/README.txt index 783461704..82bb42e1d 100644 --- a/nuttx/configs/lpc4330-xplorer/README.txt +++ b/nuttx/configs/lpc4330-xplorer/README.txt @@ -56,7 +56,8 @@ Status - The basic OS test configuration and the basic NSH configurations are present and fully verified. This includes: SYSTICK system time, - pin and GPIO configuration, and serial console support. + pin and GPIO configuration, and serial console support. A SPIFI + MTD driver is also in place but requires further verification. - The following drivers have been copied from the LPC17xx port, but require integration into the LPC43xx. This integration should @@ -89,7 +90,6 @@ Status - SD/MMC, - EMC, - - SPIFI*, - USB0, - USB1, - Ethernet, @@ -104,9 +104,6 @@ Status - Event monitor, and - CAN, - * I am not sure, exactly, what is needed for SPIFI support. There - are not SPI registers listed in the user manual. - For the missing drivers some of these can be leveraged from other MCUs that appear to support the same peripheral IP. diff --git a/nuttx/drivers/mtd/ftl.c b/nuttx/drivers/mtd/ftl.c index bf6d1e739..b16397883 100644 --- a/nuttx/drivers/mtd/ftl.c +++ b/nuttx/drivers/mtd/ftl.c @@ -195,7 +195,7 @@ static ssize_t ftl_read(FAR struct inode *inode, unsigned char *buffer, } /**************************************************************************** - * Name: ftl_write + * Name: ftl_flush * * Description: Write the specified number of sectors * diff --git a/nuttx/include/termios.h b/nuttx/include/termios.h index d082cef81..4398b6449 100644 --- a/nuttx/include/termios.h +++ b/nuttx/include/termios.h @@ -138,7 +138,15 @@ #define VSUSP 8 /* Bit 8: SUSP character */ #define NCCS 9 /* Bit 9: Size of the array c_cc for control characters */ -/* Baud Rate Selection. */ +/* Baud Rate Selection. These are instances of type speed_t. Values of 38400 + * and below are specified by POSIX; values above 38400 are sometimes referred + * to as extended values and most values appear in most termios.h implementations. + * + * NOTE that is NuttX that the encoding of the speed_t values is simply the + * value of the baud itself. So this opens a window for non-portable abuse + * of the speed-related interfaces: The defined values should be used where- + * ever possible for reasons of portability. + */ #define B0 0 /* Hang up */ #define B50 50 /* 50 baud */ @@ -236,17 +244,55 @@ extern "C" { #define EXTERN extern #endif -EXTERN speed_t cfgetispeed(FAR const struct termios *); -EXTERN speed_t cfgetospeed(FAR const struct termios *); -EXTERN int cfsetispeed(FAR struct termios *, speed_t); -EXTERN int cfsetospeed(FAR struct termios *, speed_t); -EXTERN int tcdrain(int); -EXTERN int tcflow(int, int); -EXTERN int tcflush(int, int); -EXTERN int tcgetattr(int, FAR struct termios *); -EXTERN pid_t tcgetsid(int); -EXTERN int tcsendbreak(int, int); -EXTERN int tcsetattr(int, int, FAR const struct termios *); +/* The cfgetspeed() function is a non-POSIX function will extract the baud + * from the termios structure to which the termiosp argument points. NuttX + * does not control input/output baud independently. Both must be the same. + * The POSIX standard interfaces, cfisetispeed() and cfisetospeed() are + * supported by simply defining them to be cfsetspeed(). + */ + +EXTERN speed_t cfgetspeed(FAR const struct termios *termiosp); +#define cfgetispeed(termiosp) cfgetspeed(termiosp) +#define cfgetospeed(termiosp) cfgetspeed(termiosp) + +/* The cfsetspeed() function is a non-POSIX function that sets the baud + * stored in the structure pointed to by termiosp to speed. NuttX does + * not control input/output baud independently. Both must be the same. + * The POSIX standard interfaces, cfigetispeed() and cfigetospeed() are + * supported by simply defining them to be cfsetspeed(). + */ + +EXTERN int cfsetspeed(FAR struct termios *termiosp, speed_t speed); +#define cfsetispeed(termiosp,speed) cfsetspeed(termiosp,speed) +#define cfsetospeed(termiosp,speed) cfsetspeed(termiosp,speed) + +/* Wait for transmission of output */ + +EXTERN int tcdrain(int fd); + +/* Suspend or restart the transmission or reception of data */ + +EXTERN int tcflow(int fd, int action); + +/* Flush non-transmitted output data, non-read input data or both */ + +EXTERN int tcflush(int fd, int cmd); + +/* Get the parameters associated with the terminal */ + +EXTERN int tcgetattr(int fd, FAR struct termios *termiosp); + +/* Get process group ID for session leader for controlling terminal */ + +EXTERN pid_t tcgetsid(int fd); + +/* Send a "break" for a specific duration */ + +EXTERN int tcsendbreak(int fd, int duration); + +/* Set the parameters associated with the terminal */ + +EXTERN int tcsetattr(int fd, int options, FAR const struct termios *termiosp); #undef EXTERN #ifdef __cplusplus diff --git a/nuttx/lib/termios/Make.defs b/nuttx/lib/termios/Make.defs index 194482a55..c0a090bd5 100644 --- a/nuttx/lib/termios/Make.defs +++ b/nuttx/lib/termios/Make.defs @@ -37,8 +37,7 @@ TERMIOS_SRCS = ifneq ($(CONFIG_NFILE_DESCRIPTORS),0) -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 +TERMIOS_SRCS += lib_cfgetspeed.c lib_cfsetspeed.c lib_tcflush.c +TERMIOS_SRCS += lib_tcgetattr.c lib_tcsetattr.c endif diff --git a/nuttx/lib/termios/lib_cfgetispeed.c b/nuttx/lib/termios/lib_cfgetispeed.c deleted file mode 100644 index ebb52106d..000000000 --- a/nuttx/lib/termios/lib_cfgetispeed.c +++ /dev/null @@ -1,92 +0,0 @@ -/**************************************************************************** - * lib/termios/lib_cfgetispeed.c - * - * Copyright (C) 2012 Gregory Nutt. All rights reserved. - * Author: Gregory Nutt - * - * 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 -#include - -/**************************************************************************** - * Pre-processor Definitions - ****************************************************************************/ - -/**************************************************************************** - * Private Variables - ****************************************************************************/ - -/**************************************************************************** - * Public Variables - ****************************************************************************/ - -/**************************************************************************** - * Private Functions - ****************************************************************************/ - -/**************************************************************************** - * Public Functions - ****************************************************************************/ - -/**************************************************************************** - * Name: cfgetispeed - * - * Descripton: - * The cfgetispeed() function shall extract the input baud rate from the - * termios structure to which the termiosp argument points. - * - * This function shall return exactly the value in the termios data - * structure, without interpretation. - * - * NOTE 1: NuttX does not not control input/output baud rates independently - * Hense, this function is *identical* to cfgetospeed. - * NOTE 2. 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 may be returned here... not just those enumerated in - * termios.h - * - * Input Parameters: - * termiosp - The termiosp argument is a pointer to a termios structure. - * - * Returned Value: - * Encoded baud value from the termios structure. - * - ****************************************************************************/ - -speed_t cfgetispeed(FAR const struct termios *termiosp) -{ - DEBUGASSERT(termiosp); - return termiosp->c_speed; -} diff --git a/nuttx/lib/termios/lib_cfgetospeed.c b/nuttx/lib/termios/lib_cfgetospeed.c deleted file mode 100644 index b45c1b721..000000000 --- a/nuttx/lib/termios/lib_cfgetospeed.c +++ /dev/null @@ -1,92 +0,0 @@ -/**************************************************************************** - * lib/termios/lib_cfgetospeed.c - * - * Copyright (C) 2012 Gregory Nutt. All rights reserved. - * Author: Gregory Nutt - * - * 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 -#include - -/**************************************************************************** - * Pre-processor Definitions - ****************************************************************************/ - -/**************************************************************************** - * Private Variables - ****************************************************************************/ - -/**************************************************************************** - * Public Variables - ****************************************************************************/ - -/**************************************************************************** - * Private Functions - ****************************************************************************/ - -/**************************************************************************** - * Public Functions - ****************************************************************************/ - -/**************************************************************************** - * Name: cfgetospeed - * - * Descripton: - * The cfgetospeed() function shall extract the output baud rate from the - * termios structure to which the termiosp argument points. - * - * This function shall return exactly the value in the termios data - * structure, without interpretation. - * - * NOTE 1: NuttX does not not control input/output baud rates independently - * Hense, this function is *identical* to cfgetispeed. - * NOTE 2. 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 may be returned here... not just those enumerated in - * termios.h - * - * Input Parameters: - * termiosp - The termiosp argument is a pointer to a termios structure. - * - * Returned Value: - * Encoded baud value from the termios structure. - * - ****************************************************************************/ - -speed_t cfgetospeed(FAR const struct termios *termiosp) -{ - DEBUGASSERT(termiosp); - return termiosp->c_speed; -} diff --git a/nuttx/lib/termios/lib_cfgetspeed.c b/nuttx/lib/termios/lib_cfgetspeed.c new file mode 100644 index 000000000..d7f0dc473 --- /dev/null +++ b/nuttx/lib/termios/lib_cfgetspeed.c @@ -0,0 +1,93 @@ +/**************************************************************************** + * lib/termios/lib_cfgetspeed.c + * + * Copyright (C) 2012 Gregory Nutt. All rights reserved. + * Author: Gregory Nutt + * + * 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 +#include + +/**************************************************************************** + * Pre-processor Definitions + ****************************************************************************/ + +/**************************************************************************** + * Private Variables + ****************************************************************************/ + +/**************************************************************************** + * Public Variables + ****************************************************************************/ + +/**************************************************************************** + * Private Functions + ****************************************************************************/ + +/**************************************************************************** + * Public Functions + ****************************************************************************/ + +/**************************************************************************** + * Name: cfgetspeed + * + * Descripton: + * The cfgetspeed() function is a non-POSIX function will extract the baud + * from the termios structure to which the termiosp argument points. + * + * This function will return exactly the value in the termios data + * structure, without interpretation. + * + * NOTE 1: NuttX does not control input/output baud independently. Both + * must be the same. The POSIX standard interfaces, cfisetispeed() and + * cfisetospeed() are defined to be cfgetspeed() in termios.h. + * NOTE 2. 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 may be returned here... not just those enumerated in + * termios.h + * + * Input Parameters: + * termiosp - The termiosp argument is a pointer to a termios structure. + * + * Returned Value: + * Encoded baud value from the termios structure. + * + ****************************************************************************/ + +speed_t cfgetspeed(FAR const struct termios *termiosp) +{ + DEBUGASSERT(termiosp); + return termiosp->c_speed; +} diff --git a/nuttx/lib/termios/lib_cfsetispeed.c b/nuttx/lib/termios/lib_cfsetispeed.c deleted file mode 100644 index 9a4dfaef1..000000000 --- a/nuttx/lib/termios/lib_cfsetispeed.c +++ /dev/null @@ -1,103 +0,0 @@ -/**************************************************************************** - * lib/termios/lib_cfsetispeed.c - * - * Copyright (C) 2012 Gregory Nutt. All rights reserved. - * Author: Gregory Nutt - * - * 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 -#include -#include - -/**************************************************************************** - * Pre-processor Definitions - ****************************************************************************/ - -/**************************************************************************** - * Private Variables - ****************************************************************************/ - -/**************************************************************************** - * Public Variables - ****************************************************************************/ - -/**************************************************************************** - * Private Functions - ****************************************************************************/ - -/**************************************************************************** - * Public Functions - ****************************************************************************/ - -/**************************************************************************** - * Name: cfsetispeed - * - * Descripton: - * The cfsetispeed() function sets the input baud rate stored in the - * structure pointed to by termiosp to speed. - * - * 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 1: NuttX does not not control input/output baud rates independently - * Hense, this function is *identical* to cfsetospeed. - * NOTE 2. 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. - * speed - The new input speed - * - * Returned Value: - * Baud is not checked... OK is always returned (this is non-standard - * behavior). - * - ****************************************************************************/ - -int cfsetispeed(FAR struct termios *termiosp, speed_t speed) -{ - FAR speed_t *speedp; - - DEBUGASSERT(termiosp); - - speedp = (FAR speed_t *)&termiosp->c_speed; - *speedp = speed; - - return OK; -} diff --git a/nuttx/lib/termios/lib_cfsetospeed.c b/nuttx/lib/termios/lib_cfsetospeed.c deleted file mode 100644 index e6d8fa3ad..000000000 --- a/nuttx/lib/termios/lib_cfsetospeed.c +++ /dev/null @@ -1,103 +0,0 @@ -/**************************************************************************** - * lib/termios/lib_cfsetospeed.c - * - * Copyright (C) 2012 Gregory Nutt. All rights reserved. - * Author: Gregory Nutt - * - * 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 -#include -#include - -/**************************************************************************** - * Pre-processor Definitions - ****************************************************************************/ - -/**************************************************************************** - * Private Variables - ****************************************************************************/ - -/**************************************************************************** - * Public Variables - ****************************************************************************/ - -/**************************************************************************** - * Private Functions - ****************************************************************************/ - -/**************************************************************************** - * Public Functions - ****************************************************************************/ - -/**************************************************************************** - * Name: cfsetospeed - * - * Descripton: - * The cfsetospeed() function sets the output baud rate stored in the - * structure pointed to by termiosp to speed. - * - * 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 1: NuttX does not not control input/output baud rates independently - * Hense, this function is *identical* to cfsetispeed. - * NOTE 2. 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. - * speed - The new output speed - * - * Returned Value: - * Baud is not checked... OK is always returned (this is non-standard - * behavior). - * - ****************************************************************************/ - -int cfsetospeed(struct termios *termiosp, speed_t speed) -{ - FAR speed_t *speedp; - - DEBUGASSERT(termiosp); - - speedp = (FAR speed_t *)&termiosp->c_speed; - *speedp = speed; - - return OK; -} diff --git a/nuttx/lib/termios/lib_cfsetspeed.c b/nuttx/lib/termios/lib_cfsetspeed.c new file mode 100644 index 000000000..f2e11f577 --- /dev/null +++ b/nuttx/lib/termios/lib_cfsetspeed.c @@ -0,0 +1,112 @@ +/**************************************************************************** + * lib/termios/lib_cfsetspeed.c + * + * Copyright (C) 2012 Gregory Nutt. All rights reserved. + * Author: Gregory Nutt + * + * 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 +#include +#include + +/**************************************************************************** + * Pre-processor Definitions + ****************************************************************************/ + +/**************************************************************************** + * Private Variables + ****************************************************************************/ + +/**************************************************************************** + * Public Variables + ****************************************************************************/ + +/**************************************************************************** + * Private Functions + ****************************************************************************/ + +/**************************************************************************** + * Public Functions + ****************************************************************************/ + +/**************************************************************************** + * Name: cfsetspeed + * + * Descripton: + * The cfsetspeed() function is a non-POSIX function that sets the baud + * stored in the structure pointed to by termiosp to speed. + * + * There is no effect on the baud set in the hardware until a subsequent + * successful call to tcsetattr() on the same termios structure. + * + * NOTE 1: NuttX does not control input/output baud independently. Both + * must be the same. The POSIX standard interfaces, cfisetispeed() and + * cfisetospeed() are defined to be cfsetspeed() in termios.h. + * NOTE 2. 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! + * + * Linux, for example, would require this (also non-portable) sequence: + * + * cfsetispeed(termiosp, BOTHER); + * termiosp->c_ispeed = baud; + * + * cfsetospeed(termiosp, BOTHER); + * termiosp->c_ospeed = baud; + * + * Input Parameters: + * termiosp - The termiosp argument is a pointer to a termios structure. + * speed - The new input speed + * + * Returned Value: + * Baud is not checked... OK is always returned (this is non-standard + * behavior). + * + ****************************************************************************/ + +int cfsetspeed(FAR struct termios *termiosp, speed_t speed) +{ + FAR speed_t *speedp; + + DEBUGASSERT(termiosp); + + speedp = (FAR speed_t *)&termiosp->c_speed; + *speedp = speed; + + return OK; +} -- cgit v1.2.3