summaryrefslogtreecommitdiff
diff options
context:
space:
mode:
authorpatacongo <patacongo@42af7a65-404d-4744-a932-0658087f49c3>2013-01-16 14:14:14 +0000
committerpatacongo <patacongo@42af7a65-404d-4744-a932-0658087f49c3>2013-01-16 14:14:14 +0000
commitf06a61ad2416526b0f9afddc0b42fb5c928b7093 (patch)
tree5c82c94b6cb8e68f1ffda9326d9cb2f108e5db86
parent9cc7477faf3e49678aa827a6bc1ab99e2812c4d8 (diff)
downloadpx4-nuttx-f06a61ad2416526b0f9afddc0b42fb5c928b7093.tar.gz
px4-nuttx-f06a61ad2416526b0f9afddc0b42fb5c928b7093.tar.bz2
px4-nuttx-f06a61ad2416526b0f9afddc0b42fb5c928b7093.zip
BINFS now supports open, close, and FIOC_FILENAME ioctl
git-svn-id: svn://svn.code.sf.net/p/nuttx/code/trunk@5522 42af7a65-404d-4744-a932-0658087f49c3
-rw-r--r--apps/ChangeLog.txt4
-rw-r--r--apps/builtin/binfs.c331
-rw-r--r--apps/include/apps.h3
-rw-r--r--nuttx/TODO21
-rw-r--r--nuttx/binfmt/binfmt_execmodule.c14
-rw-r--r--nuttx/fs/nfs/nfs_vfsops.c61
-rw-r--r--nuttx/fs/nxffs/nxffs_open.c3
-rw-r--r--nuttx/include/nuttx/fs/binfs.h80
-rw-r--r--nuttx/include/nuttx/fs/ioctl.h1
9 files changed, 216 insertions, 302 deletions
diff --git a/apps/ChangeLog.txt b/apps/ChangeLog.txt
index ea4fcd07b..f91dc318b 100644
--- a/apps/ChangeLog.txt
+++ b/apps/ChangeLog.txt
@@ -469,3 +469,7 @@
* builtin/binfs.c: Add hooks for dup() method (not implemented).
* builtin/exec_builtin.c, nshlib/nsh_parse.c, and nshlib/nsh_builtin.c:
NSH now supports re-direction of I/O to files (but still not from).
+ * builtin/binfs.c: Greatly simplified (it is going to need to be
+ very lightweight). Now supports open, close, and a new ioctl to recover
+ the builtin filename. The latter will be needed to support a binfs
+ binfmt.
diff --git a/apps/builtin/binfs.c b/apps/builtin/binfs.c
index 1fc2e7940..611e2b3bb 100644
--- a/apps/builtin/binfs.c
+++ b/apps/builtin/binfs.c
@@ -45,7 +45,6 @@
#include <stdint.h>
#include <stdbool.h>
-#include <stdlib.h>
#include <string.h>
#include <fcntl.h>
#include <assert.h>
@@ -53,8 +52,11 @@
#include <debug.h>
#include <nuttx/fs/fs.h>
+#include <nuttx/fs/binfs.h>
#include <nuttx/fs/dirent.h>
+#include <apps/apps.h>
+
#include "builtin.h"
#if !defined(CONFIG_DISABLE_MOUNTPOINT) && defined(CONFIG_APPS_BINDIR)
@@ -63,24 +65,12 @@
* Private Types
****************************************************************************/
-/* This structure represents the overall mountpoint state. An instance of this
- * structure is retained as inode private data on each mountpoint that is
- * mounted with a fat32 filesystem.
- */
-
-struct binfs_state_s
-{
- sem_t bm_sem; /* Used to assume thread-safe access */
-};
-
/****************************************************************************
* Private Function Prototypes
****************************************************************************/
-static void binfs_semtake(struct binfs_state_s *bm);
-static inline void binfs_semgive(struct binfs_state_s *bm);
static int binfs_open(FAR struct file *filep, const char *relpath,
- int oflags, mode_t mode);
+ int oflags, mode_t mode);
static int binfs_close(FAR struct file *filep);
static ssize_t binfs_read(FAR struct file *filep, char *buffer, size_t buflen);
static int binfs_ioctl(FAR struct file *filep, int cmd, unsigned long arg);
@@ -89,15 +79,19 @@ static int binfs_dup(FAR const struct file *oldp, FAR struct file *newp);
static int binfs_opendir(struct inode *mountpt, const char *relpath,
struct fs_dirent_s *dir);
-static int binfs_readdir(struct inode *mountpt, struct fs_dirent_s *dir);
-static int binfs_rewinddir(struct inode *mountpt, struct fs_dirent_s *dir);
+static int binfs_readdir(FAR struct inode *mountpt,
+ FAR struct fs_dirent_s *dir);
+static int binfs_rewinddir(FAR struct inode *mountpt,
+ FAR struct fs_dirent_s *dir);
-static int binfs_bind(FAR struct inode *blkdriver, const void *data,
- void **handle);
-static int binfs_unbind(void *handle, FAR struct inode **blkdriver);
-static int binfs_statfs(struct inode *mountpt, struct statfs *buf);
+static int binfs_bind(FAR struct inode *blkdriver, FAR const void *data,
+ FAR void **handle);
+static int binfs_unbind(FAR void *handle, FAR struct inode **blkdriver);
+static int binfs_statfs(FAR struct inode *mountpt,
+ FAR struct statfs *buf);
-static int binfs_stat(struct inode *mountpt, const char *relpath, struct stat *buf);
+static int binfs_stat(FAR struct inode *mountpt, FAR const char *relpath,
+ FAR struct stat *buf);
/****************************************************************************
* Private Variables
@@ -145,70 +139,41 @@ const struct mountpt_operations binfs_operations =
****************************************************************************/
/****************************************************************************
- * Name: binfs_semtake
- ****************************************************************************/
-
-static void binfs_semtake(struct binfs_state_s *bm)
-{
- /* Take the semaphore (perhaps waiting) */
-
- while (sem_wait(&bm->bm_sem) != 0)
- {
- /* The only case that an error should occur here is if
- * the wait was awakened by a signal.
- */
-
- ASSERT(errno == EINTR);
- }
-}
-
-/****************************************************************************
- * Name: binfs_semgive
- ****************************************************************************/
-
-static inline void binfs_semgive(struct binfs_state_s *bm)
-{
- sem_post(&bm->bm_sem);
-}
-
-/****************************************************************************
* Name: binfs_open
****************************************************************************/
-static int binfs_open(FAR struct file *filep, const char *relpath,
- int oflags, mode_t mode)
+static int binfs_open(FAR struct file *filep, FAR const char *relpath,
+ int oflags, mode_t mode)
{
- struct binfs_state_s *bm;
- int ret = -ENOSYS;
+ int index;
fvdbg("Open '%s'\n", relpath);
- /* Sanity checks */
-
- DEBUGASSERT(filep->f_priv == NULL && filep->f_inode != NULL);
-
- /* mountpoint private data from the inode reference from the file
- * structure
- */
-
- bm = (struct binfs_state_s*)filep->f_inode->i_private;
- DEBUGASSERT(bm != NULL);
-
/* BINFS is read-only. Any attempt to open with any kind of write
* access is not permitted.
*/
if ((oflags & O_WRONLY) != 0 || (oflags & O_RDONLY) == 0)
{
- fdbg("Only O_RDONLY supported\n");
- ret = -EACCES;
+ fdbg("ERROR: Only O_RDONLY supported\n");
+ return -EACCES;
}
- /* Save open-specific state in filep->f_priv */
+ /* Check if the an entry exists with this name in the root directory.
+ * so the 'relpath' must be the name of the builtin function.
+ */
- /* Opening of elements within the pseudo-file system is not yet supported */
+ index = builtin_isavail(relpath);
+ if (index < 0)
+ {
+ fdbg("ERROR: Builting %s does not exist\n", relpath);
+ return -ENOENT;
+ }
- return ret;
+ /* Save the index as the open-specific state in filep->f_priv */
+
+ filep->f_priv = (FAR void *)index;
+ return OK;
}
/****************************************************************************
@@ -217,31 +182,8 @@ static int binfs_open(FAR struct file *filep, const char *relpath,
static int binfs_close(FAR struct file *filep)
{
- struct binfs_state_s *bm;
- int ret = -ENOSYS;
-
fvdbg("Closing\n");
-
- /* Sanity checks */
-
- DEBUGASSERT(filep->f_priv != NULL && filep->f_inode != NULL);
-
- /* Recover the open file state from the struct file instance */
- /* bf = filep->f_priv; */
-
- /* Recover the file system state from the inode */
-
- bm = filep->f_inode->i_private;
- DEBUGASSERT(bm != NULL);
-
- /* Free the open file state */
- /* free(bf); */
-
- filep->f_priv = NULL;
-
- /* Since open() is not yet supported, neither is close(). */
-
- return ret;
+ return OK;
}
/****************************************************************************
@@ -250,25 +192,10 @@ static int binfs_close(FAR struct file *filep)
static ssize_t binfs_read(FAR struct file *filep, char *buffer, size_t buflen)
{
- struct binfs_state_s *bm;
+ /* Reading is not supported. Just return end-of-file */
fvdbg("Read %d bytes from offset %d\n", buflen, filep->f_pos);
-
- /* Sanity checks */
-
- DEBUGASSERT(filep->f_priv != NULL && filep->f_inode != NULL);
-
- /* Recover the open file state data from the struct file instance */
- /* bf = filep->f_priv; */
-
- /* Recover the file system state from the inode */
-
- bm = filep->f_inode->i_private;
- DEBUGASSERT(bm != NULL);
-
- /* Since open is not yet supported, neither is reading */
-
- return -ENOSYS;
+ return 0;
}
/****************************************************************************
@@ -277,25 +204,36 @@ static ssize_t binfs_read(FAR struct file *filep, char *buffer, size_t buflen)
static int binfs_ioctl(FAR struct file *filep, int cmd, unsigned long arg)
{
- struct binfs_state_s *bm;
+ int ret;
fvdbg("cmd: %d arg: %08lx\n", cmd, arg);
- /* Sanity checks */
-
- DEBUGASSERT(filep->f_priv != NULL && filep->f_inode != NULL);
-
- /* Recover the open file state from the struct file instance */
- /* bf = filep->f_priv; */
+ /* Only one IOCTL command is supported */
- /* Recover the file system state from the inode */
-
- bm = filep->f_inode->i_private;
- DEBUGASSERT(bm != NULL);
+ if (cmd == FIOC_FILENAME)
+ {
+ /* IN: FAR char const ** pointer
+ * OUT: Pointer to a persistent file name (Guaranteed to persist while
+ * the file is open).
+ */
- /* No ioctl commands yet supported */
+ FAR const char **ptr = (FAR const char **)((uintptr_t)arg);
+ if (ptr == NULL)
+ {
+ ret = -EINVAL;
+ }
+ else
+ {
+ *ptr = g_builtins[(int)filep->f_priv].name;
+ ret = OK;
+ }
+ }
+ else
+ {
+ ret = -ENOTTY;
+ }
- return -ENOTTY;
+ return ret;
}
/****************************************************************************
@@ -308,27 +246,12 @@ static int binfs_ioctl(FAR struct file *filep, int cmd, unsigned long arg)
static int binfs_dup(FAR const struct file *oldp, FAR struct file *newp)
{
- struct binfs_state_s *bm;
- int ret = -ENOSYS;
-
fvdbg("Dup %p->%p\n", oldp, newp);
- /* Sanity checks */
-
- DEBUGASSERT(oldp->f_priv == NULL && oldp->f_inode != NULL);
-
- /* mountpoint private data from the inode reference from the file
- * structure
- */
-
- bm = (struct binfs_state_s*)oldp->f_inode->i_private;
- DEBUGASSERT(bm != NULL);
-
- /* Opening of elements within the pseudo-file system is not yet supported
- * and, hence, neither is dup'ing the opened file.
- */
+ /* Copy the index from the old to the new file structure */
- return ret;
+ newp->f_priv = oldp->f_priv;
+ return OK;
}
/****************************************************************************
@@ -342,36 +265,19 @@ static int binfs_dup(FAR const struct file *oldp, FAR struct file *newp)
static int binfs_opendir(struct inode *mountpt, const char *relpath,
struct fs_dirent_s *dir)
{
- struct binfs_state_s *bm;
- int ret;
-
fvdbg("relpath: \"%s\"\n", relpath ? relpath : "NULL");
- /* Sanity checks */
-
- DEBUGASSERT(mountpt != NULL && mountpt->i_private != NULL);
-
- /* Recover the file system state from the inode instance */
-
- bm = mountpt->i_private;
- binfs_semtake(bm);
-
/* The requested directory must be the volume-relative "root" directory */
if (relpath && relpath[0] != '\0')
{
- ret = -ENOENT;
- goto errout_with_semaphore;
+ return -ENOENT;
}
/* Set the index to the first entry */
dir->u.binfs.fb_index = 0;
- ret = OK;
-
-errout_with_semaphore:
- binfs_semgive(bm);
- return ret;
+ return OK;
}
/****************************************************************************
@@ -383,19 +289,9 @@ errout_with_semaphore:
static int binfs_readdir(struct inode *mountpt, struct fs_dirent_s *dir)
{
- struct binfs_state_s *bm;
unsigned int index;
int ret;
- /* Sanity checks */
-
- DEBUGASSERT(mountpt != NULL && mountpt->i_private != NULL);
-
- /* Recover the file system state from the inode instance */
-
- bm = mountpt->i_private;
- binfs_semtake(bm);
-
/* Have we reached the end of the directory */
index = dir->u.binfs.fb_index;
@@ -426,11 +322,10 @@ static int binfs_readdir(struct inode *mountpt, struct fs_dirent_s *dir)
* standard f_pos instead of our own private fb_index.
*/
- dir->u.binfs.fb_index = index;
- ret = OK;
+ dir->u.binfs.fb_index = index;
+ ret = OK;
}
- binfs_semgive(bm);
return ret;
}
@@ -443,22 +338,9 @@ static int binfs_readdir(struct inode *mountpt, struct fs_dirent_s *dir)
static int binfs_rewinddir(struct inode *mountpt, struct fs_dirent_s *dir)
{
- struct binfs_state_s *bm;
-
fvdbg("Entry\n");
- /* Sanity checks */
-
- DEBUGASSERT(mountpt != NULL && mountpt->i_private != NULL);
-
- /* Recover the file system state from the inode instance */
-
- bm = mountpt->i_private;
- binfs_semtake(bm);
-
- dir->u.binfs.fb_index = 0;
-
- binfs_semgive(bm);
+ dir->u.binfs.fb_index = 0;
return OK;
}
@@ -476,29 +358,7 @@ static int binfs_rewinddir(struct inode *mountpt, struct fs_dirent_s *dir)
static int binfs_bind(FAR struct inode *blkdriver, const void *data,
void **handle)
{
- struct binfs_state_s *bm;
-
fvdbg("Entry\n");
-
- /* Create an instance of the mountpt state structure */
-
- bm = (struct binfs_state_s *)zalloc(sizeof(struct binfs_state_s));
- if (!bm)
- {
- fdbg("Failed to allocate mountpoint structure\n");
- return -ENOMEM;
- }
-
- /* Initialize the allocated mountpt state structure. The filesystem is
- * responsible for one reference ont the blkdriver inode and does not
- * have to addref() here (but does have to release in ubind().
- */
-
- sem_init(&bm->bm_sem, 0, 1); /* Initialize the semaphore that controls access */
-
- /* Mounted! */
-
- *handle = (void*)bm;
return OK;
}
@@ -512,22 +372,7 @@ static int binfs_bind(FAR struct inode *blkdriver, const void *data,
static int binfs_unbind(void *handle, FAR struct inode **blkdriver)
{
- struct binfs_state_s *bm = (struct binfs_state_s*)handle;
-
fvdbg("Entry\n");
-
-#ifdef CONFIG_DEBUG
- if (!bm)
- {
- return -EINVAL;
- }
-#endif
-
- /* Check if there are sill any files opened on the filesystem. */
-
- /* Release the mountpoint private data */
-
- sem_destroy(&bm->bm_sem);
return OK;
}
@@ -540,19 +385,8 @@ static int binfs_unbind(void *handle, FAR struct inode **blkdriver)
static int binfs_statfs(struct inode *mountpt, struct statfs *buf)
{
- struct binfs_state_s *bm;
-
fvdbg("Entry\n");
- /* Sanity checks */
-
- DEBUGASSERT(mountpt && mountpt->i_private);
-
- /* Get the mountpoint private data from the inode structure */
-
- bm = mountpt->i_private;
- binfs_semtake(bm);
-
/* Fill in the statfs info */
memset(buf, 0, sizeof(struct statfs));
@@ -562,8 +396,6 @@ static int binfs_statfs(struct inode *mountpt, struct statfs *buf)
buf->f_bfree = 0;
buf->f_bavail = 0;
buf->f_namelen = NAME_MAX;
-
- binfs_semgive(bm);
return OK;
}
@@ -576,20 +408,8 @@ static int binfs_statfs(struct inode *mountpt, struct statfs *buf)
static int binfs_stat(struct inode *mountpt, const char *relpath, struct stat *buf)
{
- struct binfs_state_s *bm;
- int ret;
-
fvdbg("Entry\n");
- /* Sanity checks */
-
- DEBUGASSERT(mountpt && mountpt->i_private);
-
- /* Get the mountpoint private data from the inode structure */
-
- bm = mountpt->i_private;
- binfs_semtake(bm);
-
/* The requested directory must be the volume-relative "root" directory */
if (relpath && relpath[0] != '\0')
@@ -598,8 +418,7 @@ static int binfs_stat(struct inode *mountpt, const char *relpath, struct stat *b
if (builtin_isavail(relpath) < 0)
{
- ret = -ENOENT;
- goto errout_with_semaphore;
+ return -ENOENT;
}
/* It's a execute-only file name */
@@ -615,14 +434,10 @@ static int binfs_stat(struct inode *mountpt, const char *relpath, struct stat *b
/* File/directory size, access block size */
- buf->st_size = 0;
- buf->st_blksize = 0;
- buf->st_blocks = 0;
- ret = OK;
-
-errout_with_semaphore:
- binfs_semgive(bm);
- return ret;
+ buf->st_size = 0;
+ buf->st_blksize = 0;
+ buf->st_blocks = 0;
+ return OK;
}
/****************************************************************************
diff --git a/apps/include/apps.h b/apps/include/apps.h
index f806d8aed..9f1918e57 100644
--- a/apps/include/apps.h
+++ b/apps/include/apps.h
@@ -48,9 +48,12 @@
****************************************************************************/
#include <nuttx/config.h>
+
#include <sys/types.h>
#include <stdint.h>
+#include <nuttx/fs/ioctl.h>
+
/****************************************************************************
* Pre-processor Definitions
****************************************************************************/
diff --git a/nuttx/TODO b/nuttx/TODO
index 58ca4cc8e..248d2dafa 100644
--- a/nuttx/TODO
+++ b/nuttx/TODO
@@ -6,7 +6,7 @@ standards, things that could be improved, and ideas for enhancements.
nuttx/
- (11) Task/Scheduler (sched/)
+ (10) Task/Scheduler (sched/)
(1) Memory Managment (mm/)
(3) Signals (sched/, arch/)
(2) pthreads (sched/)
@@ -58,16 +58,6 @@ o Task/Scheduler (sched/)
Status: Closed. No, this behavior will not be implemented.
Priority: Medium, required for good emulation of process/pthread model.
- Title: MISSING ERRNO SETTINGS
- Description: Several APIs do not set errno. Need to review all APIs.
- Update: These are being fixed as they are encountered. There is
- no accounting of how many interfaces have this problem.
- Status: Open? There has been an effort over the past few years to assure
- that all errno settings are in place. What is the current state?
- Unknown.
- Priority: Medium, required for standard compliance (but makes the
- code bigger)
-
Title: TICKLESS OS
Description: On a side note, I have thought about a tick-less timer for the OS
for a long time. Basically we could replace the periodic system
@@ -178,7 +168,14 @@ o Task/Scheduler (sched/)
You would think that this should be a clone of the existing
pthread join logic. Howver there is no need for zombies
- in NuttX so, the status if the parent has already exit'ed.
+ in NuttX so no need to keep the status if the parent has
+ already exit'ed. Other simplifications:
+
+ 1. Keep the array/list of return status in the parent
+ tasks TCB.
+ 2. Use a fixed size array of return status (perhaps the
+ the enire array is allocated so that that is con
+ penalty for tasks that have no childre.
At present, exit status is not retained. If waitpid()
is called after the child task has exit'ed it simpley
diff --git a/nuttx/binfmt/binfmt_execmodule.c b/nuttx/binfmt/binfmt_execmodule.c
index 400451c40..df8da5343 100644
--- a/nuttx/binfmt/binfmt_execmodule.c
+++ b/nuttx/binfmt/binfmt_execmodule.c
@@ -1,7 +1,7 @@
/****************************************************************************
* binfmt/binfmt_execmodule.c
*
- * Copyright (C) 2009 Gregory Nutt. All rights reserved.
+ * Copyright (C) 2009, 2013 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <gnutt@nuttx.org>
*
* Redistribution and use in source and binary forms, with or without
@@ -47,6 +47,7 @@
#include <errno.h>
#include <nuttx/arch.h>
+#include <nuttx/kmalloc.h>
#include <nuttx/binfmt/binfmt.h>
#include "os_internal.h"
@@ -167,7 +168,7 @@ int exec_module(FAR const struct binary_s *binp, int priority)
/* Allocate a TCB for the new task. */
- tcb = (FAR _TCB*)zalloc(sizeof(_TCB));
+ tcb = (FAR _TCB*)kzalloc(sizeof(_TCB));
if (!tcb)
{
err = ENOMEM;
@@ -177,7 +178,7 @@ int exec_module(FAR const struct binary_s *binp, int priority)
/* Allocate the stack for the new task */
#ifndef CONFIG_CUSTOM_STACK
- stack = (FAR uint32_t*)malloc(binp->stacksize);
+ stack = (FAR uint32_t*)kmalloc(binp->stacksize);
if (!tcb)
{
err = ENOMEM;
@@ -201,6 +202,9 @@ int exec_module(FAR const struct binary_s *binp, int priority)
goto errout_with_stack;
}
+ /* Note that tcb->flags are not modified. 0=normal task */
+ /* tcb->flags |= TCB_FLAG_TTYPE_TASK; */
+
/* Add the D-Space address as the PIC base address. By convention, this
* must be the first allocated address space.
*/
@@ -257,14 +261,14 @@ errout_with_stack:
#ifndef CONFIG_CUSTOM_STACK
tcb->stack_alloc_ptr = NULL;
sched_releasetcb(tcb);
- free(stack);
+ kfree(stack);
#else
sched_releasetcb(tcb);
#endif
goto errout;
errout_with_tcb:
- free(tcb);
+ kfree(tcb);
errout:
errno = err;
bdbg("returning errno: %d\n", err);
diff --git a/nuttx/fs/nfs/nfs_vfsops.c b/nuttx/fs/nfs/nfs_vfsops.c
index 01e999ac8..2ff4ff9d3 100644
--- a/nuttx/fs/nfs/nfs_vfsops.c
+++ b/nuttx/fs/nfs/nfs_vfsops.c
@@ -680,6 +680,7 @@ static int nfs_close(FAR struct file *filep)
FAR struct nfsnode *np;
FAR struct nfsnode *prev;
FAR struct nfsnode *curr;
+ int ret;
/* Sanity checks */
@@ -703,8 +704,7 @@ static int nfs_close(FAR struct file *filep)
if (np->n_crefs > 1)
{
np->n_crefs--;
- nfs_semgive(nmp);
- return OK;
+ ret = OK;
}
/* There are no more references to the file structure. Now we need to
@@ -714,38 +714,47 @@ static int nfs_close(FAR struct file *filep)
* containted in the mount structure.
*/
- for (prev = NULL, curr = nmp->nm_head; curr; prev = curr, curr = curr->n_next)
- {
- /* Check if this node is ours */
+ else
+ {
+ /* Assume file structure will not be found. This should never happen. */
+
+ ret = -EINVAL;
- if (np == curr)
- {
- /* Yes.. remove it from the list of file structures */
+ for (prev = NULL, curr = nmp->nm_head;
+ curr;
+ prev = curr, curr = curr->n_next)
+ {
+ /* Check if this node is ours */
+
+ if (np == curr)
+ {
+ /* Yes.. remove it from the list of file structures */
- if (prev)
- {
- /* Remove from mid-list */
+ if (prev)
+ {
+ /* Remove from mid-list */
- prev->n_next = np->n_next;
- }
- else
- {
- /* Remove from the head of the list */
+ prev->n_next = np->n_next;
+ }
+ else
+ {
+ /* Remove from the head of the list */
- nmp->nm_head = np->n_next;
- }
+ nmp->nm_head = np->n_next;
+ }
- /* Then deallocate the file structure and return success */
+ /* Then deallocate the file structure and return success */
- kfree(np);
- nfs_semgive(nmp);
- return OK;
- }
- }
+ kfree(np);
+ ret = OK;
+ break;
+ }
+ }
+ }
- fdbg("ERROR: file structure not found in list: %p\n", np);
+ filep->f_priv = NULL;
nfs_semgive(nmp);
- return EINVAL;
+ return ret;
}
/****************************************************************************
diff --git a/nuttx/fs/nxffs/nxffs_open.c b/nuttx/fs/nxffs/nxffs_open.c
index b1e99267f..9fa4ef2e0 100644
--- a/nuttx/fs/nxffs/nxffs_open.c
+++ b/nuttx/fs/nxffs/nxffs_open.c
@@ -1188,9 +1188,10 @@ int nxffs_close(FAR struct file *filep)
ofile->crefs--;
}
- filep->f_priv = NULL;
+ filep->f_priv = NULL;
sem_post(&volume->exclsem);
+
errout:
return ret;
}
diff --git a/nuttx/include/nuttx/fs/binfs.h b/nuttx/include/nuttx/fs/binfs.h
new file mode 100644
index 000000000..6125384a9
--- /dev/null
+++ b/nuttx/include/nuttx/fs/binfs.h
@@ -0,0 +1,80 @@
+/****************************************************************************
+ * include/nuttx/fs/binfs.h
+ *
+ * Copyright (C) 2013 Gregory Nutt. All rights reserved.
+ * Author: Gregory Nutt <gnutt@nuttx.org>
+ *
+ * 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 __INCLUDE_NUTTX_FS_BINFS_H
+#define __INCLUDE_NUTTX_FS_BINFS_H
+
+/****************************************************************************
+ * Included Files
+ ****************************************************************************/
+
+#include <nuttx/config.h>
+
+#include <nuttx/fs/ioctl.h>
+
+/****************************************************************************
+ * Pre-processor Definitions
+ ****************************************************************************/
+/* This is the BINFS ioctl that can be used to recover the filename
+ * associated with the builtin task.
+ */
+
+#define FIOC_FILENAME FIOC_USER /* IN: FAR const char ** pointer
+ * OUT: Pointer to a persistent file name
+ * (Guaranteed to persist while the file
+ * is open).
+ */
+
+/****************************************************************************
+ * Type Definitions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Public Function Prototypes
+ ****************************************************************************/
+
+#ifdef __cplusplus
+#define EXTERN extern "C"
+extern "C" {
+#else
+#define EXTERN extern
+#endif
+
+#undef EXTERN
+#ifdef __cplusplus
+}
+#endif
+
+#endif /* __INCLUDE_NUTTX_FS_BINFS_H */
diff --git a/nuttx/include/nuttx/fs/ioctl.h b/nuttx/include/nuttx/fs/ioctl.h
index 19f29b1fb..8f2fdd7d9 100644
--- a/nuttx/include/nuttx/fs/ioctl.h
+++ b/nuttx/include/nuttx/fs/ioctl.h
@@ -105,6 +105,7 @@
#define FIOC_OPTIMIZE _FIOC(0x0003) /* IN: None
* OUT: None
*/
+#define FIOC_USER _FIOC(0x0004) /* File system-specific */
/* NuttX file system ioctl definitions **************************************/