summaryrefslogtreecommitdiff
diff options
context:
space:
mode:
authorpatacongo <patacongo@42af7a65-404d-4744-a932-0658087f49c3>2007-05-09 00:04:03 +0000
committerpatacongo <patacongo@42af7a65-404d-4744-a932-0658087f49c3>2007-05-09 00:04:03 +0000
commit039a51bde4bc3f21fe68c3f4cff966fde2532faa (patch)
treeec9942ae9a79d9a6b7315fd02f8b14d27ce95a27
parent0350e28418647956e6fecc5f6a096fb435cf47f4 (diff)
downloadpx4-nuttx-039a51bde4bc3f21fe68c3f4cff966fde2532faa.tar.gz
px4-nuttx-039a51bde4bc3f21fe68c3f4cff966fde2532faa.tar.bz2
px4-nuttx-039a51bde4bc3f21fe68c3f4cff966fde2532faa.zip
Add support for block drivers
git-svn-id: svn://svn.code.sf.net/p/nuttx/code/trunk@206 42af7a65-404d-4744-a932-0658087f49c3
-rw-r--r--nuttx/fs/Makefile5
-rw-r--r--nuttx/fs/fs_inode.c20
-rw-r--r--nuttx/fs/fs_inodefind.c4
-rw-r--r--nuttx/fs/fs_inodefinddir.c2
-rw-r--r--nuttx/fs/fs_inoderemove.c (renamed from nuttx/fs/fs_unregisterinode.c)50
-rw-r--r--nuttx/fs/fs_inodereserve.c (renamed from nuttx/fs/fs_registerinode.c)36
-rw-r--r--nuttx/fs/fs_internal.h72
-rw-r--r--nuttx/fs/fs_ioctl.c4
-rw-r--r--nuttx/fs/fs_open.c34
-rw-r--r--nuttx/fs/fs_read.c4
-rw-r--r--nuttx/fs/fs_readdir.c4
-rw-r--r--nuttx/fs/fs_registerblockdriver.c100
-rw-r--r--nuttx/fs/fs_registerdriver.c101
-rw-r--r--nuttx/fs/fs_write.c4
14 files changed, 340 insertions, 100 deletions
diff --git a/nuttx/fs/Makefile b/nuttx/fs/Makefile
index 8c57d6129..9a0638579 100644
--- a/nuttx/fs/Makefile
+++ b/nuttx/fs/Makefile
@@ -43,8 +43,9 @@ AOBJS = $(ASRCS:.S=$(OBJEXT))
CSRCS = fs_open.c fs_close.c fs_read.c fs_write.c fs_ioctl.c fs_dup.c \
fs_opendir.c fs_closedir.c fs_readdir.c fs_readdirr.c \
fs_seekdir.c fs_telldir.c fs_rewinddir.c fs_files.c \
- fs_inode.c fs_inodefind.c fs_inodefinddir.c fs_registerinode.c \
- fs_unregisterinode.c fs_inodeaddref.c fs_inoderelease.c
+ fs_inode.c fs_inodefind.c fs_inodefinddir.c fs_inodereserve.c \
+ fs_inoderemove.c fs_registerdriver.c fs_registerblockdriver.c \
+ fs_inodeaddref.c fs_inoderelease.c
COBJS = $(CSRCS:.c=$(OBJEXT))
SRCS = $(ASRCS) $(CSRCS)
diff --git a/nuttx/fs/fs_inode.c b/nuttx/fs/fs_inode.c
index 9c7cf3d07..274dcf1a4 100644
--- a/nuttx/fs/fs_inode.c
+++ b/nuttx/fs/fs_inode.c
@@ -209,7 +209,8 @@ void inode_semgive(void)
FAR struct inode *inode_search(const char **path,
FAR struct inode **peer,
- FAR struct inode **parent)
+ FAR struct inode **parent,
+ const char **relpath)
{
const char *name = *path + 1; /* Skip over leading '/' */
FAR struct inode *node = root_inode;
@@ -247,18 +248,25 @@ FAR struct inode *inode_search(const char **path,
else
{
- /* Now there are two more possibilities:
+ /* Now there are three more possibilities:
* (1) This is the node that we are looking for or,
- * (2) the node we are looking for is "blow" this one.
+ * (2) The node we are looking for is "below" this one.
+ * (3) This node is a mountpoint and will absorb all request
+ * below this one
*/
name = inode_nextname(name);
- if (!*name)
+ if (!*name || INODE_IS_MOUNTPT(node))
{
- /* We are at the end of the path, so this must be
- * the node we are looking for.
+ /* Either (1) we are at the end of the path, so this must be the
+ * node we are looking for or else (2) this node is a mountpoint
+ * and will handle the remaining part of the pathname
*/
+ if (relpath)
+ {
+ *relpath = name;
+ }
break;
}
else
diff --git a/nuttx/fs/fs_inodefind.c b/nuttx/fs/fs_inodefind.c
index 0df0b2ad5..215710311 100644
--- a/nuttx/fs/fs_inodefind.c
+++ b/nuttx/fs/fs_inodefind.c
@@ -74,7 +74,7 @@
*
************************************************************/
-FAR struct inode *inode_find(const char *path)
+FAR struct inode *inode_find(const char *path, const char **relpath)
{
FAR struct inode *node;
@@ -88,7 +88,7 @@ FAR struct inode *inode_find(const char *path)
*/
inode_semtake();
- node = inode_search(&path, (FAR void*)NULL, (FAR void*)NULL);
+ node = inode_search(&path, (FAR void*)NULL, (FAR void*)NULL, relpath);
if (node)
{
node->i_crefs++;
diff --git a/nuttx/fs/fs_inodefinddir.c b/nuttx/fs/fs_inodefinddir.c
index 73d818ba8..e9043903e 100644
--- a/nuttx/fs/fs_inodefinddir.c
+++ b/nuttx/fs/fs_inodefinddir.c
@@ -104,7 +104,7 @@ FAR struct inode *inode_finddir(const char *path)
/* Handle some special cases */
- node = inode_search(&path, (FAR void*)NULL, (FAR void*)NULL);
+ node = inode_search(&path, (FAR void*)NULL, (FAR void*)NULL, (FAR const char*)NULL);
if (node)
{
/* Does the inode have a child? If so that the child
diff --git a/nuttx/fs/fs_unregisterinode.c b/nuttx/fs/fs_inoderemove.c
index 37fd538ce..58ac734e7 100644
--- a/nuttx/fs/fs_unregisterinode.c
+++ b/nuttx/fs/fs_inoderemove.c
@@ -1,5 +1,5 @@
-/************************************************************
- * fs_unregisterinode.c
+/****************************************************************************
+ * fs_inoderemove.c
*
* Copyright (C) 2007 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <spudmonkey@racsa.co.cr>
@@ -31,11 +31,11 @@
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
* POSSIBILITY OF SUCH DAMAGE.
*
- ************************************************************/
+ ****************************************************************************/
-/************************************************************
+/****************************************************************************
* Included Files
- ************************************************************/
+ ****************************************************************************/
#include <nuttx/config.h>
#include <sys/types.h>
@@ -44,27 +44,27 @@
#include <nuttx/fs.h>
#include "fs_internal.h"
-/************************************************************
+/****************************************************************************
* Definitions
- ************************************************************/
+ ****************************************************************************/
-/************************************************************
+/****************************************************************************
* Private Variables
- ************************************************************/
+ ****************************************************************************/
-/************************************************************
+/****************************************************************************
* Public Variables
- ************************************************************/
+ ****************************************************************************/
-/************************************************************
+/****************************************************************************
* Private Functions
- ************************************************************/
+ ****************************************************************************/
-/************************************************************
- * Name: inode_remove
- ************************************************************/
+/****************************************************************************
+ * Name: inode_unlink
+ ****************************************************************************/
-static void inode_remove(struct inode *node,
+static void inode_unlink(struct inode *node,
struct inode *peer,
struct inode *parent)
{
@@ -95,15 +95,15 @@ static void inode_remove(struct inode *node,
node->i_peer = NULL;
}
-/************************************************************
+/****************************************************************************
* Public Functions
- ************************************************************/
+ ****************************************************************************/
-/************************************************************
- * Name: unregister_inode
- ************************************************************/
+/****************************************************************************
+ * Name: inode_remove
+ ****************************************************************************/
-STATUS unregister_inode(const char *path)
+STATUS inode_remove(const char *path)
{
const char *name = path;
FAR struct inode *node;
@@ -118,12 +118,12 @@ STATUS unregister_inode(const char *path)
/* Find the node to delete */
inode_semtake();
- node = inode_search(&name, &left, &parent);
+ node = inode_search(&name, &left, &parent, NULL);
if (node)
{
/* Found it, now remove it from the tree */
- inode_remove(node, left, parent);
+ inode_unlink(node, left, parent);
/* We cannot delete it if there reference to the inode */
diff --git a/nuttx/fs/fs_registerinode.c b/nuttx/fs/fs_inodereserve.c
index a2d7892e4..ad010e21e 100644
--- a/nuttx/fs/fs_registerinode.c
+++ b/nuttx/fs/fs_inodereserve.c
@@ -1,5 +1,5 @@
/************************************************************
- * fs_registerinode.c
+ * fs_registerreserve.c
*
* Copyright (C) 2007 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <spudmonkey@racsa.co.cr>
@@ -85,19 +85,12 @@ static void inode_namecpy(char *dest, const char *src)
* Name: inode_alloc
************************************************************/
-static FAR struct inode *inode_alloc(const char *name,
- struct file_operations *fops,
- mode_t mode, void *private)
+static FAR struct inode *inode_alloc(const char *name)
{
int namelen = inode_namelen(name);
FAR struct inode *node = (FAR struct inode*)zalloc(FSNODE_SIZE(namelen));
if (node)
{
- node->i_ops = fops;
-#ifdef CONFIG_FILE_MODE
- node->i_mode = mode;
-#endif
- node->i_private = private;
inode_namecpy(node->i_name, name);
}
return node;
@@ -145,12 +138,10 @@ static void inode_insert(FAR struct inode *node,
************************************************************/
/************************************************************
- * Name: register_inode
+ * Name: inode_reserve
************************************************************/
-STATUS register_inode(const char *path,
- struct file_operations *fops,
- mode_t mode, void *private)
+FAR struct inode *inode_reserve(const char *path)
{
const char *name = path;
FAR struct inode *left;
@@ -158,18 +149,16 @@ STATUS register_inode(const char *path,
if (!*path || path[0] != '/')
{
- return ERROR;
+ return NULL;
}
/* Find the location to insert the new subtree */
- inode_semtake();
- if (inode_search(&name, &left, &parent) != NULL)
+ if (inode_search(&name, &left, &parent, NULL) != NULL)
{
/* Is is an error if the node already exists in the tree */
- inode_semgive();
- return ERROR;
+ return NULL;
}
/* Now we now where to insert the subtree */
@@ -188,7 +177,7 @@ STATUS register_inode(const char *path,
{
/* Insert an operationless node */
- node = inode_alloc(name, NULL, mode, NULL);
+ node = inode_alloc(name);
if (node)
{
inode_insert(node, left, parent);
@@ -203,18 +192,15 @@ STATUS register_inode(const char *path,
}
else
{
- node = inode_alloc(name, fops, mode, private);
+ node = inode_alloc(name);
if (node)
{
inode_insert(node, left, parent);
- inode_semgive();
- return 0;
+ return node;
}
}
/* We get here on failures to allocate node memory */
-
- inode_semgive();
- return ERROR;
+ return NULL;
}
}
diff --git a/nuttx/fs/fs_internal.h b/nuttx/fs/fs_internal.h
index 111f56aae..e63d6029f 100644
--- a/nuttx/fs/fs_internal.h
+++ b/nuttx/fs/fs_internal.h
@@ -1,4 +1,4 @@
-/************************************************************
+/****************************************************************************
* fs_internal.h
*
* Copyright (C) 2007 Gregory Nutt. All rights reserved.
@@ -31,29 +31,47 @@
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
* POSSIBILITY OF SUCH DAMAGE.
*
- ************************************************************/
+ ****************************************************************************/
#ifndef __FS_INTERNAL_H
#define __FS_INTERNAL_H
-/************************************************************
+/****************************************************************************
* Included Files
- ************************************************************/
+ ****************************************************************************/
#include <nuttx/config.h>
#include <nuttx/fs.h>
#include <dirent.h>
#include <nuttx/compiler.h>
-/************************************************************
+/****************************************************************************
* Definitions
- ************************************************************/
-
-#define FSNODEFLAG_DELETED 0x00000001
-
-/************************************************************
+ ****************************************************************************/
+
+#define FSNODEFLAG_TYPE_MASK 0x00000003
+#define FSNODEFLAG_TYPE_DRIVER 0x00000000
+#define FSNODEFLAG_TYPE_BLOCK 0x00000001
+#define FSNODEFLAG_TYPE_MOUNTPT 0x00000002
+#define FSNODEFLAG_DELETED 0x00000004
+
+#define INODE_IS_DRIVER(i) \
+ (((i)->i_flags & FSNODEFLAG_TYPE_MASK) == FSNODEFLAG_TYPE_DRIVER)
+#define INODE_IS_BLOCK(i) \
+ (((i)->i_flags & FSNODEFLAG_TYPE_BLOCK) == FSNODEFLAG_TYPE_BLOCK)
+#define INODE_IS_MOUNTPT(i) \
+ (((i)->i_flags & FSNODEFLAG_TYPE_MOUNTPT) == FSNODEFLAG_TYPE_MOUNTPT)
+
+#define INODE_SET_DRIVER(i) \
+ ((i)->i_flags &= ~FSNODEFLAG_TYPE_MASK)
+#define INODE_SET_BLOCK(i) \
+ ((i)->i_flags = (((i)->i_flags & ~FSNODEFLAG_TYPE_MASK) | FSNODEFLAG_TYPE_BLOCK))
+#define INODE_SET_MOUNTP(i) \
+ ((i)->i_flags = (((i)->i_flags & ~FSNODEFLAG_TYPE_MASK) | FSNODEFLAG_TYPE_MOUNTP))
+
+/****************************************************************************
* Public Types
- ************************************************************/
+ ****************************************************************************/
/* The internal representation of type DIR is just a
* container for an inode reference and a dirent structure.
@@ -69,15 +87,15 @@ struct internal_dir_s
* is called */
};
-/************************************************************
+/****************************************************************************
* Global Variables
- ************************************************************/
+ ****************************************************************************/
extern FAR struct inode *root_inode;
-/************************************************************
+/****************************************************************************
* Pulblic Function Prototypes
- ************************************************************/
+ ****************************************************************************/
#undef EXTERN
#if defined(__cplusplus)
@@ -87,34 +105,42 @@ extern "C" {
#define EXTERN extern
#endif
-/* fs_inode.c ***********************************************/
+/* fs_inode.c ***************************************************************/
EXTERN void inode_semtake(void);
EXTERN void inode_semgive(void);
EXTERN FAR struct inode *inode_search(const char **path,
FAR struct inode **peer,
- FAR struct inode **parent);
+ FAR struct inode **parent,
+ const char **relpath);
EXTERN void inode_free(FAR struct inode *node);
EXTERN const char *inode_nextname(const char *name);
+/* fs_inodereserver.c ********************************************************/
+
+EXTERN FAR struct inode *inode_reserve(const char *path);
+
+/* fs_inoderemove.c **********************************************************/
+
+EXTERN STATUS inode_remove(const char *path);
-/* fs_inodefind.c ********************************************/
+/* fs_inodefind.c ************************************************************/
-EXTERN FAR struct inode *inode_find(const char *path);
+EXTERN FAR struct inode *inode_find(const char *path, const char **relpath);
-/* fs_inodefinddir.c *****************************************/
+/* fs_inodefinddir.c *********************************************************/
EXTERN FAR struct inode *inode_finddir(const char *path);
-/* fs_inodeaddref.c ******************************************/
+/* fs_inodeaddref.c **********************************************************/
EXTERN void inode_addref(FAR struct inode *inode);
-/* fs_inoderelease.c *****************************************/
+/* fs_inoderelease.c *********************************************************/
EXTERN void inode_release(FAR struct inode *inode);
-/* fs_files.c ***********************************************/
+/* fs_files.c ***************************************************************/
#if CONFIG_NFILE_DESCRIPTORS >0
EXTERN void weak_function files_initialize(void);
diff --git a/nuttx/fs/fs_ioctl.c b/nuttx/fs/fs_ioctl.c
index 2a49aec9b..8035c4cc4 100644
--- a/nuttx/fs/fs_ioctl.c
+++ b/nuttx/fs/fs_ioctl.c
@@ -77,11 +77,11 @@ int ioctl(int fd, int req, unsigned long arg)
/* Is a driver registered? Does it support the ioctl method? */
- if (inode && inode->i_ops && inode->i_ops->ioctl)
+ if (inode && inode->u.i_ops && inode->u.i_ops->ioctl)
{
/* Yes, then let it perform the ioctl */
- ret = (int)inode->i_ops->ioctl(this_file, req, arg);
+ ret = (int)inode->u.i_ops->ioctl(this_file, req, arg);
}
}
return ret;
diff --git a/nuttx/fs/fs_open.c b/nuttx/fs/fs_open.c
index 9b235f57b..0fc1b5133 100644
--- a/nuttx/fs/fs_open.c
+++ b/nuttx/fs/fs_open.c
@@ -60,8 +60,8 @@
int inode_checkflags(FAR struct inode *inode, int oflags)
{
- if (((oflags & O_RDOK) != 0 && !inode->i_ops->read) ||
- ((oflags & O_WROK) != 0 && !inode->i_ops->write))
+ if (((oflags & O_RDOK) != 0 && !inode->u.i_ops->read) ||
+ ((oflags & O_WROK) != 0 && !inode->u.i_ops->write))
{
*get_errno_ptr() = EACCES;
return ERROR;
@@ -105,18 +105,29 @@ int open(const char *path, int oflags, ...)
/* Get an inode for this file */
- inode = inode_find(path);
+ const char *relpath = NULL;
+ inode = inode_find(path, &relpath);
if (!inode)
{
/* "O_CREAT is not set and the named file does not exist. Or,
- * a directory component in pathname does not exist or is a
- * dangling symbolic link.
+ * a directory component in pathname does not exist or is a
+ * dangling symbolic link."
*/
*get_errno_ptr() = ENOENT;
return ERROR;
}
+ /* Verify that the inode is either a "normal" or a mountpoint. We
+ * specifically exclude block drivers.
+ */
+
+ if (!INODE_IS_DRIVER(inode) && !INODE_IS_MOUNTPT(inode))
+ {
+ *get_errno_ptr() = ENXIO;
+ return ERROR;
+ }
+
/* Make sure that the inode supports the requested access */
if (inode_checkflags(inode, oflags) != OK)
@@ -138,12 +149,19 @@ int open(const char *path, int oflags, ...)
/* Perform the driver open operation */
status = OK;
- if (inode->i_ops && inode->i_ops->open)
+ if (inode->u.i_ops && inode->u.i_ops->open)
{
- status = inode->i_ops->open((FAR struct file*)&list->fl_files[fd]);
+ if (INODE_IS_MOUNTPT(inode))
+ {
+ status = inode->u.i_ops->open((FAR struct file*)&list->fl_files[fd]);
+ }
+ else
+ {
+ status = inode->u.i_mops->open((FAR struct file*)&list->fl_files[fd], relpath);
+ }
}
- if (status != OK || !inode->i_ops)
+ if (status != OK || !inode->u.i_ops)
{
files_release(fd);
inode_release(inode);
diff --git a/nuttx/fs/fs_read.c b/nuttx/fs/fs_read.c
index 7d0edb25e..d5a97c553 100644
--- a/nuttx/fs/fs_read.c
+++ b/nuttx/fs/fs_read.c
@@ -83,11 +83,11 @@ int read(int fd, void *buf, unsigned int nbytes)
/* Is a driver registered? Does it support the read method? */
- if (inode && inode->i_ops && inode->i_ops->read)
+ if (inode && inode->u.i_ops && inode->u.i_ops->read)
{
/* Yes, then let it perform the read */
- ret = (int)inode->i_ops->read(this_file, (char*)buf, (size_t)nbytes);
+ ret = (int)inode->u.i_ops->read(this_file, (char*)buf, (size_t)nbytes);
}
}
}
diff --git a/nuttx/fs/fs_readdir.c b/nuttx/fs/fs_readdir.c
index 034770c80..54a880328 100644
--- a/nuttx/fs/fs_readdir.c
+++ b/nuttx/fs/fs_readdir.c
@@ -104,7 +104,7 @@ FAR struct dirent *readdir(DIR *dirp)
*/
idir->dir.d_type = 0;
- if (idir->next->i_ops)
+ if (idir->next->u.i_ops)
{
idir->dir.d_type |= DTYPE_FILE;
}
@@ -113,7 +113,7 @@ FAR struct dirent *readdir(DIR *dirp)
* is a directory. NOTE: that the node can be both!
*/
- if (idir->next->i_child || !idir->next->i_ops)
+ if (idir->next->i_child || !idir->next->u.i_ops)
{
idir->dir.d_type |= DTYPE_DIRECTORY;
}
diff --git a/nuttx/fs/fs_registerblockdriver.c b/nuttx/fs/fs_registerblockdriver.c
new file mode 100644
index 000000000..1e51deb37
--- /dev/null
+++ b/nuttx/fs/fs_registerblockdriver.c
@@ -0,0 +1,100 @@
+/************************************************************
+ * fs_registerblockdriver.c
+ *
+ * Copyright (C) 2007 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 Gregory Nutt nor the names of its contributors may be
+ * used to endorse or promote products derived from this software
+ * without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+ * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+ * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+ * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+ * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+ * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+ * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
+ * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
+ * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+ * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+ * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+ * POSSIBILITY OF SUCH DAMAGE.
+ *
+ ************************************************************/
+
+/************************************************************
+ * Included Files
+ ************************************************************/
+
+#include <nuttx/config.h>
+#include <sys/types.h>
+#include <errno.h>
+#include <nuttx/fs.h>
+#include "fs_internal.h"
+
+/************************************************************
+ * Definitions
+ ************************************************************/
+
+/************************************************************
+ * Private Variables
+ ************************************************************/
+
+/************************************************************
+ * Public Variables
+ ************************************************************/
+
+/************************************************************
+ * Private Functions
+ ************************************************************/
+
+/************************************************************
+ * Public Functions
+ ************************************************************/
+
+/************************************************************
+ * Name: register_driver
+ ************************************************************/
+
+STATUS register_blockdriver(const char *path,
+ const struct block_operations *bops,
+ mode_t mode, void *private)
+{
+ struct inode *node;
+ STATUS ret = ERROR;
+
+ /* Insert a dummy node -- we need to hold the inode semaphore
+ * to do this because we will have a momentarily bad structure.
+ */
+
+ inode_semtake();
+ node = inode_reserve(path);
+ if (node != NULL)
+ {
+ /* We have it, now populate it with block driver specific
+ * information.
+ */
+
+ INODE_SET_BLOCK(node);
+
+ node->u.i_bops = bops;
+#ifdef CONFIG_FILE_MODE
+ node->i_mode = mode;
+#endif
+ node->i_private = private;
+ ret = OK;
+ }
+ inode_semgive();
+ return ret;
+}
diff --git a/nuttx/fs/fs_registerdriver.c b/nuttx/fs/fs_registerdriver.c
new file mode 100644
index 000000000..c92a05216
--- /dev/null
+++ b/nuttx/fs/fs_registerdriver.c
@@ -0,0 +1,101 @@
+/************************************************************
+ * fs_registerdriver.c
+ *
+ * Copyright (C) 2007 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 Gregory Nutt nor the names of its contributors may be
+ * used to endorse or promote products derived from this software
+ * without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+ * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+ * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+ * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+ * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+ * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+ * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
+ * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
+ * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+ * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+ * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+ * POSSIBILITY OF SUCH DAMAGE.
+ *
+ ************************************************************/
+
+/************************************************************
+ * Included Files
+ ************************************************************/
+
+#include <nuttx/config.h>
+#include <sys/types.h>
+#include <errno.h>
+#include <nuttx/fs.h>
+#include "fs_internal.h"
+
+/************************************************************
+ * Definitions
+ ************************************************************/
+
+/************************************************************
+ * Private Variables
+ ************************************************************/
+
+/************************************************************
+ * Public Variables
+ ************************************************************/
+
+/************************************************************
+ * Private Functions
+ ************************************************************/
+
+/************************************************************
+ * Public Functions
+ ************************************************************/
+
+/************************************************************
+ * Name: register_driver
+ ************************************************************/
+
+STATUS register_driver(const char *path,
+ const struct file_operations *fops,
+ mode_t mode, void *private)
+{
+ struct inode *node;
+ STATUS ret = ERROR;
+
+ /* Insert a dummy node -- we need to hold the inode semaphore
+ * to do this because we will have a momentarily bad structure.
+ */
+
+ inode_semtake();
+ node = inode_reserve(path);
+ if (node != NULL)
+ {
+ /* We have it, now populate it with driver specific
+ * information.
+ */
+
+ INODE_SET_DRIVER(node);
+
+ node->u.i_ops = fops;
+#ifdef CONFIG_FILE_MODE
+ node->i_mode = mode;
+#endif
+ node->i_private = private;
+ ret = OK;
+ }
+
+ inode_semgive();
+ return ret;
+}
diff --git a/nuttx/fs/fs_write.c b/nuttx/fs/fs_write.c
index d25a88489..cebb49e60 100644
--- a/nuttx/fs/fs_write.c
+++ b/nuttx/fs/fs_write.c
@@ -83,11 +83,11 @@ int write(int fd, const void *buf, unsigned int nbytes)
/* Is a driver registered? Does it support the write method? */
- if (inode && inode->i_ops && inode->i_ops->write)
+ if (inode && inode->u.i_ops && inode->u.i_ops->write)
{
/* Yes, then let it perform the write */
- ret = inode->i_ops->write(this_file, buf, nbytes);
+ ret = inode->u.i_ops->write(this_file, buf, nbytes);
}
}
}