summaryrefslogtreecommitdiff
diff options
context:
space:
mode:
-rw-r--r--nuttx/include/net/ethernet.h10
-rw-r--r--nuttx/include/net/if.h10
-rw-r--r--nuttx/include/net/ioctls.h39
-rw-r--r--nuttx/include/nuttx/init.h8
-rw-r--r--nuttx/include/nuttx/ioctl.h95
-rw-r--r--nuttx/include/nuttx/irq.h32
-rw-r--r--nuttx/include/nuttx/lib.h30
-rw-r--r--nuttx/include/nuttx/mm.h8
-rw-r--r--nuttx/include/sys/ioctl.h29
-rw-r--r--nuttx/include/sys/mount.h8
-rw-r--r--nuttx/include/sys/statfs.h28
-rw-r--r--nuttx/include/sys/vfs.h28
12 files changed, 215 insertions, 110 deletions
diff --git a/nuttx/include/net/ethernet.h b/nuttx/include/net/ethernet.h
index 116f1c516..92a810c90 100644
--- a/nuttx/include/net/ethernet.h
+++ b/nuttx/include/net/ethernet.h
@@ -1,7 +1,7 @@
/****************************************************************************
- * net/ethernet.h
+ * include/net/ethernet.h
*
- * Copyright (C) 2007 Gregory Nutt. All rights reserved.
+ * Copyright (C) 2007, 2008 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <spudmonkey@racsa.co.cr>
*
* 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.
*
@@ -43,13 +43,13 @@
#include <sys/types.h>
/****************************************************************************
- * Definitions
+ * Pre-Processor Definitions
****************************************************************************/
#define ETHER_ADDR_LEN 6
/****************************************************************************
- * Type Definitions
+ * Public Type Definitions
****************************************************************************/
struct ether_addr
diff --git a/nuttx/include/net/if.h b/nuttx/include/net/if.h
index 7d8ea6007..cd3a23c89 100644
--- a/nuttx/include/net/if.h
+++ b/nuttx/include/net/if.h
@@ -1,7 +1,7 @@
/****************************************************************************
- * net/if.h
+ * include/net/if.h
*
- * Copyright (C) 2007 Gregory Nutt. All rights reserved.
+ * Copyright (C) 2007, 2008 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <spudmonkey@racsa.co.cr>
*
* 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.
*
@@ -43,7 +43,7 @@
#include <sys/socket.h>
/****************************************************************************
- * Definitions
+ * Pre-Processor Definitions
****************************************************************************/
/* Sizing parameters */
@@ -52,7 +52,7 @@
#define IFHWADDRLEN 6
/****************************************************************************
- * Type Definitions
+ * Public Type Definitions
****************************************************************************/
struct ifreq
diff --git a/nuttx/include/net/ioctls.h b/nuttx/include/net/ioctls.h
index 785c7d4f2..2395c1787 100644
--- a/nuttx/include/net/ioctls.h
+++ b/nuttx/include/net/ioctls.h
@@ -1,7 +1,7 @@
/****************************************************************************
- * net/ioctls.h
+ * include/net/ioctls.h
*
- * Copyright (C) 2007 Gregory Nutt. All rights reserved.
+ * Copyright (C) 2007, 2008 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <spudmonkey@racsa.co.cr>
*
* Redistribution and use in source and binary forms, with or without
@@ -40,32 +40,33 @@
* Included Files
****************************************************************************/
+#include <nuttx/ioctl.h> /* _SIOCBASE, etc. */
+
/****************************************************************************
* Definitions
****************************************************************************/
/* These are ioctl commands to use with a socket FD. At present, commnads
- * are accepted onloy to set/get IP addresses, broadcast address, network
+ * are accepted only to set/get IP addresses, broadcast address, network
* masks, and hardware address, and a few others
*/
-#define _SIOCBASE (0x8900)
-#define _SIOCMASK (0x00ff)
-#define _SIOCVALID(c) (((c) & ~_SIOCMASK) == _SIOCBASE)
+#define _SIOCVALID(c) (_IOC_TYPE(c)==_SIOCBASE)
+#define _SIOC(nr) _IOC(_SIOCBASE,nr)
-#define SIOCGIFADDR (_SIOCBASE|0x0001) /* Get IP address */
-#define SIOCSIFADDR (_SIOCBASE|0x0002) /* Set IP address */
-#define SIOCGIFDSTADDR (_SIOCBASE|0x0003) /* Get P-to-P address */
-#define SIOCSIFDSTADDR (_SIOCBASE|0x0004) /* Set P-to-P address */
-#define SIOCGIFBRDADDR (_SIOCBASE|0x0005) /* Get broadcast IP address */
-#define SIOCSIFBRDADDR (_SIOCBASE|0x0006) /* Set broadcast IP address */
-#define SIOCGIFNETMASK (_SIOCBASE|0x0007) /* Get network mask */
-#define SIOCSIFNETMASK (_SIOCBASE|0x0008) /* Set network mask */
-#define SIOCGIFMTU (_SIOCBASE|0x0009) /* Get MTU size */
-#define SIOCGIFHWADDR (_SIOCBASE|0x000a) /* Get hardware address */
-#define SIOCSIFHWADDR (_SIOCBASE|0x000b) /* Set hardware address */
-#define SIOCDIFADDR (_SIOCBASE|0x000c) /* Delete IP address */
-#define SIOCGIFCOUNT (_SIOCBASE|0x000d) /* Get number of devices */
+#define SIOCGIFADDR _SIOC(0x0001) /* Get IP address */
+#define SIOCSIFADDR _SIOC(0x0002) /* Set IP address */
+#define SIOCGIFDSTADDR _SIOC(0x0003) /* Get P-to-P address */
+#define SIOCSIFDSTADDR _SIOC(0x0004) /* Set P-to-P address */
+#define SIOCGIFBRDADDR _SIOC(0x0005) /* Get broadcast IP address */
+#define SIOCSIFBRDADDR _SIOC(0x0006) /* Set broadcast IP address */
+#define SIOCGIFNETMASK _SIOC(0x0007) /* Get network mask */
+#define SIOCSIFNETMASK _SIOC(0x0008) /* Set network mask */
+#define SIOCGIFMTU _SIOC(0x0009) /* Get MTU size */
+#define SIOCGIFHWADDR _SIOC(0x000a) /* Get hardware address */
+#define SIOCSIFHWADDR _SIOC(0x000b) /* Set hardware address */
+#define SIOCDIFADDR _SIOC(0x000c) /* Delete IP address */
+#define SIOCGIFCOUNT _SIOC(0x000d) /* Get number of devices */
/****************************************************************************
* Type Definitions
diff --git a/nuttx/include/nuttx/init.h b/nuttx/include/nuttx/init.h
index e8fdcaf8c..3dd75209b 100644
--- a/nuttx/include/nuttx/init.h
+++ b/nuttx/include/nuttx/init.h
@@ -1,7 +1,7 @@
/****************************************************************************
- * nuttx/init.h
+ * include/nuttx/init.h
*
- * Copyright (C) 2007 Gregory Nutt. All rights reserved.
+ * Copyright (C) 2007, 2008 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <spudmonkey@racsa.co.cr>
*
* 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.
*
@@ -44,7 +44,7 @@
#include <nuttx/compiler.h>
/****************************************************************************
- * Definitions
+ * Pre-Processor Definitions
****************************************************************************/
/****************************************************************************
diff --git a/nuttx/include/nuttx/ioctl.h b/nuttx/include/nuttx/ioctl.h
new file mode 100644
index 000000000..a61d1108d
--- /dev/null
+++ b/nuttx/include/nuttx/ioctl.h
@@ -0,0 +1,95 @@
+/****************************************************************************
+ * include/nuttx/ioctl.h
+ *
+ * Copyright (C) 2008 Gregory Nutt. All rights reserved.
+ * Author: Gregory Nutt <spudmonkey@racsa.co.cr>
+ *
+ * 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 __NUTTX_IOCTL_H
+#define __NUTTX_IOCTL_H
+
+/****************************************************************************
+ * Included Files
+ ****************************************************************************/
+
+#include <nuttx/config.h>
+#include <sys/types.h>
+
+/****************************************************************************
+ * Pre-Processor Definitions
+ ****************************************************************************/
+
+/* Each NuttX ioctl commands are uint16's consisting of an 8-bit type
+ * identifier and an 8-bit command number. All comman type identifiers are
+ * defined below:
+ */
+
+#define _BIOCBASE (0x8800) /* Block driver ioctl commands */
+#define _SIOCBASE (0x8900) /* Socket ioctl commandss */
+
+/* Macros used to manage ioctl commands */
+
+#define _IOC_MASK (0x00ff)
+#define _IOC_TYPE(cmd) ((cmd)&~_IOC_MASK)
+#define _IOC_NR(cmd) ((cmd)&_IOC_MASK)
+
+#define _IOC(type,nr) ((type)|(nr))
+
+/* NuttX block driver ioctl definitions */
+
+#define _BIOCVALID(c) (_IOC_TYPE(c)==_BIOCBASE)
+#define _BIOC(nr) _IOC(_SIOCBASE,nr)
+
+#define _BIOC_XIPBASE _BIOC(0x0001) /* IN: None
+ * OUT: If underlying is random acccesible,
+ * return (void*) base address */
+
+/****************************************************************************
+ * Public Type Definitions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Public Function Prototypes
+ ****************************************************************************/
+
+#ifdef __cplusplus
+#define EXTERN extern "C"
+extern "C" {
+#else
+#define EXTERN extern
+#endif
+
+#undef EXTERN
+#ifdef __cplusplus
+}
+#endif
+
+#endif /* __NUTTX_IOCTL_H */
diff --git a/nuttx/include/nuttx/irq.h b/nuttx/include/nuttx/irq.h
index e9b66293c..388b631d6 100644
--- a/nuttx/include/nuttx/irq.h
+++ b/nuttx/include/nuttx/irq.h
@@ -1,7 +1,7 @@
-/************************************************************
- * irq.h
+/****************************************************************************
+ * include/nuttx/irq.h
*
- * Copyright (C) 2007 Gregory Nutt. All rights reserved.
+ * Copyright (C) 2007, 2008 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <spudmonkey@racsa.co.cr>
*
* 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,31 +31,31 @@
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
* POSSIBILITY OF SUCH DAMAGE.
*
- ************************************************************/
+ ****************************************************************************/
#ifndef __IRQ_H
#define __IRQ_H
-/************************************************************
+/****************************************************************************
* Included Files
- ************************************************************/
+ ****************************************************************************/
#ifndef __ASSEMBLY__
# include <sys/types.h>
# include <assert.h>
#endif
-/************************************************************
- * Definitions
- ************************************************************/
+/****************************************************************************
+ * Pre-Processor Definitions
+ ****************************************************************************/
#ifndef __ASSEMBLY__
# define irq_detach(isr) irq_attach(isr, NULL)
#endif
-/************************************************************
+/****************************************************************************
* Public Types
- ************************************************************/
+ ****************************************************************************/
/* This struct defines the way the registers are stored */
@@ -69,13 +69,13 @@ typedef int (*swint_t)(int code, int parm2, int parm3,
#include <arch/irq.h>
-/************************************************************
+/****************************************************************************
* Public Variables
- ************************************************************/
+ ****************************************************************************/
-/************************************************************
+/****************************************************************************
* Public Function Prototypes
- ************************************************************/
+ ****************************************************************************/
#ifndef __ASSEMBLY__
#ifdef __cplusplus
diff --git a/nuttx/include/nuttx/lib.h b/nuttx/include/nuttx/lib.h
index cca174aa3..f9892bb4c 100644
--- a/nuttx/include/nuttx/lib.h
+++ b/nuttx/include/nuttx/lib.h
@@ -1,7 +1,7 @@
-/************************************************************
- * lib.h
+/****************************************************************************
+ * include/nuttx/lib.h
*
- * Copyright (C) 2007 Gregory Nutt. All rights reserved.
+ * Copyright (C) 2007, 2008 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <spudmonkey@racsa.co.cr>
*
* 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,29 +31,29 @@
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
* POSSIBILITY OF SUCH DAMAGE.
*
- ************************************************************/
+ ****************************************************************************/
#ifndef __LIB_H
#define __LIB_H
-/************************************************************
+/****************************************************************************
* Included Files
- ************************************************************/
+ ****************************************************************************/
#include <nuttx/config.h>
#include <nuttx/fs.h>
-/************************************************************
- * Definitions
- ************************************************************/
+/****************************************************************************
+ * Pre-Processor Definitions
+ ****************************************************************************/
-/************************************************************
+/****************************************************************************
* Global Function Prototypes
- ************************************************************/
+ ****************************************************************************/
-/************************************************************
+/****************************************************************************
* Global Function Prototypes
- ************************************************************/
+ ****************************************************************************/
#ifdef __cplusplus
#define EXTERN extern "C"
@@ -62,7 +62,7 @@ extern "C" {
#define EXTERN extern
#endif
-/* Functions contained in lib_init.c ************************/
+/* Functions contained in lib_init.c ****************************************/
EXTERN void weak_function lib_initialize(void);
#if CONFIG_NFILE_STREAMS > 0
diff --git a/nuttx/include/nuttx/mm.h b/nuttx/include/nuttx/mm.h
index 8b537a570..77dcfc5d0 100644
--- a/nuttx/include/nuttx/mm.h
+++ b/nuttx/include/nuttx/mm.h
@@ -1,7 +1,7 @@
/****************************************************************************
- * nuttx/mm.h
+ * include/nuttx/mm.h
*
- * Copyright (C) 2007 Gregory Nutt. All rights reserved.
+ * Copyright (C) 2007, 2008 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <spudmonkey@racsa.co.cr>
*
* 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.
*
@@ -43,7 +43,7 @@
#include <nuttx/config.h>
/****************************************************************************
- * Definitions
+ * Pre-Processor Definitions
****************************************************************************/
/****************************************************************************
diff --git a/nuttx/include/sys/ioctl.h b/nuttx/include/sys/ioctl.h
index dc7ae0574..03c79ebef 100644
--- a/nuttx/include/sys/ioctl.h
+++ b/nuttx/include/sys/ioctl.h
@@ -1,7 +1,7 @@
-/************************************************************
- * ioctl.h
+/****************************************************************************
+ * include/sys/ioctl.h
*
- * Copyright (C) 2007 Gregory Nutt. All rights reserved.
+ * Copyright (C) 2007, 2008 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <spudmonkey@racsa.co.cr>
*
* 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,18 +31,19 @@
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
* POSSIBILITY OF SUCH DAMAGE.
*
- ************************************************************/
+ ****************************************************************************/
#ifndef __SYS_IOCTL_H
#define __SYS_IOCTL_H
-/************************************************************
+/****************************************************************************
* Included Files
- ************************************************************/
+ ****************************************************************************/
-/* Get NuttX configuration */
+/* Get NuttX configuration and NuttX-specific IOCTL definitions */
#include <nuttx/config.h>
+#include <nuttx/ioctl.h>
/* Include network ioctls info */
@@ -50,13 +51,17 @@
# include <net/ioctls.h>
#endif
-/************************************************************
+/****************************************************************************
+ * Pre-Processor Definitions
+ ****************************************************************************/
+
+/****************************************************************************
* Type Definitions
- ************************************************************/
+ ****************************************************************************/
-/************************************************************
+/****************************************************************************
* Public Function Prototypes
- ************************************************************/
+ ****************************************************************************/
#undef EXTERN
#if defined(__cplusplus)
diff --git a/nuttx/include/sys/mount.h b/nuttx/include/sys/mount.h
index 30433809f..0199325d7 100644
--- a/nuttx/include/sys/mount.h
+++ b/nuttx/include/sys/mount.h
@@ -1,7 +1,7 @@
/****************************************************************************
- * sys/mount.h
+ * include/sys/mount.h
*
- * Copyright (C) 2007 Gregory Nutt. All rights reserved.
+ * Copyright (C) 2007, 2008 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <spudmonkey@racsa.co.cr>
*
* 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.
*
@@ -43,7 +43,7 @@
#include <sys/types.h>
/****************************************************************************
- * Definitions
+ * Pre-Processor Definitions
****************************************************************************/
/* Mount flags */
diff --git a/nuttx/include/sys/statfs.h b/nuttx/include/sys/statfs.h
index c677e7f1a..05688f566 100644
--- a/nuttx/include/sys/statfs.h
+++ b/nuttx/include/sys/statfs.h
@@ -1,7 +1,7 @@
-/************************************************************
- * sys/statfs.h
+/****************************************************************************
+ * include/sys/statfs.h
*
- * Copyright (C) 2007 Gregory Nutt. All rights reserved.
+ * Copyright (C) 2007, 2008 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <spudmonkey@racsa.co.cr>
*
* 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_STATFS_H
#define __SYS_STATFS_H
-/************************************************************
+/****************************************************************************
* Included Files
- ************************************************************/
+ ****************************************************************************/
#include <nuttx/config.h>
#include <sys/types.h>
-/************************************************************
- * Definitions
- ************************************************************/
+/****************************************************************************
+ * Pre-Processor Definitions
+ ****************************************************************************/
/* struct statfs file system types. */
@@ -94,9 +94,9 @@
#define XFS_SUPER_MAGIC 0x58465342
#define _XIAFS_SUPER_MAGIC 0x012FD16D
-/************************************************************
+/****************************************************************************
* Type Definitions
- ************************************************************/
+ ****************************************************************************/
struct statfs
{
@@ -110,9 +110,9 @@ struct statfs
uint32 f_namelen; /* Maximum length of filenames */
};
-/************************************************************
+/****************************************************************************
* Public Function Prototypes
- ************************************************************/
+ ****************************************************************************/
#undef EXTERN
#if defined(__cplusplus)
diff --git a/nuttx/include/sys/vfs.h b/nuttx/include/sys/vfs.h
index d1633f5ec..6625a9fa4 100644
--- a/nuttx/include/sys/vfs.h
+++ b/nuttx/include/sys/vfs.h
@@ -1,7 +1,7 @@
-/************************************************************
- * sys/vfs.h
+/****************************************************************************
+ * include/sys/vfs.h
*
- * Copyright (C) 2007 Gregory Nutt. All rights reserved.
+ * Copyright (C) 2007, 2008 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <spudmonkey@racsa.co.cr>
*
* 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,14 +31,14 @@
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
* POSSIBILITY OF SUCH DAMAGE.
*
- ************************************************************/
+ ****************************************************************************/
#ifndef __SYS_VFS_H
#define __SYS_VFS_H
-/************************************************************
+/****************************************************************************
* Included Files
- ************************************************************/
+ ****************************************************************************/
/* sys/vfs.h is just an alternative location for the
* information in sys/statfs.h.
@@ -46,12 +46,16 @@
#include <sys/statfs.h>
-/************************************************************
- * Type Definitions
- ************************************************************/
+/****************************************************************************
+ * Pre-Processor Definitions
+ ****************************************************************************/
-/************************************************************
+/****************************************************************************
+ * Public Type Definitions
+ ****************************************************************************/
+
+/****************************************************************************
* Public Function Prototypes
- ************************************************************/
+ ****************************************************************************/
#endif /* __SYS_VFS_H */