From 9ba21bda5abae13e746ddad1a65d77ede4a84963 Mon Sep 17 00:00:00 2001 From: patacongo Date: Sun, 20 Jul 2008 20:58:32 +0000 Subject: Add mkfifo() git-svn-id: svn://svn.code.sf.net/p/nuttx/code/trunk@773 42af7a65-404d-4744-a932-0658087f49c3 --- nuttx/ChangeLog | 1 + nuttx/Documentation/NuttX.html | 3 +- nuttx/Documentation/NuttxUserGuide.html | 3 +- nuttx/drivers/Makefile | 2 +- nuttx/drivers/fifo.c | 569 ++++++++++++++++++++++++++++++++ nuttx/fs/fs_fat32.h | 13 +- nuttx/include/nuttx/fat.h | 6 +- nuttx/include/nuttx/fs.h | 2 +- nuttx/include/sys/stat.h | 27 +- 9 files changed, 602 insertions(+), 24 deletions(-) create mode 100644 nuttx/drivers/fifo.c (limited to 'nuttx') diff --git a/nuttx/ChangeLog b/nuttx/ChangeLog index 6628eba5c..fe7e73fe4 100644 --- a/nuttx/ChangeLog +++ b/nuttx/ChangeLog @@ -374,3 +374,4 @@ * Improved solution to POSIX timer lifetime controls bug fixed in 0.3.11. * Add test for recursive mutexes * Correct bug in recursive mutex logic + * Add mkfifo() diff --git a/nuttx/Documentation/NuttX.html b/nuttx/Documentation/NuttX.html index 9dbac248d..70ab56081 100644 --- a/nuttx/Documentation/NuttX.html +++ b/nuttx/Documentation/NuttX.html @@ -8,7 +8,7 @@

NuttX RTOS

-

Last Updated: June 3, 2008

+

Last Updated: July 20, 2008

@@ -1023,6 +1023,7 @@ nuttx-0.3.12 2008-xx-xx Gregory Nutt <spudmonkey@racsa.co.cr> * Improved solution to POSIX timer lifetime controls bug fixed in 0.3.11. * Add test for recursive mutexes * Correct bug in recursive mutex logic + * Add mkfifo() pascal-0.1.3 2008-xx-xx Gregory Nutt <spudmonkey@racsa.co.cr> diff --git a/nuttx/Documentation/NuttxUserGuide.html b/nuttx/Documentation/NuttxUserGuide.html index c424662d0..c69987f8c 100644 --- a/nuttx/Documentation/NuttxUserGuide.html +++ b/nuttx/Documentation/NuttxUserGuide.html @@ -21,7 +21,7 @@ User's Manual

Gregory Nutt

-Last Update: May 31, 2008 +Last Update: July 20, 2008

1.0 Introduction

@@ -5964,6 +5964,7 @@ interface of the same name. int fstat(int fd, FAR struct stat *buf); /* Prototyped but not implemented */ char *getcwd(FAR char *buf, size_t size); /* Prototyped but not implemented */ int mkdir(const char *path, mode_t mode); + int mkfifo(const char *path, mode_t mode); int rmdir(const char *path); int stat(const char *path, FAR struct stat *buf); int statfs(const char *path, FAR struct statfs *buf); /* Prototyped but not implemented */ diff --git a/nuttx/drivers/Makefile b/nuttx/drivers/Makefile index b300045bc..19e775e8a 100644 --- a/nuttx/drivers/Makefile +++ b/nuttx/drivers/Makefile @@ -44,7 +44,7 @@ AOBJS = $(ASRCS:.S=$(OBJEXT)) CSRCS = ifneq ($(CONFIG_NFILE_DESCRIPTORS),0) -CSRCS += dev_null.c dev_zero.c serial.c lowconsole.c can.c +CSRCS += dev_null.c dev_zero.c fifo.c serial.c lowconsole.c can.c ifneq ($(CONFIG_DISABLE_MOUNTPOINT),y) CSRCS += ramdisk.c endif diff --git a/nuttx/drivers/fifo.c b/nuttx/drivers/fifo.c new file mode 100644 index 000000000..0fefc80c8 --- /dev/null +++ b/nuttx/drivers/fifo.c @@ -0,0 +1,569 @@ +/**************************************************************************** + * 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 +#include +#include +#include +#include +#include + +/**************************************************************************** + * Definitions + ****************************************************************************/ + +#ifndef CONFIG_DEV_FIFO_SIZE +# define CONFIG_DEV_FIFO_SIZE 1024 +#endif + +/* Maximum number of open's supported on FIFO */ + +#define CONFIG_DEV_FIFO_MAXUSER 255 + +/**************************************************************************** + * Private Types + ****************************************************************************/ + +/* Make the FIFO index as small as possible for the configured FIFO size */ + +#if CONFIG_DEV_FIFO_SIZE > 65535 +typedef uint32 fifo_ndx_t; /* 32-bit index */ +#elif CONFIG_DEV_FIFO_SIZE > 255 +typedef uint16 fifo_ndx_t; /* 16-bit index */ +#else +typedef ubyte fifo_ndx_t; /* 8-bit index */ +#endif + +struct fifo_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 */ + fifo_ndx_t d_wrndx; /* Index in d_buffer to save next byte written */ + fifo_ndx_t d_rdndx; /* Index in d_buffer to return the next byte read */ + ubyte d_refs; /* References counts on FIFO (limited to 255) */ + ubyte d_nreaders; /* Number of readers waiting for write data to empty buffer */ + ubyte d_nwriters; /* Number of writers wiating for data read out of full buffer */ + ubyte d_buffer[CONFIG_DEV_FIFO_SIZE]; +}; + +/**************************************************************************** + * Private Function Prototypes + ****************************************************************************/ + +static inline FAR struct fifo_dev_s *fifo_allocdev(void); +static inline void fifo_freedev(FAR struct fifo_dev_s *dev); +static void fifo_semtake(sem_t *sem); + +static int fifo_open(FAR struct file *filep); +static int fifo_close(FAR struct file *filep); +static ssize_t fifo_read(FAR struct file *, FAR char *, size_t); +static ssize_t fifo_write(FAR struct file *, FAR const char *, size_t); + +/**************************************************************************** + * Private Data + ****************************************************************************/ + +static struct file_operations fifo_fops = +{ + fifo_open, /* open */ + fifo_close, /* close */ + fifo_read, /* read */ + fifo_write, /* write */ + 0, /* seek */ + 0 /* ioctl */ +}; + +/**************************************************************************** + * Private Functions + ****************************************************************************/ + +/**************************************************************************** + * Name: fifo_allocdev + ****************************************************************************/ +static inline FAR struct fifo_dev_s *fifo_allocdev(void) +{ + struct fifo_dev_s *dev; + + /* Allocate a private structure to manage the FIFO */ + + dev = (struct fifo_dev_s *)malloc(sizeof(struct fifo_dev_s)); + if (dev) + { + /* Initialize the private structure */ + + sem_init(&dev->d_bfsem, 0, 1); + sem_init(&dev->d_rdsem, 0, 0); + sem_init(&dev->d_wrsem, 0, 0); + dev->d_wrndx = 0; + dev->d_rdndx = 0; + dev->d_refs = 0; + dev->d_nreaders = 0; + dev->d_nwriters = 0; + } + return dev; +} + +/**************************************************************************** + * Name: fifo_freedev + ****************************************************************************/ +static inline void fifo_freedev(FAR struct fifo_dev_s *dev) +{ + sem_destroy(&dev->d_bfsem); + sem_destroy(&dev->d_rdsem); + sem_destroy(&dev->d_wrsem); + free(dev); +} + +/**************************************************************************** + * Name: fifo_semtake + ****************************************************************************/ +static void fifo_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: fifo_open + ****************************************************************************/ +static int fifo_open(FAR struct file *filep) +{ + struct inode *inode = filep->f_inode; + struct fifo_dev_s *dev = inode->i_private; + + /* The device structure will be allocated the first time that the FIFO is + * opened + */ + + if (!dev) + { + /* Allocate and initialize a new device structure instance */ + + dev = fifo_allocdev(); + if (!dev) + { + return -ENOMEM; + } + + /* Set the private data on the inode to this instance */ + + inode->i_private = dev; + } + + /* Make sure that we have exclusive access to the device structure */ + + if (sem_wait(&dev->d_bfsem) == 0) + { + /* Increment the reference count on the fifo instance */ + + dev->d_refs++; + (void)sem_post(&dev->d_bfsem); + return OK; + } + return ERROR; +} + +/**************************************************************************** + * Name: fifo_close + ****************************************************************************/ +static int fifo_close(FAR struct file *filep) +{ + struct inode *inode = filep->f_inode; + struct fifo_dev_s *dev = inode->i_private; + + /* 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. + */ + + fifo_semtake(&dev->d_bfsem); + + /* Check if the decremented reference count would be zero */ + + if (dev->d_refs > 1) + { + /* No.. then just decrement the reference count */ + + dev->d_refs--; + sem_post(&dev->d_bfsem); + } + else + { + /* Then nothing else can be holding the semaphore, so it is save to */ + + inode->i_private = NULL; + sem_post(&dev->d_bfsem); + + /* Then free the fifo structure instance */ + + fifo_freedev(dev); + } + return OK; +} + +/**************************************************************************** + * Name: fifo_read + ****************************************************************************/ +static ssize_t fifo_read(FAR struct file *filep, FAR char *buffer, size_t len) +{ + struct inode *inode = filep->f_inode; + struct fifo_dev_s *dev = inode->i_private; + ssize_t nread = 0; + ssize_t nrqstd = len; + 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; + } + + /* Loop until all of the bytes have been read */ + + for (;;) + { + ssize_t nbytes; + + /* Is there data available at the end of the buffer? When the write + * index is smaller than the read index, then all of the data from the + * read index to the end of the buffer is available for reading. + */ + + if (dev->d_rdndx > dev->d_wrndx) + { + /* Yes.. How many bytes are available at the end of the circular buffer */ + + nbytes = CONFIG_DEV_FIFO_SIZE - dev->d_rdndx; + if (nbytes > 0) + { + /* Read bytes from the end of the buffer. Are there more than we + * need? + */ + + if (nbytes > nrqstd) + { + nbytes = nrqstd; + } + + /* Copy the correct number of bytes */ + + memcpy(&buffer[nread], &dev->d_buffer[dev->d_rdndx], nbytes); + + /* Then update all indices and counts */ + + nread += nbytes; + nrqstd -= nbytes; + dev->d_rdndx += nbytes; + if (dev->d_rdndx >= CONFIG_DEV_FIFO_SIZE) + { + dev->d_rdndx = 0; + } + } + } + + /* We have read some or all of the data at the end of the buffer. Do we still need more? */ + + if (nrqstd > 0) + { + /* Yes... then we now that we have consumed all of the bytes at the end of the + * buffer. How many bytes are available at the end of the circular buffer> + */ + + nbytes = dev->d_wrndx - dev->d_rdndx; + if (nbytes > 0) + { + /* Read bytes from the beginning of the buffer. Are there more than we + * need? + */ + + if (nbytes > nrqstd) + { + nbytes = nrqstd; + } + + /* Copy the correct number of bytes */ + + memcpy(&buffer[nread], &dev->d_buffer[dev->d_rdndx], nbytes); + + /* Then update all indices and counts */ + + nread += nbytes; + nrqstd -= nbytes; + dev->d_rdndx += nbytes; + } + } + + /* Was anything read? */ + + if (nread > 0) + { + /* Yes.. Notify the waiting writers that space is again available */ + + if (dev->d_nwriters > 0) + { + sem_post(&dev->d_wrsem); + } + + /* Return the number of bytes read */ + + sem_post(&dev->d_bfsem); + return nread; + } + else + { + /* No.. wait for data to be added to the FIFO */ + + dev->d_nreaders++; + sched_lock(); + sem_post(&dev->d_bfsem); + ret = sem_wait(&dev->d_rdsem); + sched_unlock(); + fifo_semtake(&dev->d_bfsem); + dev->d_nreaders--; + + if (ret != 0) + { + return ERROR; + } + } + } +} + +/**************************************************************************** + * Name: fifo_write + ****************************************************************************/ +static ssize_t fifo_write(FAR struct file *filep, FAR const char *buffer, size_t len) +{ + struct inode *inode = filep->f_inode; + struct fifo_dev_s *dev = inode->i_private; + const char *src; + ssize_t nwritten = 0; + ssize_t ntowrite = len; + + /* 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; + } + + /* Loop until all of the bytes have been written */ + + src = buffer; + for (;;) + { + ssize_t nbytes; + + /* Is there space available at the end of the buffer? When the write + * index is greater than the read index, then all of the data from the + * write index to the end of the buffer is available for writing. + */ + + if (dev->d_wrndx >= dev->d_rdndx) + { + /* How many bytes are available at the end of the circular buffer */ + + nbytes = CONFIG_DEV_FIFO_SIZE - dev->d_wrndx; + if (nbytes > 0) + { + /* Write bytes to the end of the buffer. Is there more space than we + * need? + */ + + if (nbytes > ntowrite) + { + nbytes = ntowrite; + } + + /* Copy the correct number of bytes */ + + memcpy(&dev->d_buffer[dev->d_wrndx], &src[nwritten], nbytes); + + /* Then update all indices and counts */ + + nwritten += nbytes; + ntowrite -= nbytes; + dev->d_wrndx += nbytes; + if (dev->d_wrndx >= CONFIG_DEV_FIFO_SIZE) + { + dev->d_wrndx = 0; + } + } + } + + /* Do we still need to write more data? */ + + if (ntowrite > 0) + { + /* Yes... How many bytes are available at the end of the circular buffer */ + + nbytes = dev->d_rdndx - dev->d_wrndx - 1; + if (nbytes > 0) + { + /* Write bytes to the beginning of the buffer. Is there more space than we + * need? + */ + + if (nbytes > ntowrite) + { + nbytes = ntowrite; + } + + /* Copy the correct number of bytes */ + + memcpy(&dev->d_buffer[dev->d_wrndx], &src[nwritten], nbytes); + + /* Then update all indices and counts */ + + nwritten += nbytes; + ntowrite -= nbytes; + dev->d_wrndx += nbytes; + } + } + + /* Was anything written? */ + + if (nwritten > 0) + { + /* Yes.. Notify the waiting reades that more data is available */ + + if (dev->d_nreaders > 0) + { + sem_post(&dev->d_rdsem); + } + } + + /* Was everything written? */ + + if (ntowrite <= 0 ) + { + /* Return the number of bytes written */ + + sem_post(&dev->d_bfsem); + return len; + } + + /* There is more to be writtend.. wait for data to be removed from the FIFO */ + + dev->d_nwriters++; + sched_lock(); + sem_post(&dev->d_bfsem); + fifo_semtake(&dev->d_wrsem); + sched_unlock(); + fifo_semtake(&dev->d_bfsem); + dev->d_nwriters--; + + src = &src[nwritten]; + nwritten = 0; + } +} + +/**************************************************************************** + * 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. NuttX FIFOs need + * not be open at both ends before input or output operations on it. + * + * In NuttX pipes are built on top of FIFOs + * + * 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) +{ + return register_driver(pathname, &fifo_fops, mode, NULL); +} diff --git a/nuttx/fs/fs_fat32.h b/nuttx/fs/fs_fat32.h index d3936f3a8..ab48fa796 100644 --- a/nuttx/fs/fs_fat32.h +++ b/nuttx/fs/fs_fat32.h @@ -56,8 +56,8 @@ * refer to the interpretation under FAT32. */ -#define BS_JUMP 0 /* 3@0: Jump instruction to boot code (ignored) */ -#define BS_OEMNAME 3 /* 8@3: Usually "MSWIN4.1" */ +#define BS_JUMP 0 /* 3@0: Jump instruction to boot code (ignored) */ +#define BS_OEMNAME 3 /* 8@3: Usually "MSWIN4.1" */ #define BS_BYTESPERSEC 11 /* 2@11: Bytes per sector: 512, 1024, 2048, 4096 */ #define BS_SECPERCLUS 13 /* 1@13: Sectors per allocation unit: 2**n, n=0..7 */ #define BS_RESVDSECCOUNT 14 /* 2@14: Reserved sector count: Usually 32 */ @@ -74,12 +74,15 @@ /* The following fields are only valid for FAT12/16 */ #define BS16_DRVNUM 36 /* 1@36: Drive number for MSDOS bootstrap */ - /* 1@37: Reserverd (zero) */ + /* 1@37: Reserved (zero) */ #define BS16_BOOTSIG 38 /* 1@38: Extended boot signature: 0x29 if following valid */ #define BS16_VOLID 39 /* 4@39: Volume serial number */ #define BS16_VOLLAB 43 /* 11@43: Volume label */ #define BS16_FILESYSTYPE 54 /* 8@54: "FAT12 ", "FAT16 ", or "FAT " */ +#define BS16_BOOTCODE 62 /* Boot code may be placed in the remainder of the sector */ +#define BS16_BOOTCODESIZE 448 + /* The following fields are only valid for FAT32 */ #define BS32_FATSZ32 36 /* 4@36: Count of sectors occupied by one FAT */ @@ -96,6 +99,9 @@ #define BS32_VOLLAB 71 /* 11@71: Volume label */ #define BS32_FILESYSTYPE 82 /* 8@82: "FAT12 ", "FAT16 ", or "FAT " */ +#define BS32_BOOTCODE 90 /* Boot code may be placed in the remainder of the sector */ +#define BS32_BOOTCODESIZE 420 + /* If the sector is not an MBR, then it could have a partition table at * this offset. */ @@ -123,6 +129,7 @@ #define DIR_WRTDATE 24 /* 2@24: Date of last write */ #define DIR_FSTCLUSTLO 26 /* 2@26: LS first cluster number */ #define DIR_FILESIZE 28 /* 4@28: File size in bytes */ +#define DIR_SIZE 32 /* First byte of the directory name has special meanings: */ diff --git a/nuttx/include/nuttx/fat.h b/nuttx/include/nuttx/fat.h index 720e64547..f45725e0a 100644 --- a/nuttx/include/nuttx/fat.h +++ b/nuttx/include/nuttx/fat.h @@ -1,5 +1,5 @@ /**************************************************************************** - * nuttx/fat.h + * include/nuttx/fat.h * * Copyright (C) 2007, 2008 Gregory Nutt. All rights reserved. * Author: Gregory Nutt @@ -75,9 +75,7 @@ extern "C" { #define EXTERN extern #endif -/* Non-standard functions to get and set FAT fire/directgory - * attributes - */ +/* Non-standard functions to get and set FAT file/directory attributes */ EXTERN int fat_getattrib(const char *path, fat_attrib_t *attrib); EXTERN int fat_setattrib(const char *path, fat_attrib_t setbits, fat_attrib_t clearbits); diff --git a/nuttx/include/nuttx/fs.h b/nuttx/include/nuttx/fs.h index 355a13047..713d9ac9f 100644 --- a/nuttx/include/nuttx/fs.h +++ b/nuttx/include/nuttx/fs.h @@ -1,5 +1,5 @@ /**************************************************************************** - * nutts/fs.h + * include/nuttx/fs.h * * Copyright (C) 2007, 2008 Gregory Nutt. All rights reserved. * Author: Gregory Nutt diff --git a/nuttx/include/sys/stat.h b/nuttx/include/sys/stat.h index 20fbc3a59..0377a53ff 100644 --- a/nuttx/include/sys/stat.h +++ b/nuttx/include/sys/stat.h @@ -1,7 +1,7 @@ -/************************************************************ - * sys/stat.h +/**************************************************************************** + * include/sys/stat.h * - * Copyright (C) 2007 Gregory Nutt. All rights reserved. + * Copyright (C) 2007, 2008 Gregory Nutt. All rights reserved. * Author: Gregory Nutt * * Redistribution and use in source and binary forms, with or without @@ -14,7 +14,7 @@ * notice, this list of conditions and the following disclaimer in * the documentation and/or other materials provided with the * distribution. - * 3. Neither the name Gregory Nutt nor the names of its contributors may be + * 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. * @@ -31,21 +31,21 @@ * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE * POSSIBILITY OF SUCH DAMAGE. * - ************************************************************/ + ****************************************************************************/ #ifndef __SYS_STAT_H #define __SYS_STAT_H -/************************************************************ +/**************************************************************************** * Included Files - ************************************************************/ + ****************************************************************************/ #include #include -/************************************************************ +/**************************************************************************** * Definitions - ************************************************************/ + ****************************************************************************/ /* mode_t bit settings (most of these do not apply to Nuttx). * This assumes that the full size of a mode_t is 16-bits. @@ -91,9 +91,9 @@ #define S_ISFIFO(m) (((m) & S_IFMT) == S_IFIFO) #define S_ISSOCK(m) (((m) & S_IFMT) == S_IFSOCK) -/************************************************************ +/**************************************************************************** * Type Definitions - ************************************************************/ + ****************************************************************************/ /* This is the simplified struct stat as returned by fstat(). * This structure provides information about a specific file @@ -111,9 +111,9 @@ struct stat time_t st_ctime; /* Time of last status change */ }; -/************************************************************ +/**************************************************************************** * Global Function Prototypes - ************************************************************/ + ****************************************************************************/ #undef EXTERN #if defined(__cplusplus) @@ -124,6 +124,7 @@ extern "C" { #endif EXTERN int mkdir(FAR const char *pathname, mode_t mode); +EXTERN int mkfifo(FAR const char *pathname, mode_t mode); EXTERN int stat(const char *path, FAR struct stat *buf); EXTERN int fstat(int fd, FAR struct stat *buf); -- cgit v1.2.3