summaryrefslogtreecommitdiff
path: root/nuttx
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 /nuttx
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
Diffstat (limited to 'nuttx')
-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
6 files changed, 136 insertions, 44 deletions
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 **************************************/