From 0ee20483b0ff4150e09338821ef7e5a62eab2d47 Mon Sep 17 00:00:00 2001 From: patacongo Date: Sun, 18 Oct 2009 13:52:21 +0000 Subject: Move some drivers to separate subdirectories git-svn-id: svn://svn.code.sf.net/p/nuttx/code/trunk@2156 42af7a65-404d-4744-a932-0658087f49c3 --- nuttx/drivers/Makefile | 23 +- nuttx/drivers/README.txt | 56 +++ nuttx/drivers/fifo.c | 139 ------- nuttx/drivers/lowconsole.c | 132 ------- nuttx/drivers/pipe.c | 282 --------------- nuttx/drivers/pipe_common.c | 654 --------------------------------- nuttx/drivers/pipe_common.h | 136 ------- nuttx/drivers/pipes/Make.defs | 41 +++ nuttx/drivers/pipes/fifo.c | 139 +++++++ nuttx/drivers/pipes/pipe.c | 282 +++++++++++++++ nuttx/drivers/pipes/pipe_common.c | 654 +++++++++++++++++++++++++++++++++ nuttx/drivers/pipes/pipe_common.h | 136 +++++++ nuttx/drivers/serial.c | 741 -------------------------------------- nuttx/drivers/serial/Make.defs | 41 +++ nuttx/drivers/serial/lowconsole.c | 132 +++++++ nuttx/drivers/serial/serial.c | 741 ++++++++++++++++++++++++++++++++++++++ nuttx/drivers/serial/serialirq.c | 172 +++++++++ nuttx/drivers/serialirq.c | 172 --------- 18 files changed, 2411 insertions(+), 2262 deletions(-) create mode 100644 nuttx/drivers/README.txt delete mode 100644 nuttx/drivers/fifo.c delete mode 100755 nuttx/drivers/lowconsole.c delete mode 100644 nuttx/drivers/pipe.c delete mode 100644 nuttx/drivers/pipe_common.c delete mode 100644 nuttx/drivers/pipe_common.h create mode 100644 nuttx/drivers/pipes/Make.defs create mode 100644 nuttx/drivers/pipes/fifo.c create mode 100644 nuttx/drivers/pipes/pipe.c create mode 100644 nuttx/drivers/pipes/pipe_common.c create mode 100644 nuttx/drivers/pipes/pipe_common.h delete mode 100644 nuttx/drivers/serial.c create mode 100644 nuttx/drivers/serial/Make.defs create mode 100644 nuttx/drivers/serial/lowconsole.c create mode 100644 nuttx/drivers/serial/serial.c create mode 100644 nuttx/drivers/serial/serialirq.c delete mode 100644 nuttx/drivers/serialirq.c (limited to 'nuttx/drivers') diff --git a/nuttx/drivers/Makefile b/nuttx/drivers/Makefile index ad9dcaa0f..9155aedc1 100644 --- a/nuttx/drivers/Makefile +++ b/nuttx/drivers/Makefile @@ -39,12 +39,24 @@ ifeq ($(WINTOOL),y) INCDIROPT = -w endif +ifneq ($(CONFIG_NFILE_DESCRIPTORS),0) +include serial/Make.defs +ROOTDEPPATH = --dep-path . +SERIALDEPPATH = --dep-path serial +endif + ifeq ($(CONFIG_NET),y) include net/Make.defs ROOTDEPPATH = --dep-path . NETDEPPATH = --dep-path net endif +ifneq ($(CONFIG_NFILE_DESCRIPTORS),0) +include pipes/Make.defs +ROOTDEPPATH = --dep-path . +PIPEDEPPATH = --dep-path pipes +endif + ifeq ($(CONFIG_USBDEV),y) include usbdev/Make.defs ROOTDEPPATH = --dep-path . @@ -66,18 +78,17 @@ CFLAGS += ${shell $(TOPDIR)/tools/incdir.sh $(INCDIROPT) "$(CC)" $(TOPDIR)/driv endif endif -ASRCS = $(NET_ASRCS) $(USBDEV_ASRCS) $(MMCSD_ASRCS) $(BCH_ASRCS) +ASRCS = $(SERIAL_ASRCS) $(NET_ASRCS) $(PIPE_ASRCS) $(USBDEV_ASRCS) $(MMCSD_ASRCS) $(BCH_ASRCS) AOBJS = $(ASRCS:.S=$(OBJEXT)) CSRCS = ifneq ($(CONFIG_NFILE_DESCRIPTORS),0) -CSRCS += dev_null.c dev_zero.c pipe.c fifo.c pipe_common.c \ - loop.c serial.c serialirq.c lowconsole.c can.c +CSRCS += dev_null.c dev_zero.c loop.c can.c ifneq ($(CONFIG_DISABLE_MOUNTPOINT),y) CSRCS += ramdisk.c endif endif -CSRCS += $(NET_CSRCS) $(USBDEV_CSRCS) $(MMCSD_CSRCS) $(BCH_CSRCS) +CSRCS += $(SERIAL_CSRCS) $(NET_CSRCS) $(PIPE_CSRCS) $(USBDEV_CSRCS) $(MMCSD_CSRCS) $(BCH_CSRCS) COBJS = $(CSRCS:.c=$(OBJEXT)) SRCS = $(ASRCS) $(CSRCS) @@ -85,7 +96,7 @@ OBJS = $(AOBJS) $(COBJS) BIN = libdrivers$(LIBEXT) -VPATH = net:usbdev:mmcsd:bch +VPATH = serial:net:pipes:usbdev:mmcsd:bch all: $(BIN) @@ -101,7 +112,7 @@ $(BIN): $(OBJS) done ; ) .depend: Makefile $(SRCS) - @$(MKDEP) $(ROOTDEPPATH) $(NETDEPPATH) $(USBDEVDEPPATH) $(MMCSDDEPPATH) $(BCHDEPPATH) \ + @$(MKDEP) $(ROOTDEPPATH) $(SERIALDEPPATH) $(NETDEPPATH) $(PIPEDEPPATH)$(USBDEVDEPPATH) $(MMCSDDEPPATH) $(BCHDEPPATH) \ $(CC) -- $(CFLAGS) -- $(SRCS) >Make.dep @touch $@ diff --git a/nuttx/drivers/README.txt b/nuttx/drivers/README.txt new file mode 100644 index 000000000..c7e42c9a7 --- /dev/null +++ b/nuttx/drivers/README.txt @@ -0,0 +1,56 @@ +README +^^^^^^ + +This directory contains various device drivers -- both block and +character drivers as well as other more specialized drivers. + +Files in this directory: +^^^^^^^^^^^^^^^^^^^^^^^ + +can.c + An unfinished CAN driver. + +dev_null.c and dev_zero.c + These files provide the standard /dev/null and /dev/zero devices. + See include/nuttx/fs.h for functions that should be called if you + want to register these devices (devnull_register() and + devzero_register()). + +loop.c + Supports the standard loop device that can be used to export a + file (or character device) as a block device. See losetup() and + loteardown() in include/nuttx/fs.h. + +ramdisk.c + Can be used to set up a block of memory or (read-only) FLASH as + a block driver that can be mounted as a files system. See + include/nuttx/ramdisk.h. + +Subdirectories of this directory: +^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ + +bch/ + Contains logic that may be used to convert a block driver into + a character driver. This is the complementary conversion as that + performed by loop.c. See include/nuttx/fs.h for registration + information. + +mmcsd/ + Support for MMC/SD block drivers. At present, only SPI-based + MMC/SD is supported. See include/nuttx/mmcsd.h. + +net/ + Network interface drivers. See also include/nuttx/net.h + +pipes/ + FIFO and named pipe drivers. Standard interfaces are declared + in include/unistd.h + +serial/ + Front-ends character drivers for chip-specific UARTs. This provide + some TTY-like functionality and are commonly used (but not required for) + the NuttX system console. See include/nuttx/serial.h + +usbdev/ + USB device drivers. See include/nuttx/usb*.h + diff --git a/nuttx/drivers/fifo.c b/nuttx/drivers/fifo.c deleted file mode 100644 index 4e0bbf49c..000000000 --- a/nuttx/drivers/fifo.c +++ /dev/null @@ -1,139 +0,0 @@ -/**************************************************************************** - * drivers/fifo.c - * - * Copyright (C) 2008 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. - * - ****************************************************************************/ - -/**************************************************************************** - * Compilation Switches - ****************************************************************************/ - -/**************************************************************************** - * Included Files - ****************************************************************************/ - -#include - -#include -#include -#include - -#include "pipe_common.h" - -#if CONFIG_DEV_PIPE_SIZE > 0 - -/**************************************************************************** - * Definitions - ****************************************************************************/ - -/**************************************************************************** - * Private Types - ****************************************************************************/ - -/**************************************************************************** - * Private Function Prototypes - ****************************************************************************/ - -/**************************************************************************** - * Private Data - ****************************************************************************/ - -static const struct file_operations fifo_fops = -{ - pipecommon_open, /* open */ - pipecommon_close, /* close */ - pipecommon_read, /* read */ - pipecommon_write, /* write */ - 0, /* seek */ - 0 /* ioctl */ -#ifndef CONFIG_DISABLE_POLL - , pipecommon_poll /* poll */ -#endif -}; - -/**************************************************************************** - * Private Functions - ****************************************************************************/ - -/**************************************************************************** - * Public Functions - ****************************************************************************/ - -/**************************************************************************** - * Name: mkfifo - * - * Description: - * mkfifo() makes a FIFO device driver file with name 'pathname.' Unlike - * Linux, a NuttX FIFO is not a special file type but simply a device driver - * instance. 'mode' specifies the FIFO's permissions. - * - * Once the FIFO has been created by mkfifo(), any thread can open it for - * reading or writing, in the same way as an ordinary file. However, it must - * have been opened from both reading and writing before input or output - * can be performed. This FIFO implementation will block all attempts to - * open a FIFO read-only until at least one thread has opened the FIFO for - * writing. - * - * If all threads that write to the FIFO have closed, subsequent calls to - * read() on the FIFO will return 0 (end-of-file). - * - * Inputs: - * pathname - The full path to the FIFO instance to attach to or to create - * (if not already created). - * mode - Ignored for now - * - * Return: - * 0 is returned on success; otherwise, -1 is returned with errno set - * appropriately. - * - ****************************************************************************/ -int mkfifo(FAR const char *pathname, mode_t mode) -{ - struct pipe_dev_s *dev; - int ret; - - /* Allocate and initialize a new device structure instance */ - - dev = pipecommon_allocdev(); - if (!dev) - { - return -ENOMEM; - } - - ret = register_driver(pathname, &fifo_fops, mode, (void*)dev); - if (ret != 0) - { - pipecommon_freedev(dev); - } - return ret; -} -#endif /* CONFIG_DEV_PIPE_SIZE > 0 */ diff --git a/nuttx/drivers/lowconsole.c b/nuttx/drivers/lowconsole.c deleted file mode 100755 index 15f639391..000000000 --- a/nuttx/drivers/lowconsole.c +++ /dev/null @@ -1,132 +0,0 @@ -/**************************************************************************** - * drivers/lowconsole.c - * - * Copyright (C) 2008, 2009 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 -#include - -#include -#include - -/**************************************************************************** - * Definitions - ****************************************************************************/ - -/* The architecture must provide up_putc for this driver */ - -#ifndef CONFIG_ARCH_LOWPUTC -# error "Architecture must provide up_putc() for this driver" -#endif - -/**************************************************************************** - * Private Function Prototypes - ****************************************************************************/ - -static ssize_t lowconsole_read(struct file *filep, char *buffer, size_t buflen); -static ssize_t lowconsole_write(struct file *filep, const char *buffer, size_t buflen); -static int lowconsole_ioctl(struct file *filep, int cmd, unsigned long arg); - -/**************************************************************************** - * Private Variables - ****************************************************************************/ - -static const struct file_operations g_consoleops = -{ - 0, /* open */ - 0, /* close */ - lowconsole_read, /* read */ - lowconsole_write, /* write */ - 0, /* seek */ - lowconsole_ioctl /* ioctl */ -#ifndef CONFIG_DISABLE_POLL - , 0 /* poll */ -#endif -}; - -/**************************************************************************** - * Private Functions - ****************************************************************************/ - -/**************************************************************************** - * Name: lowconsole_ioctl - ****************************************************************************/ - -static int lowconsole_ioctl(struct file *filep, int cmd, unsigned long arg) -{ - return -ENOTTY; -} - -/**************************************************************************** - * Name: lowconsole_read - ****************************************************************************/ - -static ssize_t lowconsole_read(struct file *filep, char *buffer, size_t buflen) -{ - return 0; -} - -/**************************************************************************** - * Name: lowconsole_write - ****************************************************************************/ - -static ssize_t lowconsole_write(struct file *filep, const char *buffer, size_t buflen) -{ - ssize_t ret = buflen; - - for (; buflen; buflen--) - { - up_putc(*buffer++); - } - return ret; -} - -/**************************************************************************** - * Public Functions - ****************************************************************************/ - -/**************************************************************************** - * Name: lowconsole_init -****************************************************************************/ - -void lowconsole_init(void) -{ - (void)register_driver("/dev/console", &g_consoleops, 0666, NULL); -} diff --git a/nuttx/drivers/pipe.c b/nuttx/drivers/pipe.c deleted file mode 100644 index 4b052e40f..000000000 --- a/nuttx/drivers/pipe.c +++ /dev/null @@ -1,282 +0,0 @@ -/**************************************************************************** - * drivers/pipe.c - * - * Copyright (C) 2008-2009 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. - * - ****************************************************************************/ - -/**************************************************************************** - * Compilation Switches - ****************************************************************************/ - -/**************************************************************************** - * Included Files - ****************************************************************************/ - -#include - -#include -#include -#include -#include -#include -#include -#include - -#include "pipe_common.h" - -#if CONFIG_DEV_PIPE_SIZE > 0 - -/**************************************************************************** - * Definitions - ****************************************************************************/ - -#define MAX_PIPES 32 - -/**************************************************************************** - * Private Types - ****************************************************************************/ - -/**************************************************************************** - * Private Function Prototypes - ****************************************************************************/ - -static int pipe_close(FAR struct file *filep); - -/**************************************************************************** - * Private Data - ****************************************************************************/ - -static const struct file_operations pipe_fops = -{ - pipecommon_open, /* open */ - pipe_close, /* close */ - pipecommon_read, /* read */ - pipecommon_write, /* write */ - 0, /* seek */ - 0 /* ioctl */ -#ifndef CONFIG_DISABLE_POLL - , pipecommon_poll /* poll */ -#endif -}; - -static sem_t g_pipesem = { 1 }; -static uint32 g_pipeset = 0; -static uint32 g_pipecreated = 0; - -/**************************************************************************** - * Private Functions - ****************************************************************************/ - -/**************************************************************************** - * Name: pipe_allocate - ****************************************************************************/ - -static inline int pipe_allocate(void) -{ - int pipeno; - int ret = -ENFILE; - - for (pipeno = 0; pipeno < MAX_PIPES; pipeno++) - { - if ((g_pipeset & (1 << pipeno)) == 0) - { - g_pipeset |= (1 << pipeno); - ret = pipeno; - break; - } - } - return ret; -} - -/**************************************************************************** - * Name: pipe_free - ****************************************************************************/ - -static inline void pipe_free(int pipeno) -{ - int ret = sem_wait(&g_pipesem); - if (ret == 0) - { - g_pipeset &= ~(1 << pipeno); - (void)sem_post(&g_pipesem); - } -} - -/**************************************************************************** - * Name: pipe_close - ****************************************************************************/ - -static int pipe_close(FAR struct file *filep) -{ - struct inode *inode = filep->f_inode; - struct pipe_dev_s *dev = inode->i_private; - int ret; - - /* Some sanity checking */ -#if CONFIG_DEBUG - if (!dev) - { - return -EBADF; - } -#endif - - /* Perform common close operations */ - - ret = pipecommon_close(filep); - if (ret == 0 && dev->d_refs == 0) - { - /* Release the pipe when there are no further open references to it. */ - - pipe_free(dev->d_pipeno); - } - return ret; -} - -/**************************************************************************** - * Public Functions - ****************************************************************************/ - -/**************************************************************************** - * Name: pipe - * - * Description: - * pipe() creates a pair of file descriptors, pointing to a pipe inode, and - * places them in the array pointed to by 'filedes'. filedes[0] is for reading, - * filedes[1] is for writing. - * - * Inputs: - * filedes[2] - The user provided array in which to catch the pipe file - * descriptors - * - * Return: - * 0 is returned on success; otherwise, -1 is returned with errno set - * appropriately. - * - ****************************************************************************/ - -int pipe(int filedes[2]) -{ - struct pipe_dev_s *dev = NULL; - char devname[16]; - int pipeno; - int err; - int ret; - - /* Get exclusive access to the pipe allocation data */ - - ret = sem_wait(&g_pipesem); - if (ret < 0) - { - /* sem_wait() will have already set errno */ - - return ERROR; - } - - /* Allocate a minor number for the pipe device */ - - pipeno = pipe_allocate(); - if (pipeno < 0) - { - (void)sem_post(&g_pipesem); - err = -pipeno; - goto errout; - } - - /* Create a pathname to the pipe device */ - - sprintf(devname, "/dev/pipe%d", pipeno); - - /* Check if the pipe device has already been created */ - - if ((g_pipecreated & (1 << pipeno)) == 0) - { - /* No.. Allocate and initialize a new device structure instance */ - - dev = pipecommon_allocdev(); - if (!dev) - { - (void)sem_post(&g_pipesem); - err = ENOMEM; - goto errout_with_pipe; - } - dev->d_pipeno = pipeno; - - /* Register the pipe device */ - - ret = register_driver(devname, &pipe_fops, 0666, (void*)dev); - if (ret != 0) - { - (void)sem_post(&g_pipesem); - err = -ret; - goto errout_with_dev; - } - - /* Remember that we created this device */ - - g_pipecreated |= (1 << pipeno); - } - (void)sem_post(&g_pipesem); - - /* Get a write file descriptor */ - - filedes[1] = open(devname, O_WRONLY); - if (filedes[1] < 0) - { - err = -filedes[1]; - goto errout_with_driver; - } - - /* Get a read file descriptor */ - - filedes[0] = open(devname, O_RDONLY); - if (filedes[0] < 0) - { - err = -filedes[0]; - goto errout_with_wrfd; - } - - return OK; - -errout_with_wrfd: - close(filedes[1]); -errout_with_driver: - unregister_driver(devname); -errout_with_dev: - pipecommon_freedev(dev); -errout_with_pipe: - pipe_free(pipeno); -errout: - errno = err; - return ERROR; -} - -#endif /* CONFIG_DEV_PIPE_SIZE > 0 */ diff --git a/nuttx/drivers/pipe_common.c b/nuttx/drivers/pipe_common.c deleted file mode 100644 index a0fd00b7a..000000000 --- a/nuttx/drivers/pipe_common.c +++ /dev/null @@ -1,654 +0,0 @@ -/**************************************************************************** - * drivers/pipe_common.c - * - * Copyright (C) 2008-2009 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 -#include -#include -#include -#include -#include -#include -#include -#include - -#include -#if CONFIG_DEBUG -# include -#endif - -#include "pipe_common.h" - -#if CONFIG_DEV_PIPE_SIZE > 0 - -/**************************************************************************** - * Pre-processor Definitions - ****************************************************************************/ - -/* CONFIG_DEV_PIPEDUMP will dump the contents of each transfer into and out - * of the pipe. - */ - -#ifdef CONFIG_DEV_PIPEDUMP -# define pipe_dumpbuffer(m,a,n) lib_dumpbuffer(m,a,n) -#else -# define pipe_dumpbuffer(m,a,n) -#endif - -/**************************************************************************** - * Private Types - ****************************************************************************/ - -/**************************************************************************** - * Private Function Prototypes - ****************************************************************************/ - -static void pipecommon_semtake(sem_t *sem); - -/**************************************************************************** - * Private Data - ****************************************************************************/ - -/**************************************************************************** - * Private Functions - ****************************************************************************/ - -/**************************************************************************** - * Name: pipecommon_semtake - ****************************************************************************/ - -static void pipecommon_semtake(sem_t *sem) -{ - while (sem_wait(sem) != 0) - { - /* The only case that an error should occur here is if the wait was - * awakened by a signal. - */ - - ASSERT(errno == EINTR); - } -} - -/**************************************************************************** - * Name: pipecommon_pollnotify - ****************************************************************************/ - -#ifndef CONFIG_DISABLE_POLL -static void pipecommon_pollnotify(FAR struct pipe_dev_s *dev, pollevent_t eventset) -{ - int i; - - for (i = 0; i < CONFIG_DEV_PIPE_NPOLLWAITERS; i++) - { - struct pollfd *fds = dev->d_fds[i]; - if (fds) - { - fds->revents |= (fds->events & eventset); - if (fds->revents != 0) - { - fvdbg("Report events: %02x\n", fds->revents); - sem_post(fds->sem); - } - } - } -} -#else -# define pipecommon_pollnotify(dev,event) -#endif - -/**************************************************************************** - * Public Functions - ****************************************************************************/ - -/**************************************************************************** - * Name: pipecommon_allocdev - ****************************************************************************/ - -FAR struct pipe_dev_s *pipecommon_allocdev(void) -{ - struct pipe_dev_s *dev; - - /* Allocate a private structure to manage the pipe */ - - dev = (struct pipe_dev_s *)malloc(sizeof(struct pipe_dev_s)); - if (dev) - { - /* Initialize the private structure */ - - memset(dev, 0, sizeof(struct pipe_dev_s)); - sem_init(&dev->d_bfsem, 0, 1); - sem_init(&dev->d_rdsem, 0, 0); - sem_init(&dev->d_wrsem, 0, 0); - } - return dev; -} - -/**************************************************************************** - * Name: pipecommon_freedev - ****************************************************************************/ - -void pipecommon_freedev(FAR struct pipe_dev_s *dev) -{ - sem_destroy(&dev->d_bfsem); - sem_destroy(&dev->d_rdsem); - sem_destroy(&dev->d_wrsem); - free(dev); -} - -/**************************************************************************** - * Name: pipecommon_open - ****************************************************************************/ - -int pipecommon_open(FAR struct file *filep) -{ - struct inode *inode = filep->f_inode; - struct pipe_dev_s *dev = inode->i_private; - int sval; - - /* Some sanity checking */ -#if CONFIG_DEBUG - if (!dev) - { - return -EBADF; - } -#endif - /* Make sure that we have exclusive access to the device structure */ - - if (sem_wait(&dev->d_bfsem) == 0) - { - /* If this the first reference on the device, then allocate the buffer */ - - if (dev->d_refs == 0) - { - dev->d_buffer = (ubyte*)malloc(CONFIG_DEV_PIPE_SIZE); - if (!dev->d_buffer) - { - (void)sem_post(&dev->d_bfsem); - return -ENOMEM; - } - } - - /* Increment the reference count on the pipe instance */ - - dev->d_refs++; - - /* If opened for writing, increment the count of writers on on the pipe instance */ - - if ((filep->f_oflags & O_WROK) != 0) - { - dev->d_nwriters++; - - /* If this this is the first writer, then the read semaphore indicates the - * number of readers waiting for the first writer. Wake them all up. - */ - - if (dev->d_nwriters == 1) - { - while (sem_getvalue(&dev->d_rdsem, &sval) == 0 && sval < 0) - { - sem_post(&dev->d_rdsem); - } - } - } - - /* If opened for read-only, then wait for at least one writer on the pipe */ - - sched_lock(); - (void)sem_post(&dev->d_bfsem); - if ((filep->f_oflags & O_RDWR) == O_RDONLY && dev->d_nwriters < 1) - { - /* NOTE: d_rdsem is normally used when the read logic waits for more - * data to be written. But until the first writer has opened the - * pipe, the meaning is different: it is used prevent O_RDONLY open - * calls from returning until there is at least one writer on the pipe. - * This is required both by spec and also because it prevents - * subsequent read() calls from returning end-of-file because there is - * no writer on the pipe. - */ - - pipecommon_semtake(&dev->d_rdsem); - } - sched_unlock(); - return OK; - } - return ERROR; -} - -/**************************************************************************** - * Name: pipecommon_close - ****************************************************************************/ - -int pipecommon_close(FAR struct file *filep) -{ - struct inode *inode = filep->f_inode; - struct pipe_dev_s *dev = inode->i_private; - int sval; - - /* Some sanity checking */ -#if CONFIG_DEBUG - if (!dev) - { - return -EBADF; - } -#endif - - /* Make sure that we have exclusive access to the device structure. - * NOTE: close() is supposed to return EINTR if interrupted, however - * I've never seen anyone check that. - */ - - pipecommon_semtake(&dev->d_bfsem); - - /* Check if the decremented reference count would go to zero */ - - if (dev->d_refs > 1) - { - /* No.. then just decrement the reference count */ - - dev->d_refs--; - - /* If opened for writing, decrement the count of writers on on the pipe instance */ - - if ((filep->f_oflags & O_WROK) != 0) - { - /* If there are no longer any writers on the pipe, then notify all of the - * waiting readers that they must return end-of-file. - */ - - if (--dev->d_nwriters <= 0) - { - while (sem_getvalue(&dev->d_rdsem, &sval) == 0 && sval < 0) - { - sem_post(&dev->d_rdsem); - } - } - } - } - else - { - /* Yes... deallocate the buffer */ - - free(dev->d_buffer); - dev->d_buffer = NULL; - - /* And reset all counts and indices */ - - dev->d_wrndx = 0; - dev->d_rdndx = 0; - dev->d_refs = 0; - dev->d_nwriters = 0; - } - - sem_post(&dev->d_bfsem); - return OK; -} - -/**************************************************************************** - * Name: pipecommon_read - ****************************************************************************/ - -ssize_t pipecommon_read(FAR struct file *filep, FAR char *buffer, size_t len) -{ - struct inode *inode = filep->f_inode; - struct pipe_dev_s *dev = inode->i_private; -#ifdef CONFIG_DEV_PIPEDUMP - FAR ubyte *start = (ubyte*)buffer; -#endif - ssize_t nread = 0; - int sval; - int ret; - - /* Some sanity checking */ -#if CONFIG_DEBUG - if (!dev) - { - return -ENODEV; - } -#endif - - /* Make sure that we have exclusive access to the device structure */ - - if (sem_wait(&dev->d_bfsem) < 0) - { - return ERROR; - } - - /* If the pipe is empty, then wait for something to be written to it */ - - while (dev->d_wrndx == dev->d_rdndx) - { - /* If O_NONBLOCK was set, then return EGAIN */ - - if (filep->f_oflags & O_NONBLOCK) - { - sem_post(&dev->d_bfsem); - return -EAGAIN; - } - - /* If there are no writers on the pipe, then return end of file */ - - if (dev->d_nwriters <= 0) - { - sem_post(&dev->d_bfsem); - return 0; - } - - /* Otherwise, wait for something to be written to the pipe */ - - sched_lock(); - sem_post(&dev->d_bfsem); - ret = sem_wait(&dev->d_rdsem); - sched_unlock(); - - if (ret < 0 || sem_wait(&dev->d_bfsem) < 0) - { - return ERROR; - } - } - - /* Then return whatever is available in the pipe (which is at least one byte) */ - - nread = 0; - while (nread < len && dev->d_wrndx != dev->d_rdndx) - { - *buffer++ = dev->d_buffer[dev->d_rdndx]; - if (++dev->d_rdndx >= CONFIG_DEV_PIPE_SIZE) - { - dev->d_rdndx = 0; - } - nread++; - } - - /* Notify all waiting writers that bytes have been removed from the buffer */ - - while (sem_getvalue(&dev->d_wrsem, &sval) == 0 && sval < 0) - { - sem_post(&dev->d_wrsem); - } - - /* Notify all poll/select waiters that they can write to the FIFO */ - - pipecommon_pollnotify(dev, POLLOUT); - - sem_post(&dev->d_bfsem); - pipe_dumpbuffer("From PIPE:", start, nread); - return nread; -} - -/**************************************************************************** - * Name: pipecommon_write - ****************************************************************************/ - -ssize_t pipecommon_write(FAR struct file *filep, FAR const char *buffer, size_t len) -{ - struct inode *inode = filep->f_inode; - struct pipe_dev_s *dev = inode->i_private; - ssize_t nwritten = 0; - ssize_t last; - int nxtwrndx; - int sval; - - /* Some sanity checking */ - -#if CONFIG_DEBUG - if (!dev) - { - return -ENODEV; - } -#endif - pipe_dumpbuffer("To PIPE:", (ubyte*)buffer, len); - - /* At present, this method cannot be called from interrupt handlers. That is - * because it calls sem_wait (via pipecommon_semtake below) and sem_wait cannot - * be called from interrupt level. This actually happens fairly commonly - * IF dbg() is called from interrupt handlers and stdout is being redirected - * via a pipe. In that case, the debug output will try to go out the pipe - * (interrupt handlers should use the lldbg() APIs). - * - * On the other hand, it would be very valuable to be able to feed the pipe - * from an interrupt handler! TODO: Consider disabling interrupts instead - * of taking semaphores so that pipes can be written from interupt handlers - */ - - DEBUGASSERT(up_interrupt_context() == FALSE) - - /* Make sure that we have exclusive access to the device structure */ - - if (sem_wait(&dev->d_bfsem) < 0) - { - return ERROR; - } - - /* Loop until all of the bytes have been written */ - - last = 0; - for (;;) - { - /* Calculate the write index AFTER the next byte is written */ - - nxtwrndx = dev->d_wrndx + 1; - if (nxtwrndx >= CONFIG_DEV_PIPE_SIZE) - { - nxtwrndx = 0; - } - - /* Would the next write overflow the circular buffer? */ - - if (nxtwrndx != dev->d_rdndx) - { - /* No... copy the byte */ - - dev->d_buffer[dev->d_wrndx] = *buffer++; - dev->d_wrndx = nxtwrndx; - - /* Is the write complete? */ - - if (++nwritten >= len) - { - /* Yes.. Notify all of the waiting readers that more data is available */ - - while (sem_getvalue(&dev->d_rdsem, &sval) == 0 && sval < 0) - { - sem_post(&dev->d_rdsem); - } - - /* Notify all poll/select waiters that they can write to the FIFO */ - - pipecommon_pollnotify(dev, POLLIN); - - /* Return the number of bytes written */ - - sem_post(&dev->d_bfsem); - return len; - } - } - else - { - /* There is not enough room for the next byte. Was anything written in this pass? */ - - if (last < nwritten) - { - /* Yes.. Notify all of the waiting readers that more data is available */ - - while (sem_getvalue(&dev->d_rdsem, &sval) == 0 && sval < 0) - { - sem_post(&dev->d_rdsem); - } - } - last = nwritten; - - /* If O_NONBLOCK was set, then return partial bytes written or EGAIN */ - - if (filep->f_oflags & O_NONBLOCK) - { - if (nwritten == 0) - { - nwritten = -EAGAIN; - } - sem_post(&dev->d_bfsem); - return nwritten; - } - - /* There is more to be written.. wait for data to be removed from the pipe */ - - sched_lock(); - sem_post(&dev->d_bfsem); - pipecommon_semtake(&dev->d_wrsem); - sched_unlock(); - pipecommon_semtake(&dev->d_bfsem); - } - } -} - -/**************************************************************************** - * Name: pipecommon_poll - ****************************************************************************/ - -#ifndef CONFIG_DISABLE_POLL -int pipecommon_poll(FAR struct file *filep, FAR struct pollfd *fds, - boolean setup) -{ - FAR struct inode *inode = filep->f_inode; - FAR struct pipe_dev_s *dev = inode->i_private; - pollevent_t eventset; - pipe_ndx_t nbytes; - int ret = OK; - int i; - - /* Some sanity checking */ - -#if CONFIG_DEBUG - if (!dev || !fds) - { - return -ENODEV; - } -#endif - - /* Are we setting up the poll? Or tearing it down? */ - - pipecommon_semtake(&dev->d_bfsem); - if (setup) - { - /* This is a request to set up the poll. Find an available - * slot for the poll structure reference - */ - - for (i = 0; i < CONFIG_DEV_PIPE_NPOLLWAITERS; i++) - { - /* Find an available slot */ - - if (!dev->d_fds[i]) - { - /* Bind the poll structure and this slot */ - - dev->d_fds[i] = fds; - fds->priv = &dev->d_fds[i]; - break; - } - } - - if (i >= CONFIG_DEV_PIPE_NPOLLWAITERS) - { - fds->priv = NULL; - ret = -EBUSY; - goto errout; - } - - /* Should immediately notify on any of the requested events? - * First, determine how many bytes are in the buffer - */ - - if (dev->d_wrndx >= dev->d_rdndx) - { - nbytes = dev->d_wrndx - dev->d_rdndx; - } - else - { - nbytes = (CONFIG_DEV_PIPE_SIZE-1) + dev->d_wrndx - dev->d_rdndx; - } - - /* Notify the POLLOUT event if the pipe is not full */ - - eventset = 0; - if (nbytes < (CONFIG_DEV_PIPE_SIZE-1)) - { - eventset |= POLLOUT; - } - - /* Notify the POLLIN event if the pipe is not empty */ - - if (nbytes > 0) - { - eventset |= POLLIN; - } - - if (eventset) - { - pipecommon_pollnotify(dev, eventset); - } - } - else - { - /* This is a request to tear down the poll. */ - - struct pollfd **slot = (struct pollfd **)fds->priv; - -#ifdef CONFIG_DEBUG - if (!slot) - { - ret = -EIO; - goto errout; - } -#endif - - /* Remove all memory of the poll setup */ - - *slot = NULL; - fds->priv = NULL; - } - -errout: - sem_post(&dev->d_bfsem); - return ret; -} -#endif - -#endif /* CONFIG_DEV_PIPE_SIZE > 0 */ diff --git a/nuttx/drivers/pipe_common.h b/nuttx/drivers/pipe_common.h deleted file mode 100644 index 56fa4865b..000000000 --- a/nuttx/drivers/pipe_common.h +++ /dev/null @@ -1,136 +0,0 @@ -/**************************************************************************** - * drivers/pipe_common.h - * - * Copyright (C) 2008 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. - * - ****************************************************************************/ - -#ifndef __DRIVERS_PIPE_COMMON_H -#define __DRIVERS_PIPE_COMMON_H - -/**************************************************************************** - * Included Files - ****************************************************************************/ - -#include -#include -#include - -#ifndef CONFIG_DEV_PIPE_SIZE -# define CONFIG_DEV_PIPE_SIZE 1024 -#endif - -#if CONFIG_DEV_PIPE_SIZE > 0 - -/**************************************************************************** - * Definitions - ****************************************************************************/ - -/* Maximum number of threads than can be waiting for POLL events */ - -#ifndef CONFIG_DEV_PIPE_NPOLLWAITERS -# define CONFIG_DEV_PIPE_NPOLLWAITERS 2 -#endif - -/* Maximum number of open's supported on pipe */ - -#define CONFIG_DEV_PIPE_MAXUSER 255 - -/**************************************************************************** - * Public Types - ****************************************************************************/ - -/* Make the buffer index as small as possible for the configured pipe size */ - -#if CONFIG_DEV_PIPE_SIZE > 65535 -typedef uint32 pipe_ndx_t; /* 32-bit index */ -#elif CONFIG_DEV_PIPE_SIZE > 255 -typedef uint16 pipe_ndx_t; /* 16-bit index */ -#else -typedef ubyte pipe_ndx_t; /* 8-bit index */ -#endif - -/* This structure represents the state of one pipe. A reference to this - * structure is retained in the i_private field of the inode whenthe pipe/fifo - * device is registered. - */ - -struct pipe_dev_s -{ - sem_t d_bfsem; /* Used to serialize access to d_buffer and indices */ - sem_t d_rdsem; /* Empty buffer - Reader waits for data write */ - sem_t d_wrsem; /* Full buffer - Writer waits for data read */ - pipe_ndx_t d_wrndx; /* Index in d_buffer to save next byte written */ - pipe_ndx_t d_rdndx; /* Index in d_buffer to return the next byte read */ - ubyte d_refs; /* References counts on pipe (limited to 255) */ - ubyte d_nwriters; /* Number of reference counts for write access */ - ubyte d_pipeno; /* Pipe minor number */ - ubyte *d_buffer; /* Buffer allocated when device opened */ - - /* The following is a list if poll structures of threads waiting for - * driver events. The 'struct pollfd' reference for each open is also - * retained in the f_priv field of the 'struct file'. - */ - -#ifndef CONFIG_DISABLE_POLL - struct pollfd *d_fds[CONFIG_DEV_PIPE_NPOLLWAITERS]; -#endif -}; - -/**************************************************************************** - * Public Function Prototypes - ****************************************************************************/ - -#ifdef __cplusplus -# define EXTERN extern "C" -extern "C" { -#else -# define EXTERN extern -#endif - -EXTERN FAR struct pipe_dev_s *pipecommon_allocdev(void); -EXTERN void pipecommon_freedev(FAR struct pipe_dev_s *dev); -EXTERN int pipecommon_open(FAR struct file *filep); -EXTERN int pipecommon_close(FAR struct file *filep); -EXTERN ssize_t pipecommon_read(FAR struct file *, FAR char *, size_t); -EXTERN ssize_t pipecommon_write(FAR struct file *, FAR const char *, size_t); -#ifndef CONFIG_DISABLE_POLL -EXTERN int pipecommon_poll(FAR struct file *filep, FAR struct pollfd *fds, - boolean setup); -#endif - -#undef EXTERN -#ifdef __cplusplus -} -#endif - -#endif /* CONFIG_DEV_PIPE_SIZE > 0 */ -#endif /* __DRIVERS_PIPE_COMMON_H */ diff --git a/nuttx/drivers/pipes/Make.defs b/nuttx/drivers/pipes/Make.defs new file mode 100644 index 000000000..be16366bb --- /dev/null +++ b/nuttx/drivers/pipes/Make.defs @@ -0,0 +1,41 @@ +############################################################################ +# drivers/pipes/Make.defs +# +# Copyright (C) 2009 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. +# +############################################################################ + +PIPE_ASRCS = +ifneq ($(CONFIG_NFILE_DESCRIPTORS),0) +PIPE_CSRCS = pipe.c fifo.c pipe_common.c +else +PIPE_CSRCS = +endif diff --git a/nuttx/drivers/pipes/fifo.c b/nuttx/drivers/pipes/fifo.c new file mode 100644 index 000000000..bc9f629f5 --- /dev/null +++ b/nuttx/drivers/pipes/fifo.c @@ -0,0 +1,139 @@ +/**************************************************************************** + * drivers/pipes/fifo.c + * + * Copyright (C) 2008-2009 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. + * + ****************************************************************************/ + +/**************************************************************************** + * Compilation Switches + ****************************************************************************/ + +/**************************************************************************** + * Included Files + ****************************************************************************/ + +#include + +#include +#include +#include + +#include "pipe_common.h" + +#if CONFIG_DEV_PIPE_SIZE > 0 + +/**************************************************************************** + * Definitions + ****************************************************************************/ + +/**************************************************************************** + * Private Types + ****************************************************************************/ + +/**************************************************************************** + * Private Function Prototypes + ****************************************************************************/ + +/**************************************************************************** + * Private Data + ****************************************************************************/ + +static const struct file_operations fifo_fops = +{ + pipecommon_open, /* open */ + pipecommon_close, /* close */ + pipecommon_read, /* read */ + pipecommon_write, /* write */ + 0, /* seek */ + 0 /* ioctl */ +#ifndef CONFIG_DISABLE_POLL + , pipecommon_poll /* poll */ +#endif +}; + +/**************************************************************************** + * Private Functions + ****************************************************************************/ + +/**************************************************************************** + * Public Functions + ****************************************************************************/ + +/**************************************************************************** + * Name: mkfifo + * + * Description: + * mkfifo() makes a FIFO device driver file with name 'pathname.' Unlike + * Linux, a NuttX FIFO is not a special file type but simply a device driver + * instance. 'mode' specifies the FIFO's permissions. + * + * Once the FIFO has been created by mkfifo(), any thread can open it for + * reading or writing, in the same way as an ordinary file. However, it must + * have been opened from both reading and writing before input or output + * can be performed. This FIFO implementation will block all attempts to + * open a FIFO read-only until at least one thread has opened the FIFO for + * writing. + * + * If all threads that write to the FIFO have closed, subsequent calls to + * read() on the FIFO will return 0 (end-of-file). + * + * Inputs: + * pathname - The full path to the FIFO instance to attach to or to create + * (if not already created). + * mode - Ignored for now + * + * Return: + * 0 is returned on success; otherwise, -1 is returned with errno set + * appropriately. + * + ****************************************************************************/ +int mkfifo(FAR const char *pathname, mode_t mode) +{ + struct pipe_dev_s *dev; + int ret; + + /* Allocate and initialize a new device structure instance */ + + dev = pipecommon_allocdev(); + if (!dev) + { + return -ENOMEM; + } + + ret = register_driver(pathname, &fifo_fops, mode, (void*)dev); + if (ret != 0) + { + pipecommon_freedev(dev); + } + return ret; +} +#endif /* CONFIG_DEV_PIPE_SIZE > 0 */ diff --git a/nuttx/drivers/pipes/pipe.c b/nuttx/drivers/pipes/pipe.c new file mode 100644 index 000000000..95049b354 --- /dev/null +++ b/nuttx/drivers/pipes/pipe.c @@ -0,0 +1,282 @@ +/**************************************************************************** + * drivers/pipes/pipe.c + * + * Copyright (C) 2008-2009 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. + * + ****************************************************************************/ + +/**************************************************************************** + * Compilation Switches + ****************************************************************************/ + +/**************************************************************************** + * Included Files + ****************************************************************************/ + +#include + +#include +#include +#include +#include +#include +#include +#include + +#include "pipe_common.h" + +#if CONFIG_DEV_PIPE_SIZE > 0 + +/**************************************************************************** + * Definitions + ****************************************************************************/ + +#define MAX_PIPES 32 + +/**************************************************************************** + * Private Types + ****************************************************************************/ + +/**************************************************************************** + * Private Function Prototypes + ****************************************************************************/ + +static int pipe_close(FAR struct file *filep); + +/**************************************************************************** + * Private Data + ****************************************************************************/ + +static const struct file_operations pipe_fops = +{ + pipecommon_open, /* open */ + pipe_close, /* close */ + pipecommon_read, /* read */ + pipecommon_write, /* write */ + 0, /* seek */ + 0 /* ioctl */ +#ifndef CONFIG_DISABLE_POLL + , pipecommon_poll /* poll */ +#endif +}; + +static sem_t g_pipesem = { 1 }; +static uint32 g_pipeset = 0; +static uint32 g_pipecreated = 0; + +/**************************************************************************** + * Private Functions + ****************************************************************************/ + +/**************************************************************************** + * Name: pipe_allocate + ****************************************************************************/ + +static inline int pipe_allocate(void) +{ + int pipeno; + int ret = -ENFILE; + + for (pipeno = 0; pipeno < MAX_PIPES; pipeno++) + { + if ((g_pipeset & (1 << pipeno)) == 0) + { + g_pipeset |= (1 << pipeno); + ret = pipeno; + break; + } + } + return ret; +} + +/**************************************************************************** + * Name: pipe_free + ****************************************************************************/ + +static inline void pipe_free(int pipeno) +{ + int ret = sem_wait(&g_pipesem); + if (ret == 0) + { + g_pipeset &= ~(1 << pipeno); + (void)sem_post(&g_pipesem); + } +} + +/**************************************************************************** + * Name: pipe_close + ****************************************************************************/ + +static int pipe_close(FAR struct file *filep) +{ + struct inode *inode = filep->f_inode; + struct pipe_dev_s *dev = inode->i_private; + int ret; + + /* Some sanity checking */ +#if CONFIG_DEBUG + if (!dev) + { + return -EBADF; + } +#endif + + /* Perform common close operations */ + + ret = pipecommon_close(filep); + if (ret == 0 && dev->d_refs == 0) + { + /* Release the pipe when there are no further open references to it. */ + + pipe_free(dev->d_pipeno); + } + return ret; +} + +/**************************************************************************** + * Public Functions + ****************************************************************************/ + +/**************************************************************************** + * Name: pipe + * + * Description: + * pipe() creates a pair of file descriptors, pointing to a pipe inode, and + * places them in the array pointed to by 'filedes'. filedes[0] is for reading, + * filedes[1] is for writing. + * + * Inputs: + * filedes[2] - The user provided array in which to catch the pipe file + * descriptors + * + * Return: + * 0 is returned on success; otherwise, -1 is returned with errno set + * appropriately. + * + ****************************************************************************/ + +int pipe(int filedes[2]) +{ + struct pipe_dev_s *dev = NULL; + char devname[16]; + int pipeno; + int err; + int ret; + + /* Get exclusive access to the pipe allocation data */ + + ret = sem_wait(&g_pipesem); + if (ret < 0) + { + /* sem_wait() will have already set errno */ + + return ERROR; + } + + /* Allocate a minor number for the pipe device */ + + pipeno = pipe_allocate(); + if (pipeno < 0) + { + (void)sem_post(&g_pipesem); + err = -pipeno; + goto errout; + } + + /* Create a pathname to the pipe device */ + + sprintf(devname, "/dev/pipe%d", pipeno); + + /* Check if the pipe device has already been created */ + + if ((g_pipecreated & (1 << pipeno)) == 0) + { + /* No.. Allocate and initialize a new device structure instance */ + + dev = pipecommon_allocdev(); + if (!dev) + { + (void)sem_post(&g_pipesem); + err = ENOMEM; + goto errout_with_pipe; + } + dev->d_pipeno = pipeno; + + /* Register the pipe device */ + + ret = register_driver(devname, &pipe_fops, 0666, (void*)dev); + if (ret != 0) + { + (void)sem_post(&g_pipesem); + err = -ret; + goto errout_with_dev; + } + + /* Remember that we created this device */ + + g_pipecreated |= (1 << pipeno); + } + (void)sem_post(&g_pipesem); + + /* Get a write file descriptor */ + + filedes[1] = open(devname, O_WRONLY); + if (filedes[1] < 0) + { + err = -filedes[1]; + goto errout_with_driver; + } + + /* Get a read file descriptor */ + + filedes[0] = open(devname, O_RDONLY); + if (filedes[0] < 0) + { + err = -filedes[0]; + goto errout_with_wrfd; + } + + return OK; + +errout_with_wrfd: + close(filedes[1]); +errout_with_driver: + unregister_driver(devname); +errout_with_dev: + pipecommon_freedev(dev); +errout_with_pipe: + pipe_free(pipeno); +errout: + errno = err; + return ERROR; +} + +#endif /* CONFIG_DEV_PIPE_SIZE > 0 */ diff --git a/nuttx/drivers/pipes/pipe_common.c b/nuttx/drivers/pipes/pipe_common.c new file mode 100644 index 000000000..60d028c00 --- /dev/null +++ b/nuttx/drivers/pipes/pipe_common.c @@ -0,0 +1,654 @@ +/**************************************************************************** + * drivers/pipes/pipe_common.c + * + * Copyright (C) 2008-2009 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 +#include +#include +#include +#include +#include +#include +#include +#include + +#include +#if CONFIG_DEBUG +# include +#endif + +#include "pipe_common.h" + +#if CONFIG_DEV_PIPE_SIZE > 0 + +/**************************************************************************** + * Pre-processor Definitions + ****************************************************************************/ + +/* CONFIG_DEV_PIPEDUMP will dump the contents of each transfer into and out + * of the pipe. + */ + +#ifdef CONFIG_DEV_PIPEDUMP +# define pipe_dumpbuffer(m,a,n) lib_dumpbuffer(m,a,n) +#else +# define pipe_dumpbuffer(m,a,n) +#endif + +/**************************************************************************** + * Private Types + ****************************************************************************/ + +/**************************************************************************** + * Private Function Prototypes + ****************************************************************************/ + +static void pipecommon_semtake(sem_t *sem); + +/**************************************************************************** + * Private Data + ****************************************************************************/ + +/**************************************************************************** + * Private Functions + ****************************************************************************/ + +/**************************************************************************** + * Name: pipecommon_semtake + ****************************************************************************/ + +static void pipecommon_semtake(sem_t *sem) +{ + while (sem_wait(sem) != 0) + { + /* The only case that an error should occur here is if the wait was + * awakened by a signal. + */ + + ASSERT(errno == EINTR); + } +} + +/**************************************************************************** + * Name: pipecommon_pollnotify + ****************************************************************************/ + +#ifndef CONFIG_DISABLE_POLL +static void pipecommon_pollnotify(FAR struct pipe_dev_s *dev, pollevent_t eventset) +{ + int i; + + for (i = 0; i < CONFIG_DEV_PIPE_NPOLLWAITERS; i++) + { + struct pollfd *fds = dev->d_fds[i]; + if (fds) + { + fds->revents |= (fds->events & eventset); + if (fds->revents != 0) + { + fvdbg("Report events: %02x\n", fds->revents); + sem_post(fds->sem); + } + } + } +} +#else +# define pipecommon_pollnotify(dev,event) +#endif + +/**************************************************************************** + * Public Functions + ****************************************************************************/ + +/**************************************************************************** + * Name: pipecommon_allocdev + ****************************************************************************/ + +FAR struct pipe_dev_s *pipecommon_allocdev(void) +{ + struct pipe_dev_s *dev; + + /* Allocate a private structure to manage the pipe */ + + dev = (struct pipe_dev_s *)malloc(sizeof(struct pipe_dev_s)); + if (dev) + { + /* Initialize the private structure */ + + memset(dev, 0, sizeof(struct pipe_dev_s)); + sem_init(&dev->d_bfsem, 0, 1); + sem_init(&dev->d_rdsem, 0, 0); + sem_init(&dev->d_wrsem, 0, 0); + } + return dev; +} + +/**************************************************************************** + * Name: pipecommon_freedev + ****************************************************************************/ + +void pipecommon_freedev(FAR struct pipe_dev_s *dev) +{ + sem_destroy(&dev->d_bfsem); + sem_destroy(&dev->d_rdsem); + sem_destroy(&dev->d_wrsem); + free(dev); +} + +/**************************************************************************** + * Name: pipecommon_open + ****************************************************************************/ + +int pipecommon_open(FAR struct file *filep) +{ + struct inode *inode = filep->f_inode; + struct pipe_dev_s *dev = inode->i_private; + int sval; + + /* Some sanity checking */ +#if CONFIG_DEBUG + if (!dev) + { + return -EBADF; + } +#endif + /* Make sure that we have exclusive access to the device structure */ + + if (sem_wait(&dev->d_bfsem) == 0) + { + /* If this the first reference on the device, then allocate the buffer */ + + if (dev->d_refs == 0) + { + dev->d_buffer = (ubyte*)malloc(CONFIG_DEV_PIPE_SIZE); + if (!dev->d_buffer) + { + (void)sem_post(&dev->d_bfsem); + return -ENOMEM; + } + } + + /* Increment the reference count on the pipe instance */ + + dev->d_refs++; + + /* If opened for writing, increment the count of writers on on the pipe instance */ + + if ((filep->f_oflags & O_WROK) != 0) + { + dev->d_nwriters++; + + /* If this this is the first writer, then the read semaphore indicates the + * number of readers waiting for the first writer. Wake them all up. + */ + + if (dev->d_nwriters == 1) + { + while (sem_getvalue(&dev->d_rdsem, &sval) == 0 && sval < 0) + { + sem_post(&dev->d_rdsem); + } + } + } + + /* If opened for read-only, then wait for at least one writer on the pipe */ + + sched_lock(); + (void)sem_post(&dev->d_bfsem); + if ((filep->f_oflags & O_RDWR) == O_RDONLY && dev->d_nwriters < 1) + { + /* NOTE: d_rdsem is normally used when the read logic waits for more + * data to be written. But until the first writer has opened the + * pipe, the meaning is different: it is used prevent O_RDONLY open + * calls from returning until there is at least one writer on the pipe. + * This is required both by spec and also because it prevents + * subsequent read() calls from returning end-of-file because there is + * no writer on the pipe. + */ + + pipecommon_semtake(&dev->d_rdsem); + } + sched_unlock(); + return OK; + } + return ERROR; +} + +/**************************************************************************** + * Name: pipecommon_close + ****************************************************************************/ + +int pipecommon_close(FAR struct file *filep) +{ + struct inode *inode = filep->f_inode; + struct pipe_dev_s *dev = inode->i_private; + int sval; + + /* Some sanity checking */ +#if CONFIG_DEBUG + if (!dev) + { + return -EBADF; + } +#endif + + /* Make sure that we have exclusive access to the device structure. + * NOTE: close() is supposed to return EINTR if interrupted, however + * I've never seen anyone check that. + */ + + pipecommon_semtake(&dev->d_bfsem); + + /* Check if the decremented reference count would go to zero */ + + if (dev->d_refs > 1) + { + /* No.. then just decrement the reference count */ + + dev->d_refs--; + + /* If opened for writing, decrement the count of writers on on the pipe instance */ + + if ((filep->f_oflags & O_WROK) != 0) + { + /* If there are no longer any writers on the pipe, then notify all of the + * waiting readers that they must return end-of-file. + */ + + if (--dev->d_nwriters <= 0) + { + while (sem_getvalue(&dev->d_rdsem, &sval) == 0 && sval < 0) + { + sem_post(&dev->d_rdsem); + } + } + } + } + else + { + /* Yes... deallocate the buffer */ + + free(dev->d_buffer); + dev->d_buffer = NULL; + + /* And reset all counts and indices */ + + dev->d_wrndx = 0; + dev->d_rdndx = 0; + dev->d_refs = 0; + dev->d_nwriters = 0; + } + + sem_post(&dev->d_bfsem); + return OK; +} + +/**************************************************************************** + * Name: pipecommon_read + ****************************************************************************/ + +ssize_t pipecommon_read(FAR struct file *filep, FAR char *buffer, size_t len) +{ + struct inode *inode = filep->f_inode; + struct pipe_dev_s *dev = inode->i_private; +#ifdef CONFIG_DEV_PIPEDUMP + FAR ubyte *start = (ubyte*)buffer; +#endif + ssize_t nread = 0; + int sval; + int ret; + + /* Some sanity checking */ +#if CONFIG_DEBUG + if (!dev) + { + return -ENODEV; + } +#endif + + /* Make sure that we have exclusive access to the device structure */ + + if (sem_wait(&dev->d_bfsem) < 0) + { + return ERROR; + } + + /* If the pipe is empty, then wait for something to be written to it */ + + while (dev->d_wrndx == dev->d_rdndx) + { + /* If O_NONBLOCK was set, then return EGAIN */ + + if (filep->f_oflags & O_NONBLOCK) + { + sem_post(&dev->d_bfsem); + return -EAGAIN; + } + + /* If there are no writers on the pipe, then return end of file */ + + if (dev->d_nwriters <= 0) + { + sem_post(&dev->d_bfsem); + return 0; + } + + /* Otherwise, wait for something to be written to the pipe */ + + sched_lock(); + sem_post(&dev->d_bfsem); + ret = sem_wait(&dev->d_rdsem); + sched_unlock(); + + if (ret < 0 || sem_wait(&dev->d_bfsem) < 0) + { + return ERROR; + } + } + + /* Then return whatever is available in the pipe (which is at least one byte) */ + + nread = 0; + while (nread < len && dev->d_wrndx != dev->d_rdndx) + { + *buffer++ = dev->d_buffer[dev->d_rdndx]; + if (++dev->d_rdndx >= CONFIG_DEV_PIPE_SIZE) + { + dev->d_rdndx = 0; + } + nread++; + } + + /* Notify all waiting writers that bytes have been removed from the buffer */ + + while (sem_getvalue(&dev->d_wrsem, &sval) == 0 && sval < 0) + { + sem_post(&dev->d_wrsem); + } + + /* Notify all poll/select waiters that they can write to the FIFO */ + + pipecommon_pollnotify(dev, POLLOUT); + + sem_post(&dev->d_bfsem); + pipe_dumpbuffer("From PIPE:", start, nread); + return nread; +} + +/**************************************************************************** + * Name: pipecommon_write + ****************************************************************************/ + +ssize_t pipecommon_write(FAR struct file *filep, FAR const char *buffer, size_t len) +{ + struct inode *inode = filep->f_inode; + struct pipe_dev_s *dev = inode->i_private; + ssize_t nwritten = 0; + ssize_t last; + int nxtwrndx; + int sval; + + /* Some sanity checking */ + +#if CONFIG_DEBUG + if (!dev) + { + return -ENODEV; + } +#endif + pipe_dumpbuffer("To PIPE:", (ubyte*)buffer, len); + + /* At present, this method cannot be called from interrupt handlers. That is + * because it calls sem_wait (via pipecommon_semtake below) and sem_wait cannot + * be called from interrupt level. This actually happens fairly commonly + * IF dbg() is called from interrupt handlers and stdout is being redirected + * via a pipe. In that case, the debug output will try to go out the pipe + * (interrupt handlers should use the lldbg() APIs). + * + * On the other hand, it would be very valuable to be able to feed the pipe + * from an interrupt handler! TODO: Consider disabling interrupts instead + * of taking semaphores so that pipes can be written from interupt handlers + */ + + DEBUGASSERT(up_interrupt_context() == FALSE) + + /* Make sure that we have exclusive access to the device structure */ + + if (sem_wait(&dev->d_bfsem) < 0) + { + return ERROR; + } + + /* Loop until all of the bytes have been written */ + + last = 0; + for (;;) + { + /* Calculate the write index AFTER the next byte is written */ + + nxtwrndx = dev->d_wrndx + 1; + if (nxtwrndx >= CONFIG_DEV_PIPE_SIZE) + { + nxtwrndx = 0; + } + + /* Would the next write overflow the circular buffer? */ + + if (nxtwrndx != dev->d_rdndx) + { + /* No... copy the byte */ + + dev->d_buffer[dev->d_wrndx] = *buffer++; + dev->d_wrndx = nxtwrndx; + + /* Is the write complete? */ + + if (++nwritten >= len) + { + /* Yes.. Notify all of the waiting readers that more data is available */ + + while (sem_getvalue(&dev->d_rdsem, &sval) == 0 && sval < 0) + { + sem_post(&dev->d_rdsem); + } + + /* Notify all poll/select waiters that they can write to the FIFO */ + + pipecommon_pollnotify(dev, POLLIN); + + /* Return the number of bytes written */ + + sem_post(&dev->d_bfsem); + return len; + } + } + else + { + /* There is not enough room for the next byte. Was anything written in this pass? */ + + if (last < nwritten) + { + /* Yes.. Notify all of the waiting readers that more data is available */ + + while (sem_getvalue(&dev->d_rdsem, &sval) == 0 && sval < 0) + { + sem_post(&dev->d_rdsem); + } + } + last = nwritten; + + /* If O_NONBLOCK was set, then return partial bytes written or EGAIN */ + + if (filep->f_oflags & O_NONBLOCK) + { + if (nwritten == 0) + { + nwritten = -EAGAIN; + } + sem_post(&dev->d_bfsem); + return nwritten; + } + + /* There is more to be written.. wait for data to be removed from the pipe */ + + sched_lock(); + sem_post(&dev->d_bfsem); + pipecommon_semtake(&dev->d_wrsem); + sched_unlock(); + pipecommon_semtake(&dev->d_bfsem); + } + } +} + +/**************************************************************************** + * Name: pipecommon_poll + ****************************************************************************/ + +#ifndef CONFIG_DISABLE_POLL +int pipecommon_poll(FAR struct file *filep, FAR struct pollfd *fds, + boolean setup) +{ + FAR struct inode *inode = filep->f_inode; + FAR struct pipe_dev_s *dev = inode->i_private; + pollevent_t eventset; + pipe_ndx_t nbytes; + int ret = OK; + int i; + + /* Some sanity checking */ + +#if CONFIG_DEBUG + if (!dev || !fds) + { + return -ENODEV; + } +#endif + + /* Are we setting up the poll? Or tearing it down? */ + + pipecommon_semtake(&dev->d_bfsem); + if (setup) + { + /* This is a request to set up the poll. Find an available + * slot for the poll structure reference + */ + + for (i = 0; i < CONFIG_DEV_PIPE_NPOLLWAITERS; i++) + { + /* Find an available slot */ + + if (!dev->d_fds[i]) + { + /* Bind the poll structure and this slot */ + + dev->d_fds[i] = fds; + fds->priv = &dev->d_fds[i]; + break; + } + } + + if (i >= CONFIG_DEV_PIPE_NPOLLWAITERS) + { + fds->priv = NULL; + ret = -EBUSY; + goto errout; + } + + /* Should immediately notify on any of the requested events? + * First, determine how many bytes are in the buffer + */ + + if (dev->d_wrndx >= dev->d_rdndx) + { + nbytes = dev->d_wrndx - dev->d_rdndx; + } + else + { + nbytes = (CONFIG_DEV_PIPE_SIZE-1) + dev->d_wrndx - dev->d_rdndx; + } + + /* Notify the POLLOUT event if the pipe is not full */ + + eventset = 0; + if (nbytes < (CONFIG_DEV_PIPE_SIZE-1)) + { + eventset |= POLLOUT; + } + + /* Notify the POLLIN event if the pipe is not empty */ + + if (nbytes > 0) + { + eventset |= POLLIN; + } + + if (eventset) + { + pipecommon_pollnotify(dev, eventset); + } + } + else + { + /* This is a request to tear down the poll. */ + + struct pollfd **slot = (struct pollfd **)fds->priv; + +#ifdef CONFIG_DEBUG + if (!slot) + { + ret = -EIO; + goto errout; + } +#endif + + /* Remove all memory of the poll setup */ + + *slot = NULL; + fds->priv = NULL; + } + +errout: + sem_post(&dev->d_bfsem); + return ret; +} +#endif + +#endif /* CONFIG_DEV_PIPE_SIZE > 0 */ diff --git a/nuttx/drivers/pipes/pipe_common.h b/nuttx/drivers/pipes/pipe_common.h new file mode 100644 index 000000000..9e9f27fc1 --- /dev/null +++ b/nuttx/drivers/pipes/pipe_common.h @@ -0,0 +1,136 @@ +/**************************************************************************** + * drivers/pipe/pipe_common.h + * + * Copyright (C) 2008i-2009 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. + * + ****************************************************************************/ + +#ifndef __DRIVERS_PIPE_COMMON_H +#define __DRIVERS_PIPE_COMMON_H + +/**************************************************************************** + * Included Files + ****************************************************************************/ + +#include +#include +#include + +#ifndef CONFIG_DEV_PIPE_SIZE +# define CONFIG_DEV_PIPE_SIZE 1024 +#endif + +#if CONFIG_DEV_PIPE_SIZE > 0 + +/**************************************************************************** + * Definitions + ****************************************************************************/ + +/* Maximum number of threads than can be waiting for POLL events */ + +#ifndef CONFIG_DEV_PIPE_NPOLLWAITERS +# define CONFIG_DEV_PIPE_NPOLLWAITERS 2 +#endif + +/* Maximum number of open's supported on pipe */ + +#define CONFIG_DEV_PIPE_MAXUSER 255 + +/**************************************************************************** + * Public Types + ****************************************************************************/ + +/* Make the buffer index as small as possible for the configured pipe size */ + +#if CONFIG_DEV_PIPE_SIZE > 65535 +typedef uint32 pipe_ndx_t; /* 32-bit index */ +#elif CONFIG_DEV_PIPE_SIZE > 255 +typedef uint16 pipe_ndx_t; /* 16-bit index */ +#else +typedef ubyte pipe_ndx_t; /* 8-bit index */ +#endif + +/* This structure represents the state of one pipe. A reference to this + * structure is retained in the i_private field of the inode whenthe pipe/fifo + * device is registered. + */ + +struct pipe_dev_s +{ + sem_t d_bfsem; /* Used to serialize access to d_buffer and indices */ + sem_t d_rdsem; /* Empty buffer - Reader waits for data write */ + sem_t d_wrsem; /* Full buffer - Writer waits for data read */ + pipe_ndx_t d_wrndx; /* Index in d_buffer to save next byte written */ + pipe_ndx_t d_rdndx; /* Index in d_buffer to return the next byte read */ + ubyte d_refs; /* References counts on pipe (limited to 255) */ + ubyte d_nwriters; /* Number of reference counts for write access */ + ubyte d_pipeno; /* Pipe minor number */ + ubyte *d_buffer; /* Buffer allocated when device opened */ + + /* The following is a list if poll structures of threads waiting for + * driver events. The 'struct pollfd' reference for each open is also + * retained in the f_priv field of the 'struct file'. + */ + +#ifndef CONFIG_DISABLE_POLL + struct pollfd *d_fds[CONFIG_DEV_PIPE_NPOLLWAITERS]; +#endif +}; + +/**************************************************************************** + * Public Function Prototypes + ****************************************************************************/ + +#ifdef __cplusplus +# define EXTERN extern "C" +extern "C" { +#else +# define EXTERN extern +#endif + +EXTERN FAR struct pipe_dev_s *pipecommon_allocdev(void); +EXTERN void pipecommon_freedev(FAR struct pipe_dev_s *dev); +EXTERN int pipecommon_open(FAR struct file *filep); +EXTERN int pipecommon_close(FAR struct file *filep); +EXTERN ssize_t pipecommon_read(FAR struct file *, FAR char *, size_t); +EXTERN ssize_t pipecommon_write(FAR struct file *, FAR const char *, size_t); +#ifndef CONFIG_DISABLE_POLL +EXTERN int pipecommon_poll(FAR struct file *filep, FAR struct pollfd *fds, + boolean setup); +#endif + +#undef EXTERN +#ifdef __cplusplus +} +#endif + +#endif /* CONFIG_DEV_PIPE_SIZE > 0 */ +#endif /* __DRIVERS_PIPE_COMMON_H */ diff --git a/nuttx/drivers/serial.c b/nuttx/drivers/serial.c deleted file mode 100644 index a7cb42b20..000000000 --- a/nuttx/drivers/serial.c +++ /dev/null @@ -1,741 +0,0 @@ -/************************************************************************************ - * drivers/serial.c - * - * Copyright (C) 2007-2009 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 -#include -#include -#include -#include -#include -#include - -#include -#include -#include -#include - -/************************************************************************************ - * Definitions - ************************************************************************************/ - -/* The architecture must provide up_putc for this driver */ - -#ifndef CONFIG_ARCH_LOWPUTC -# error "Architecture must provide up_putc() for this driver" -#endif - -#define uart_putc(ch) up_putc(ch) - -/************************************************************************************ - * Private Types - ************************************************************************************/ - -/************************************************************************************ - * Private Function Prototypes - ************************************************************************************/ - -static int uart_open(FAR struct file *filep); -static int uart_close(FAR struct file *filep); -static ssize_t uart_read(FAR struct file *filep, FAR char *buffer, size_t buflen); -static ssize_t uart_write(FAR struct file *filep, FAR const char *buffer, size_t buflen); -static int uart_ioctl(FAR struct file *filep, int cmd, unsigned long arg); -#ifndef CONFIG_DISABLE_POLL -static int uart_poll(FAR struct file *filep, FAR struct pollfd *fds, boolean setup); -#endif - -/************************************************************************************ - * Private Variables - ************************************************************************************/ - -static const struct file_operations g_serialops = -{ - uart_open, /* open */ - uart_close, /* close */ - uart_read, /* read */ - uart_write, /* write */ - 0, /* seek */ - uart_ioctl /* ioctl */ -#ifndef CONFIG_DISABLE_POLL - , uart_poll /* poll */ -#endif -}; - -/************************************************************************************ - * Private Functions - ************************************************************************************/ - -/************************************************************************************ - * Name: uart_takesem - ************************************************************************************/ - -static void uart_takesem(FAR sem_t *sem) -{ - while (sem_wait(sem) != 0) - { - /* The only case that an error should occur here is if - * the wait was awakened by a signal. - */ - - ASSERT(*get_errno_ptr() == EINTR); - } -} - -/************************************************************************************ - * Name: uart_givesem - ************************************************************************************/ - -#define uart_givesem(sem) (void)sem_post(sem) - -/**************************************************************************** - * Name: uart_pollnotify - ****************************************************************************/ - -#ifndef CONFIG_DISABLE_POLL -static void uart_pollnotify(FAR uart_dev_t *dev, pollevent_t eventset) -{ - int i; - - for (i = 0; i < CONFIG_DEV_CONSOLE_NPOLLWAITERS; i++) - { - struct pollfd *fds = dev->fds[i]; - if (fds) - { - fds->revents |= (fds->events & eventset); - if (fds->revents != 0) - { - fvdbg("Report events: %02x\n", fds->revents); - sem_post(fds->sem); - } - } - } -} -#else -# define uart_pollnotify(dev,event) -#endif - -/************************************************************************************ - * Name: uart_putxmitchar - ************************************************************************************/ - -static void uart_putxmitchar(FAR uart_dev_t *dev, int ch) -{ - int nexthead = dev->xmit.head + 1; - if (nexthead >= dev->xmit.size) - { - nexthead = 0; - } - - for(;;) - { - if (nexthead != dev->xmit.tail) - { - dev->xmit.buffer[dev->xmit.head] = ch; - dev->xmit.head = nexthead; - return; - } - else - { - /* Inform the interrupt level logic that we are waiting */ - - dev->xmitwaiting = TRUE; - - /* Wait for some characters to be sent from the buffer - * with the TX interrupt enabled. When the TX interrupt - * is enabled, uart_xmitchars should execute and remove - * some of the data from the TX buffer. - */ - - uart_enabletxint(dev); - uart_takesem(&dev->xmitsem); - uart_disabletxint(dev); - } - } -} - -/************************************************************************************ - * Name: uart_irqwrite - ************************************************************************************/ - -static ssize_t uart_irqwrite(FAR uart_dev_t *dev, FAR const char *buffer, size_t buflen) -{ - ssize_t ret = buflen; - - /* Force each character through the low level interface */ - - for (; buflen; buflen--) - { - int ch = *buffer++; - uart_putc(ch); - - /* If this is the console, then we should replace LF with LF-CR */ - - if (ch == '\n') - { - uart_putc('\r'); - } - } - - return ret; -} - -/************************************************************************************ - * Name: uart_write - ************************************************************************************/ - -static ssize_t uart_write(FAR struct file *filep, FAR const char *buffer, size_t buflen) -{ - FAR struct inode *inode = filep->f_inode; - FAR uart_dev_t *dev = inode->i_private; - ssize_t ret = buflen; - - /* We may receive console writes through this path from - * interrupt handlers and from debug output in the IDLE task! - * In these cases, we will need to do things a little - * differently. - */ - - if (up_interrupt_context() || getpid() == 0) - { - if (dev->isconsole) - { - irqstate_t flags = irqsave(); - ret = uart_irqwrite(dev, buffer, buflen); - irqrestore(flags); - return ret; - } - else - { - return ERROR; - } - } - - /* Only one user can be accessing dev->xmit.head at once */ - - uart_takesem(&dev->xmit.sem); - - /* Loop while we still have data to copy to the transmit buffer. - * we add data to the head of the buffer; uart_xmitchars takes the - * data from the end of the buffer. - */ - - uart_disabletxint(dev); - for (; buflen; buflen--) - { - int ch = *buffer++; - - /* Put the character into the transmit buffer */ - - uart_putxmitchar(dev, ch); - - /* If this is the console, then we should replace LF with LF-CR */ - - if (dev->isconsole && ch == '\n') - { - uart_putxmitchar(dev, '\r'); - } - } - - if (dev->xmit.head != dev->xmit.tail) - { - uart_enabletxint(dev); - } - - uart_givesem(&dev->xmit.sem); - return ret; -} - -/************************************************************************************ - * Name: uart_read - ************************************************************************************/ - -static ssize_t uart_read(FAR struct file *filep, FAR char *buffer, size_t buflen) -{ - FAR struct inode *inode = filep->f_inode; - FAR uart_dev_t *dev = inode->i_private; - ssize_t recvd = 0; - - /* Only one user can be accessing dev->recv.tail at once */ - - uart_takesem(&dev->recv.sem); - - /* Loop while we still have data to copy to the receive buffer. - * we add data to the head of the buffer; uart_xmitchars takes the - * data from the end of the buffer. - */ - - uart_disablerxint(dev); - while (recvd < buflen) - { - /* Check if there is more data to return in the circular buffer */ - - if (dev->recv.head != dev->recv.tail) - { - *buffer++ = dev->recv.buffer[dev->recv.tail]; - recvd++; - - if (++(dev->recv.tail) >= dev->recv.size) - { - dev->recv.tail = 0; - } - } - -#ifdef CONFIG_DEV_SERIAL_FULLBLOCKS - /* No... then we would have to wait to get receive more data. - * If the user has specified the O_NONBLOCK option, then just - * return what we have. - */ - - else if (filep->f_oflags & O_NONBLOCK) - { - /* If nothing was transferred, then return the -EAGAIN - * error (not zero which means end of file). - */ - - if (recvd < 1) - { - recvd = -EAGAIN; - } - break; - } -#else - /* No... the circular buffer is empty. Have we returned anything - * to the caller? - */ - - else if (recvd > 0) - { - /* Yes.. break out of the loop and return the number of bytes - * received up to the wait condition. - */ - - break; - } - - /* No... then we would have to wait to get receive some data. - * If the user has specified the O_NONBLOCK option, then do not - * wait. - */ - - else if (filep->f_oflags & O_NONBLOCK) - { - /* Break out of the loop returning -EAGAIN */ - - recvd = -EAGAIN; - break; - } -#endif - /* Otherwise we are going to have to wait for data to arrive */ - - else - { - /* Wait for some characters to be sent from the buffer - * with the TX interrupt re-enabled. - */ - - dev->recvwaiting = TRUE; - uart_enablerxint(dev); - uart_takesem(&dev->recvsem); - uart_disablerxint(dev); - } - } - - uart_enablerxint(dev); - uart_givesem(&dev->recv.sem); - return recvd; -} - -/************************************************************************************ - * Name: uart_ioctl - ************************************************************************************/ - -static int uart_ioctl(FAR struct file *filep, int cmd, unsigned long arg) -{ - FAR struct inode *inode = filep->f_inode; - FAR uart_dev_t *dev = inode->i_private; - - return dev->ops->ioctl(filep, cmd, arg); -} - -/**************************************************************************** - * Name: uart_poll - ****************************************************************************/ - -#ifndef CONFIG_DISABLE_POLL -int uart_poll(FAR struct file *filep, FAR struct pollfd *fds, boolean setup) -{ - FAR struct inode *inode = filep->f_inode; - FAR uart_dev_t *dev = inode->i_private; - pollevent_t eventset; - int ndx; - int ret = OK; - int i; - - /* Some sanity checking */ - -#if CONFIG_DEBUG - if (!dev || !fds) - { - return -ENODEV; - } -#endif - - /* Are we setting up the poll? Or tearing it down? */ - - uart_takesem(&dev->pollsem); - if (setup) - { - /* This is a request to set up the poll. Find an available - * slot for the poll structure reference - */ - - for (i = 0; i < CONFIG_DEV_CONSOLE_NPOLLWAITERS; i++) - { - /* Find an available slot */ - - if (!dev->fds[i]) - { - /* Bind the poll structure and this slot */ - - dev->fds[i] = fds; - fds->priv = &dev->fds[i]; - break; - } - } - - if (i >= CONFIG_DEV_CONSOLE_NPOLLWAITERS) - { - fds->priv = NULL; - ret = -EBUSY; - goto errout; - } - - /* Should immediately notify on any of the requested events? - * First, check if the xmit buffer is full. - */ - - eventset = 0; - - uart_takesem(&dev->xmit.sem); - ndx = dev->xmit.head + 1; - if (ndx >= dev->xmit.size) - { - ndx = 0; - } - if (ndx != dev->xmit.tail) - { - eventset |= POLLOUT; - } - uart_givesem(&dev->xmit.sem); - - /* Check if the receive buffer is empty */ - - uart_takesem(&dev->recv.sem); - if (dev->recv.head != dev->recv.tail) - { - eventset |= POLLIN; - } - uart_givesem(&dev->recv.sem); - - if (eventset) - { - uart_pollnotify(dev, eventset); - } - - } - else if (fds->priv) - { - /* This is a request to tear down the poll. */ - - struct pollfd **slot = (struct pollfd **)fds->priv; - -#ifdef CONFIG_DEBUG - if (!slot) - { - ret = -EIO; - goto errout; - } -#endif - - /* Remove all memory of the poll setup */ - - *slot = NULL; - fds->priv = NULL; - } - -errout: - uart_givesem(&dev->pollsem); - return ret; -} -#endif - -/************************************************************************************ - * Name: uart_close - * - * Description: - * This routine is called when the serial port gets closed. - * It waits for the last remaining data to be sent. - * - ************************************************************************************/ - -static int uart_close(FAR struct file *filep) -{ - FAR struct inode *inode = filep->f_inode; - FAR uart_dev_t *dev = inode->i_private; - irqstate_t flags; - - uart_takesem(&dev->closesem); - if (dev->open_count > 1) - { - dev->open_count--; - uart_givesem(&dev->closesem); - return OK; - } - - /* There are no more references to the port */ - - dev->open_count = 0; - - /* Stop accepting input */ - - uart_disablerxint(dev); - - /* Now we wait for the transmit buffer to clear */ - - while (dev->xmit.head != dev->xmit.tail) - { -#ifndef CONFIG_DISABLE_SIGNALS - usleep(500*1000); -#else - up_mdelay(500); -#endif - } - - /* And wait for the TX fifo to drain */ - - while (!uart_txempty(dev)) - { -#ifndef CONFIG_DISABLE_SIGNALS - usleep(500*1000); -#else - up_mdelay(500); -#endif - } - - /* Free the IRQ and disable the UART */ - - flags = irqsave(); /* Disable interrupts */ - uart_detach(dev); /* Detach interrupts */ - if (!dev->isconsole) /* Check for the serial console UART */ - { - uart_shutdown(dev); /* Disable the UART */ - } - irqrestore(flags); - - uart_givesem(&dev->closesem); - return OK; - } - -/************************************************************************************ - * Name: uart_open - * - * Description: - * This routine is called whenever a serial port is opened. - * - ************************************************************************************/ - -static int uart_open(FAR struct file *filep) -{ - struct inode *inode = filep->f_inode; - uart_dev_t *dev = inode->i_private; - ubyte tmp; - int ret = OK; - - /* If the port is the middle of closing, wait until the close is finished */ - - uart_takesem(&dev->closesem); - - /* Start up serial port */ - /* Increment the count of references to the device. */ - - tmp = dev->open_count + 1; - if (tmp == 0) - { - /* More than 255 opens; ubyte overflows to zero */ - - ret = -EMFILE; - goto errout_with_sem; - } - - /* Check if this is the first time that the driver has been opened. */ - - if (tmp == 1) - { - irqstate_t flags = irqsave(); - - /* If this is the console, then the UART has already been initialized. */ - - if (!dev->isconsole) - { - /* Perform one time hardware initialization */ - - ret = uart_setup(dev); - if (ret < 0) - { - irqrestore(flags); - goto errout_with_sem; - } - } - - /* In any event, we do have to configure for interrupt driven mode of - * operation. Attach the hardware IRQ(s). Hmm.. should shutdown() the - * the device in the rare case that uart_attach() fails, tmp==1, and - * this is not the console. - */ - - ret = uart_attach(dev); - if (ret < 0) - { - uart_shutdown(dev); - irqrestore(flags); - goto errout_with_sem; - } - - /* Mark the io buffers empty */ - - dev->xmit.head = 0; - dev->xmit.tail = 0; - dev->recv.head = 0; - dev->recv.tail = 0; - - /* Enable the RX interrupt */ - - uart_enablerxint(dev); - irqrestore(flags); - } - - /* Save the new open count on success */ - - dev->open_count = tmp; - -errout_with_sem: - uart_givesem(&dev->closesem); - return ret; -} - -/************************************************************************************ - * Public Functions - ************************************************************************************/ - -/************************************************************************************ - * Name: uart_register - * - * Description: - * Register serial console and serial ports. - * - ************************************************************************************/ - -int uart_register(FAR const char *path, FAR uart_dev_t *dev) -{ - sem_init(&dev->xmit.sem, 0, 1); - sem_init(&dev->recv.sem, 0, 1); - sem_init(&dev->closesem, 0, 1); - sem_init(&dev->xmitsem, 0, 0); - sem_init(&dev->recvsem, 0, 0); -#ifndef CONFIG_DISABLE_POLL - sem_init(&dev->pollsem, 0, 1); -#endif - - dbg("Registering %s\n", path); - return register_driver(path, &g_serialops, 0666, dev); -} - -/************************************************************************************ - * Name: uart_datareceived - * - * Description: - * This function is called from uart_recvchars when new serial data is place in - * the driver's circular buffer. This function will wake-up any stalled read() - * operations that are waiting for incoming data. - * - ************************************************************************************/ - -void uart_datareceived(FAR uart_dev_t *dev) -{ - /* Awaken any awaiting read() operations */ - - if (dev->recvwaiting) - { - dev->recvwaiting = FALSE; - (void)sem_post(&dev->recvsem); - } - - /* Notify all poll/select waiters that they can read from the recv buffer */ - - uart_pollnotify(dev, POLLIN); - -} - -/************************************************************************************ - * Name: uart_datasent - * - * Description: - * This function is called from uart_xmitchars after serial data has been sent, - * freeing up some space in the driver's circular buffer. This function will - * wake-up any stalled write() operations that was waiting for space to buffer - * outgoing data. - * - ************************************************************************************/ - -void uart_datasent(FAR uart_dev_t *dev) -{ - if (dev->xmitwaiting) - { - dev->xmitwaiting = FALSE; - (void)sem_post(&dev->xmitsem); - } - - /* Notify all poll/select waiters that they can write to xmit buffer */ - - uart_pollnotify(dev, POLLOUT); -} - - diff --git a/nuttx/drivers/serial/Make.defs b/nuttx/drivers/serial/Make.defs new file mode 100644 index 000000000..089e797d4 --- /dev/null +++ b/nuttx/drivers/serial/Make.defs @@ -0,0 +1,41 @@ +############################################################################ +# drivers/serial/Make.defs +# +# Copyright (C) 2009 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. +# +############################################################################ + +SERIAL_ASRCS = +ifneq ($(CONFIG_NFILE_DESCRIPTORS),0) +SERIAL_CSRCS = serial.c serialirq.c lowconsole.c +else +SERIAL_CSRCS = +endif diff --git a/nuttx/drivers/serial/lowconsole.c b/nuttx/drivers/serial/lowconsole.c new file mode 100644 index 000000000..1de76cc06 --- /dev/null +++ b/nuttx/drivers/serial/lowconsole.c @@ -0,0 +1,132 @@ +/**************************************************************************** + * drivers/serial/lowconsole.c + * + * Copyright (C) 2008, 2009 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 +#include + +#include +#include + +/**************************************************************************** + * Definitions + ****************************************************************************/ + +/* The architecture must provide up_putc for this driver */ + +#ifndef CONFIG_ARCH_LOWPUTC +# error "Architecture must provide up_putc() for this driver" +#endif + +/**************************************************************************** + * Private Function Prototypes + ****************************************************************************/ + +static ssize_t lowconsole_read(struct file *filep, char *buffer, size_t buflen); +static ssize_t lowconsole_write(struct file *filep, const char *buffer, size_t buflen); +static int lowconsole_ioctl(struct file *filep, int cmd, unsigned long arg); + +/**************************************************************************** + * Private Variables + ****************************************************************************/ + +static const struct file_operations g_consoleops = +{ + 0, /* open */ + 0, /* close */ + lowconsole_read, /* read */ + lowconsole_write, /* write */ + 0, /* seek */ + lowconsole_ioctl /* ioctl */ +#ifndef CONFIG_DISABLE_POLL + , 0 /* poll */ +#endif +}; + +/**************************************************************************** + * Private Functions + ****************************************************************************/ + +/**************************************************************************** + * Name: lowconsole_ioctl + ****************************************************************************/ + +static int lowconsole_ioctl(struct file *filep, int cmd, unsigned long arg) +{ + return -ENOTTY; +} + +/**************************************************************************** + * Name: lowconsole_read + ****************************************************************************/ + +static ssize_t lowconsole_read(struct file *filep, char *buffer, size_t buflen) +{ + return 0; +} + +/**************************************************************************** + * Name: lowconsole_write + ****************************************************************************/ + +static ssize_t lowconsole_write(struct file *filep, const char *buffer, size_t buflen) +{ + ssize_t ret = buflen; + + for (; buflen; buflen--) + { + up_putc(*buffer++); + } + return ret; +} + +/**************************************************************************** + * Public Functions + ****************************************************************************/ + +/**************************************************************************** + * Name: lowconsole_init +****************************************************************************/ + +void lowconsole_init(void) +{ + (void)register_driver("/dev/console", &g_consoleops, 0666, NULL); +} diff --git a/nuttx/drivers/serial/serial.c b/nuttx/drivers/serial/serial.c new file mode 100644 index 000000000..df942a050 --- /dev/null +++ b/nuttx/drivers/serial/serial.c @@ -0,0 +1,741 @@ +/************************************************************************************ + * drivers/serial/serial.c + * + * Copyright (C) 2007-2009 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 +#include +#include +#include +#include +#include +#include + +#include +#include +#include +#include + +/************************************************************************************ + * Definitions + ************************************************************************************/ + +/* The architecture must provide up_putc for this driver */ + +#ifndef CONFIG_ARCH_LOWPUTC +# error "Architecture must provide up_putc() for this driver" +#endif + +#define uart_putc(ch) up_putc(ch) + +/************************************************************************************ + * Private Types + ************************************************************************************/ + +/************************************************************************************ + * Private Function Prototypes + ************************************************************************************/ + +static int uart_open(FAR struct file *filep); +static int uart_close(FAR struct file *filep); +static ssize_t uart_read(FAR struct file *filep, FAR char *buffer, size_t buflen); +static ssize_t uart_write(FAR struct file *filep, FAR const char *buffer, size_t buflen); +static int uart_ioctl(FAR struct file *filep, int cmd, unsigned long arg); +#ifndef CONFIG_DISABLE_POLL +static int uart_poll(FAR struct file *filep, FAR struct pollfd *fds, boolean setup); +#endif + +/************************************************************************************ + * Private Variables + ************************************************************************************/ + +static const struct file_operations g_serialops = +{ + uart_open, /* open */ + uart_close, /* close */ + uart_read, /* read */ + uart_write, /* write */ + 0, /* seek */ + uart_ioctl /* ioctl */ +#ifndef CONFIG_DISABLE_POLL + , uart_poll /* poll */ +#endif +}; + +/************************************************************************************ + * Private Functions + ************************************************************************************/ + +/************************************************************************************ + * Name: uart_takesem + ************************************************************************************/ + +static void uart_takesem(FAR sem_t *sem) +{ + while (sem_wait(sem) != 0) + { + /* The only case that an error should occur here is if + * the wait was awakened by a signal. + */ + + ASSERT(*get_errno_ptr() == EINTR); + } +} + +/************************************************************************************ + * Name: uart_givesem + ************************************************************************************/ + +#define uart_givesem(sem) (void)sem_post(sem) + +/**************************************************************************** + * Name: uart_pollnotify + ****************************************************************************/ + +#ifndef CONFIG_DISABLE_POLL +static void uart_pollnotify(FAR uart_dev_t *dev, pollevent_t eventset) +{ + int i; + + for (i = 0; i < CONFIG_DEV_CONSOLE_NPOLLWAITERS; i++) + { + struct pollfd *fds = dev->fds[i]; + if (fds) + { + fds->revents |= (fds->events & eventset); + if (fds->revents != 0) + { + fvdbg("Report events: %02x\n", fds->revents); + sem_post(fds->sem); + } + } + } +} +#else +# define uart_pollnotify(dev,event) +#endif + +/************************************************************************************ + * Name: uart_putxmitchar + ************************************************************************************/ + +static void uart_putxmitchar(FAR uart_dev_t *dev, int ch) +{ + int nexthead = dev->xmit.head + 1; + if (nexthead >= dev->xmit.size) + { + nexthead = 0; + } + + for(;;) + { + if (nexthead != dev->xmit.tail) + { + dev->xmit.buffer[dev->xmit.head] = ch; + dev->xmit.head = nexthead; + return; + } + else + { + /* Inform the interrupt level logic that we are waiting */ + + dev->xmitwaiting = TRUE; + + /* Wait for some characters to be sent from the buffer + * with the TX interrupt enabled. When the TX interrupt + * is enabled, uart_xmitchars should execute and remove + * some of the data from the TX buffer. + */ + + uart_enabletxint(dev); + uart_takesem(&dev->xmitsem); + uart_disabletxint(dev); + } + } +} + +/************************************************************************************ + * Name: uart_irqwrite + ************************************************************************************/ + +static ssize_t uart_irqwrite(FAR uart_dev_t *dev, FAR const char *buffer, size_t buflen) +{ + ssize_t ret = buflen; + + /* Force each character through the low level interface */ + + for (; buflen; buflen--) + { + int ch = *buffer++; + uart_putc(ch); + + /* If this is the console, then we should replace LF with LF-CR */ + + if (ch == '\n') + { + uart_putc('\r'); + } + } + + return ret; +} + +/************************************************************************************ + * Name: uart_write + ************************************************************************************/ + +static ssize_t uart_write(FAR struct file *filep, FAR const char *buffer, size_t buflen) +{ + FAR struct inode *inode = filep->f_inode; + FAR uart_dev_t *dev = inode->i_private; + ssize_t ret = buflen; + + /* We may receive console writes through this path from + * interrupt handlers and from debug output in the IDLE task! + * In these cases, we will need to do things a little + * differently. + */ + + if (up_interrupt_context() || getpid() == 0) + { + if (dev->isconsole) + { + irqstate_t flags = irqsave(); + ret = uart_irqwrite(dev, buffer, buflen); + irqrestore(flags); + return ret; + } + else + { + return ERROR; + } + } + + /* Only one user can be accessing dev->xmit.head at once */ + + uart_takesem(&dev->xmit.sem); + + /* Loop while we still have data to copy to the transmit buffer. + * we add data to the head of the buffer; uart_xmitchars takes the + * data from the end of the buffer. + */ + + uart_disabletxint(dev); + for (; buflen; buflen--) + { + int ch = *buffer++; + + /* Put the character into the transmit buffer */ + + uart_putxmitchar(dev, ch); + + /* If this is the console, then we should replace LF with LF-CR */ + + if (dev->isconsole && ch == '\n') + { + uart_putxmitchar(dev, '\r'); + } + } + + if (dev->xmit.head != dev->xmit.tail) + { + uart_enabletxint(dev); + } + + uart_givesem(&dev->xmit.sem); + return ret; +} + +/************************************************************************************ + * Name: uart_read + ************************************************************************************/ + +static ssize_t uart_read(FAR struct file *filep, FAR char *buffer, size_t buflen) +{ + FAR struct inode *inode = filep->f_inode; + FAR uart_dev_t *dev = inode->i_private; + ssize_t recvd = 0; + + /* Only one user can be accessing dev->recv.tail at once */ + + uart_takesem(&dev->recv.sem); + + /* Loop while we still have data to copy to the receive buffer. + * we add data to the head of the buffer; uart_xmitchars takes the + * data from the end of the buffer. + */ + + uart_disablerxint(dev); + while (recvd < buflen) + { + /* Check if there is more data to return in the circular buffer */ + + if (dev->recv.head != dev->recv.tail) + { + *buffer++ = dev->recv.buffer[dev->recv.tail]; + recvd++; + + if (++(dev->recv.tail) >= dev->recv.size) + { + dev->recv.tail = 0; + } + } + +#ifdef CONFIG_DEV_SERIAL_FULLBLOCKS + /* No... then we would have to wait to get receive more data. + * If the user has specified the O_NONBLOCK option, then just + * return what we have. + */ + + else if (filep->f_oflags & O_NONBLOCK) + { + /* If nothing was transferred, then return the -EAGAIN + * error (not zero which means end of file). + */ + + if (recvd < 1) + { + recvd = -EAGAIN; + } + break; + } +#else + /* No... the circular buffer is empty. Have we returned anything + * to the caller? + */ + + else if (recvd > 0) + { + /* Yes.. break out of the loop and return the number of bytes + * received up to the wait condition. + */ + + break; + } + + /* No... then we would have to wait to get receive some data. + * If the user has specified the O_NONBLOCK option, then do not + * wait. + */ + + else if (filep->f_oflags & O_NONBLOCK) + { + /* Break out of the loop returning -EAGAIN */ + + recvd = -EAGAIN; + break; + } +#endif + /* Otherwise we are going to have to wait for data to arrive */ + + else + { + /* Wait for some characters to be sent from the buffer + * with the TX interrupt re-enabled. + */ + + dev->recvwaiting = TRUE; + uart_enablerxint(dev); + uart_takesem(&dev->recvsem); + uart_disablerxint(dev); + } + } + + uart_enablerxint(dev); + uart_givesem(&dev->recv.sem); + return recvd; +} + +/************************************************************************************ + * Name: uart_ioctl + ************************************************************************************/ + +static int uart_ioctl(FAR struct file *filep, int cmd, unsigned long arg) +{ + FAR struct inode *inode = filep->f_inode; + FAR uart_dev_t *dev = inode->i_private; + + return dev->ops->ioctl(filep, cmd, arg); +} + +/**************************************************************************** + * Name: uart_poll + ****************************************************************************/ + +#ifndef CONFIG_DISABLE_POLL +int uart_poll(FAR struct file *filep, FAR struct pollfd *fds, boolean setup) +{ + FAR struct inode *inode = filep->f_inode; + FAR uart_dev_t *dev = inode->i_private; + pollevent_t eventset; + int ndx; + int ret = OK; + int i; + + /* Some sanity checking */ + +#if CONFIG_DEBUG + if (!dev || !fds) + { + return -ENODEV; + } +#endif + + /* Are we setting up the poll? Or tearing it down? */ + + uart_takesem(&dev->pollsem); + if (setup) + { + /* This is a request to set up the poll. Find an available + * slot for the poll structure reference + */ + + for (i = 0; i < CONFIG_DEV_CONSOLE_NPOLLWAITERS; i++) + { + /* Find an available slot */ + + if (!dev->fds[i]) + { + /* Bind the poll structure and this slot */ + + dev->fds[i] = fds; + fds->priv = &dev->fds[i]; + break; + } + } + + if (i >= CONFIG_DEV_CONSOLE_NPOLLWAITERS) + { + fds->priv = NULL; + ret = -EBUSY; + goto errout; + } + + /* Should immediately notify on any of the requested events? + * First, check if the xmit buffer is full. + */ + + eventset = 0; + + uart_takesem(&dev->xmit.sem); + ndx = dev->xmit.head + 1; + if (ndx >= dev->xmit.size) + { + ndx = 0; + } + if (ndx != dev->xmit.tail) + { + eventset |= POLLOUT; + } + uart_givesem(&dev->xmit.sem); + + /* Check if the receive buffer is empty */ + + uart_takesem(&dev->recv.sem); + if (dev->recv.head != dev->recv.tail) + { + eventset |= POLLIN; + } + uart_givesem(&dev->recv.sem); + + if (eventset) + { + uart_pollnotify(dev, eventset); + } + + } + else if (fds->priv) + { + /* This is a request to tear down the poll. */ + + struct pollfd **slot = (struct pollfd **)fds->priv; + +#ifdef CONFIG_DEBUG + if (!slot) + { + ret = -EIO; + goto errout; + } +#endif + + /* Remove all memory of the poll setup */ + + *slot = NULL; + fds->priv = NULL; + } + +errout: + uart_givesem(&dev->pollsem); + return ret; +} +#endif + +/************************************************************************************ + * Name: uart_close + * + * Description: + * This routine is called when the serial port gets closed. + * It waits for the last remaining data to be sent. + * + ************************************************************************************/ + +static int uart_close(FAR struct file *filep) +{ + FAR struct inode *inode = filep->f_inode; + FAR uart_dev_t *dev = inode->i_private; + irqstate_t flags; + + uart_takesem(&dev->closesem); + if (dev->open_count > 1) + { + dev->open_count--; + uart_givesem(&dev->closesem); + return OK; + } + + /* There are no more references to the port */ + + dev->open_count = 0; + + /* Stop accepting input */ + + uart_disablerxint(dev); + + /* Now we wait for the transmit buffer to clear */ + + while (dev->xmit.head != dev->xmit.tail) + { +#ifndef CONFIG_DISABLE_SIGNALS + usleep(500*1000); +#else + up_mdelay(500); +#endif + } + + /* And wait for the TX fifo to drain */ + + while (!uart_txempty(dev)) + { +#ifndef CONFIG_DISABLE_SIGNALS + usleep(500*1000); +#else + up_mdelay(500); +#endif + } + + /* Free the IRQ and disable the UART */ + + flags = irqsave(); /* Disable interrupts */ + uart_detach(dev); /* Detach interrupts */ + if (!dev->isconsole) /* Check for the serial console UART */ + { + uart_shutdown(dev); /* Disable the UART */ + } + irqrestore(flags); + + uart_givesem(&dev->closesem); + return OK; + } + +/************************************************************************************ + * Name: uart_open + * + * Description: + * This routine is called whenever a serial port is opened. + * + ************************************************************************************/ + +static int uart_open(FAR struct file *filep) +{ + struct inode *inode = filep->f_inode; + uart_dev_t *dev = inode->i_private; + ubyte tmp; + int ret = OK; + + /* If the port is the middle of closing, wait until the close is finished */ + + uart_takesem(&dev->closesem); + + /* Start up serial port */ + /* Increment the count of references to the device. */ + + tmp = dev->open_count + 1; + if (tmp == 0) + { + /* More than 255 opens; ubyte overflows to zero */ + + ret = -EMFILE; + goto errout_with_sem; + } + + /* Check if this is the first time that the driver has been opened. */ + + if (tmp == 1) + { + irqstate_t flags = irqsave(); + + /* If this is the console, then the UART has already been initialized. */ + + if (!dev->isconsole) + { + /* Perform one time hardware initialization */ + + ret = uart_setup(dev); + if (ret < 0) + { + irqrestore(flags); + goto errout_with_sem; + } + } + + /* In any event, we do have to configure for interrupt driven mode of + * operation. Attach the hardware IRQ(s). Hmm.. should shutdown() the + * the device in the rare case that uart_attach() fails, tmp==1, and + * this is not the console. + */ + + ret = uart_attach(dev); + if (ret < 0) + { + uart_shutdown(dev); + irqrestore(flags); + goto errout_with_sem; + } + + /* Mark the io buffers empty */ + + dev->xmit.head = 0; + dev->xmit.tail = 0; + dev->recv.head = 0; + dev->recv.tail = 0; + + /* Enable the RX interrupt */ + + uart_enablerxint(dev); + irqrestore(flags); + } + + /* Save the new open count on success */ + + dev->open_count = tmp; + +errout_with_sem: + uart_givesem(&dev->closesem); + return ret; +} + +/************************************************************************************ + * Public Functions + ************************************************************************************/ + +/************************************************************************************ + * Name: uart_register + * + * Description: + * Register serial console and serial ports. + * + ************************************************************************************/ + +int uart_register(FAR const char *path, FAR uart_dev_t *dev) +{ + sem_init(&dev->xmit.sem, 0, 1); + sem_init(&dev->recv.sem, 0, 1); + sem_init(&dev->closesem, 0, 1); + sem_init(&dev->xmitsem, 0, 0); + sem_init(&dev->recvsem, 0, 0); +#ifndef CONFIG_DISABLE_POLL + sem_init(&dev->pollsem, 0, 1); +#endif + + dbg("Registering %s\n", path); + return register_driver(path, &g_serialops, 0666, dev); +} + +/************************************************************************************ + * Name: uart_datareceived + * + * Description: + * This function is called from uart_recvchars when new serial data is place in + * the driver's circular buffer. This function will wake-up any stalled read() + * operations that are waiting for incoming data. + * + ************************************************************************************/ + +void uart_datareceived(FAR uart_dev_t *dev) +{ + /* Awaken any awaiting read() operations */ + + if (dev->recvwaiting) + { + dev->recvwaiting = FALSE; + (void)sem_post(&dev->recvsem); + } + + /* Notify all poll/select waiters that they can read from the recv buffer */ + + uart_pollnotify(dev, POLLIN); + +} + +/************************************************************************************ + * Name: uart_datasent + * + * Description: + * This function is called from uart_xmitchars after serial data has been sent, + * freeing up some space in the driver's circular buffer. This function will + * wake-up any stalled write() operations that was waiting for space to buffer + * outgoing data. + * + ************************************************************************************/ + +void uart_datasent(FAR uart_dev_t *dev) +{ + if (dev->xmitwaiting) + { + dev->xmitwaiting = FALSE; + (void)sem_post(&dev->xmitsem); + } + + /* Notify all poll/select waiters that they can write to xmit buffer */ + + uart_pollnotify(dev, POLLOUT); +} + + diff --git a/nuttx/drivers/serial/serialirq.c b/nuttx/drivers/serial/serialirq.c new file mode 100644 index 000000000..a4ce80944 --- /dev/null +++ b/nuttx/drivers/serial/serialirq.c @@ -0,0 +1,172 @@ +/************************************************************************************ + * drivers/serial/serialirq.c + * + * Copyright (C) 2007, 2008 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 +#include +#include + +/************************************************************************************ + * Definitions + ************************************************************************************/ + +/************************************************************************************ + * Private Types + ************************************************************************************/ + +/************************************************************************************ + * Private Function Prototypes + ************************************************************************************/ + +/************************************************************************************ + * Private Variables + ************************************************************************************/ + +/************************************************************************************ + * Private Functions + ************************************************************************************/ + +/************************************************************************************ + * Public Functions + ************************************************************************************/ + +/************************************************************************************ + * Name: uart_xmitchars + * + * Description: + * This function is called from the UART interrupt handler when an interrupt + * is received indicating that there is more space in the transmit FIFO. This + * function will send characters from the tail of the xmit buffer while the driver + * write() logic adds data to the head of the xmit buffer. + * + ************************************************************************************/ + +void uart_xmitchars(FAR uart_dev_t *dev) +{ + uint16 nbytes = 0; + + /* Send while we still have data & room in the fifo */ + + while (dev->xmit.head != dev->xmit.tail && uart_txready(dev)) + { + /* Send the next byte */ + + uart_send(dev, dev->xmit.buffer[dev->xmit.tail]); + nbytes++; + + /* Increment the tail index */ + + if (++(dev->xmit.tail) >= dev->xmit.size) + { + dev->xmit.tail = 0; + } + } + + /* When all of the characters have been sent from the buffer + * disable the TX interrupt. + */ + + if (dev->xmit.head == dev->xmit.tail) + { + uart_disabletxint(dev); + } + + /* If any bytes were removed from the buffer, inform any waiters + * there there is space available. + */ + + if (nbytes) + { + uart_datasent(dev); + } +} + +/************************************************************************************ + * Name: uart_receivechars + * + * Description: + * This function is called from the UART interrupt handler when an interrupt + * is received indicating that are bytes available in the receive fifo. This + * function will add chars to head of receive buffer. Driver read() logic will take + * characters from the tail of the buffer. + * + ************************************************************************************/ + +void uart_recvchars(FAR uart_dev_t *dev) +{ + unsigned int status; + int nexthead = dev->recv.head + 1; + uint16 nbytes = 0; + + if (nexthead >= dev->recv.size) + { + nexthead = 0; + } + + /* Loop putting characters into the receive buffer until eithe: (1) the buffer + * is full, or (2) there are not further characters to add. + */ + + while (nexthead != dev->recv.tail && uart_rxavailable(dev)) + { + /* Add the character to the buffer */ + + dev->recv.buffer[dev->recv.head] = uart_receive(dev, &status); + nbytes++; + + /* Increment the head index */ + + dev->recv.head = nexthead; + if (++nexthead >= dev->recv.size) + { + nexthead = 0; + } + } + + /* If any bytes were added to the buffer, inform any waiters + * there there is new incoming data available. + */ + + if (nbytes) + { + uart_datareceived(dev); + } +} + diff --git a/nuttx/drivers/serialirq.c b/nuttx/drivers/serialirq.c deleted file mode 100644 index d1a18b257..000000000 --- a/nuttx/drivers/serialirq.c +++ /dev/null @@ -1,172 +0,0 @@ -/************************************************************************************ - * drivers/serialirq.c - * - * Copyright (C) 2007, 2008 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 -#include -#include - -/************************************************************************************ - * Definitions - ************************************************************************************/ - -/************************************************************************************ - * Private Types - ************************************************************************************/ - -/************************************************************************************ - * Private Function Prototypes - ************************************************************************************/ - -/************************************************************************************ - * Private Variables - ************************************************************************************/ - -/************************************************************************************ - * Private Functions - ************************************************************************************/ - -/************************************************************************************ - * Public Functions - ************************************************************************************/ - -/************************************************************************************ - * Name: uart_xmitchars - * - * Description: - * This function is called from the UART interrupt handler when an interrupt - * is received indicating that there is more space in the transmit FIFO. This - * function will send characters from the tail of the xmit buffer while the driver - * write() logic adds data to the head of the xmit buffer. - * - ************************************************************************************/ - -void uart_xmitchars(FAR uart_dev_t *dev) -{ - uint16 nbytes = 0; - - /* Send while we still have data & room in the fifo */ - - while (dev->xmit.head != dev->xmit.tail && uart_txready(dev)) - { - /* Send the next byte */ - - uart_send(dev, dev->xmit.buffer[dev->xmit.tail]); - nbytes++; - - /* Increment the tail index */ - - if (++(dev->xmit.tail) >= dev->xmit.size) - { - dev->xmit.tail = 0; - } - } - - /* When all of the characters have been sent from the buffer - * disable the TX interrupt. - */ - - if (dev->xmit.head == dev->xmit.tail) - { - uart_disabletxint(dev); - } - - /* If any bytes were removed from the buffer, inform any waiters - * there there is space available. - */ - - if (nbytes) - { - uart_datasent(dev); - } -} - -/************************************************************************************ - * Name: uart_receivechars - * - * Description: - * This function is called from the UART interrupt handler when an interrupt - * is received indicating that are bytes available in the receive fifo. This - * function will add chars to head of receive buffer. Driver read() logic will take - * characters from the tail of the buffer. - * - ************************************************************************************/ - -void uart_recvchars(FAR uart_dev_t *dev) -{ - unsigned int status; - int nexthead = dev->recv.head + 1; - uint16 nbytes = 0; - - if (nexthead >= dev->recv.size) - { - nexthead = 0; - } - - /* Loop putting characters into the receive buffer until eithe: (1) the buffer - * is full, or (2) there are not further characters to add. - */ - - while (nexthead != dev->recv.tail && uart_rxavailable(dev)) - { - /* Add the character to the buffer */ - - dev->recv.buffer[dev->recv.head] = uart_receive(dev, &status); - nbytes++; - - /* Increment the head index */ - - dev->recv.head = nexthead; - if (++nexthead >= dev->recv.size) - { - nexthead = 0; - } - } - - /* If any bytes were added to the buffer, inform any waiters - * there there is new incoming data available. - */ - - if (nbytes) - { - uart_datareceived(dev); - } -} - -- cgit v1.2.3