summaryrefslogtreecommitdiff
path: root/nuttx
diff options
context:
space:
mode:
Diffstat (limited to 'nuttx')
-rw-r--r--nuttx/ChangeLog2
-rw-r--r--nuttx/Documentation/NuttX.html1
-rw-r--r--nuttx/arch/sim/src/Makefile6
-rw-r--r--nuttx/configs/sim/pashello/Make.defs3
-rw-r--r--nuttx/drivers/dev_zero.c94
-rw-r--r--nuttx/examples/pashello/pashello.c9
-rw-r--r--nuttx/fs/Makefile6
-rw-r--r--nuttx/fs/fs_ioctl.c37
-rw-r--r--nuttx/fs/fs_lseek.c179
9 files changed, 307 insertions, 30 deletions
diff --git a/nuttx/ChangeLog b/nuttx/ChangeLog
index 191b5cf21..4a5a84d52 100644
--- a/nuttx/ChangeLog
+++ b/nuttx/ChangeLog
@@ -315,5 +315,7 @@
* Added a test case to verify the Pascal P-Code interpreter
* Added /dev/zero
* 'errno' is now defined to be *get_errno_ptr() with no name conflicts
+ * Added lseek()
+
diff --git a/nuttx/Documentation/NuttX.html b/nuttx/Documentation/NuttX.html
index 60e1857cd..9fd1c534b 100644
--- a/nuttx/Documentation/NuttX.html
+++ b/nuttx/Documentation/NuttX.html
@@ -965,6 +965,7 @@ Other memory:
* Added a test case to verify the Pascal P-Code interpreter
* Added /dev/zero
* 'errno' is now defined to be *get_errno_ptr() with no name conflicts
+ * Added lseek()
</pre></ul>
<table width ="100%">
diff --git a/nuttx/arch/sim/src/Makefile b/nuttx/arch/sim/src/Makefile
index ea92eb50c..7a5e1c7ff 100644
--- a/nuttx/arch/sim/src/Makefile
+++ b/nuttx/arch/sim/src/Makefile
@@ -60,9 +60,9 @@ SRCS = $(ASRCS) $(CSRCS) $(SPECSRCS)
OBJS = $(AOBJS) $(COBJS) $(SPECOBJS)
LDFLAGS = $(ARCHSCRIPT)
-EXTRA_LIBS = -lc
+STDLIBS = -lc
ifeq ($(CONFIG_FS_FAT),y)
-EXTRA_LIBS += -lz
+STDLIBS += -lz
endif
LINKOBJS = up_head$(OBJEXT)
@@ -89,7 +89,7 @@ libarch$(LIBEXT): $(OBJS)
nuttx$(EXEEXT): $(LINKOBJS)
@echo "LD: nuttx$(EXEEXT)"
@$(CC) $(LDFLAGS) $(LDPATHES) -o $(TOPDIR)/$@ $(LINKOBJS) \
- -Wl,--start-group $(LDLIBS) -Wl,--end-group $(EXTRA_LIBS)
+ -Wl,--start-group $(LDLIBS) -Wl,--end-group $(STDLIBS) $(EXTRA_LIBS)
@$(NM) $(TOPDIR)/$@ | \
grep -v '\(compiled\)\|\(\.o$$\)\|\( [aUw] \)\|\(\.\.ng$$\)\|\(LASH[RL]DI\)' | \
sort > $(TOPDIR)/System.map
diff --git a/nuttx/configs/sim/pashello/Make.defs b/nuttx/configs/sim/pashello/Make.defs
index 28069e16a..9f23c5da8 100644
--- a/nuttx/configs/sim/pashello/Make.defs
+++ b/nuttx/configs/sim/pashello/Make.defs
@@ -1,5 +1,5 @@
############################################################################
-# configs/sim/Make.defs
+# configs/sim/pashello/Make.defs
#
# Copyright (C) 2007, 2008 Gregory Nutt. All rights reserved.
# Author: Gregory Nutt <spudmonkey@racsa.co.cr>
@@ -67,6 +67,7 @@ EXEEXT =
ifeq ("${CONFIG_DEBUG}","y")
LDFLAGS += -g
endif
+EXTRA_LIBS = -lm
define COMPILE
@echo "CC: $1"
diff --git a/nuttx/drivers/dev_zero.c b/nuttx/drivers/dev_zero.c
new file mode 100644
index 000000000..7116758b4
--- /dev/null
+++ b/nuttx/drivers/dev_zero.c
@@ -0,0 +1,94 @@
+/****************************************************************************
+ * drivers/dev_null.c
+ *
+ * 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.
+ *
+ ****************************************************************************/
+
+/****************************************************************************
+ * Compilation Switches
+ ****************************************************************************/
+
+/****************************************************************************
+ * Included Files
+ ****************************************************************************/
+
+#include <nuttx/config.h>
+
+#include <sys/types.h>
+#include <string.h>
+#include <errno.h>
+#include <nuttx/fs.h>
+
+/****************************************************************************
+ * Private Function Prototypes
+ ****************************************************************************/
+
+static ssize_t devzero_read(struct file *, char *, size_t);
+static ssize_t devzero_write(struct file *, const char *, size_t);
+
+/****************************************************************************
+ * Private Data
+ ****************************************************************************/
+
+static struct file_operations devzero_fops =
+{
+ 0, /* open */
+ 0, /* close */
+ devzero_read, /* read */
+ devzero_write, /* write */
+ 0, /* seek */
+ 0 /* ioctl */
+};
+
+/****************************************************************************
+ * Private Functions
+ ****************************************************************************/
+
+static ssize_t devzero_read(struct file *filp, char *buffer, size_t len)
+{
+ return 0; /* Return EOF */
+}
+
+static ssize_t devzero_write(struct file *filp, const char *buffer, size_t len)
+{
+ memset(buffer, 0, len);
+ return len;
+}
+
+/****************************************************************************
+ * Public Functions
+ ****************************************************************************/
+
+void devzero_register(void)
+{
+ (void)register_driver("/dev/zero", &devzero_fops, 0666, NULL);
+}
diff --git a/nuttx/examples/pashello/pashello.c b/nuttx/examples/pashello/pashello.c
index 2aff2d961..4cd7f4921 100644
--- a/nuttx/examples/pashello/pashello.c
+++ b/nuttx/examples/pashello/pashello.c
@@ -100,12 +100,11 @@ static void prun(FAR struct pexec_s *st)
* user_initialize
****************************************************************************/
+#ifndef CONFIG_HAVE_WEAKFUNCTIONS
void user_initialize(void)
{
- /* Register the /dev/hello driver */
-
- hello_register();
}
+#endif
/****************************************************************************
* user_start
@@ -115,6 +114,10 @@ int user_start(int argc, FAR char *argv[])
{
FAR struct pexec_s *st;
+ /* Register the /dev/hello driver */
+
+ hello_register();
+
/* Load the POFF file */
st = pload("/dev/hello", CONFIG_PASHELLO_VARSTACKSIZE, CONFIG_PASHELLO_STRSTACKSIZE);
diff --git a/nuttx/fs/Makefile b/nuttx/fs/Makefile
index 267f89355..98218bf2a 100644
--- a/nuttx/fs/Makefile
+++ b/nuttx/fs/Makefile
@@ -44,9 +44,9 @@ ifneq ($(CONFIG_NSOCKET_DESCRIPTORS),0)
CSRCS += fs_close.c fs_write.c fs_ioctl.c
endif
else
-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_stat.c fs_readdir.c fs_readdirr.c \
- fs_seekdir.c fs_telldir.c fs_rewinddir.c fs_files.c \
+CSRCS += fs_open.c fs_close.c fs_read.c fs_write.c fs_ioctl.c fs_lseek.c \
+ fs_dup.c fs_opendir.c fs_closedir.c fs_stat.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_inodereserve.c fs_statfs.c \
fs_inoderemove.c fs_registerdriver.c fs_unregisterdriver.c \
fs_inodeaddref.c fs_inoderelease.c
diff --git a/nuttx/fs/fs_ioctl.c b/nuttx/fs/fs_ioctl.c
index ba81228c1..0d0889164 100644
--- a/nuttx/fs/fs_ioctl.c
+++ b/nuttx/fs/fs_ioctl.c
@@ -1,7 +1,7 @@
/****************************************************************************
* fs/fs_ioctl.c
*
- * 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.
*
@@ -42,9 +42,9 @@
****************************************************************************/
#include <nuttx/config.h>
+
#include <sys/types.h>
#include <sys/ioctl.h>
-
#include <sched.h>
#include <errno.h>
@@ -67,7 +67,7 @@
* Perform device specific operations.
*
* Parameters:
- * fd Filt/socket descriptor of device
+ * fd File/socket descriptor of device
* req The ioctl command
* arg The argument of the ioctl cmd
*
@@ -94,7 +94,9 @@ int ioctl(int fd, int req, unsigned long arg)
int err;
#if CONFIG_NFILE_DESCRIPTORS > 0
FAR struct filelist *list;
- int ret = OK;
+ FAR struct file *this_file;
+ FAR struct inode *inode;
+ int ret = OK;
/* Did we get a valid file descriptor? */
@@ -126,25 +128,20 @@ int ioctl(int fd, int req, unsigned long arg)
goto errout;
}
- /* Were we give a valid file descriptor? */
+ /* Is a driver registered? Does it support the ioctl method? */
- if ((unsigned int)fd < CONFIG_NFILE_DESCRIPTORS)
- {
- FAR struct file *this_file = &list->fl_files[fd];
- struct inode *inode = this_file->f_inode;
+ this_file = &list->fl_files[fd];
+ inode = this_file->f_inode;
- /* Is a driver registered? Does it support the ioctl method? */
+ if (inode && inode->u.i_ops && inode->u.i_ops->ioctl)
+ {
+ /* Yes, then let it perform the ioctl */
- if (inode && inode->u.i_ops && inode->u.i_ops->ioctl)
+ ret = (int)inode->u.i_ops->ioctl(this_file, req, arg);
+ if (ret < 0)
{
- /* Yes, then let it perform the ioctl */
-
- ret = (int)inode->u.i_ops->ioctl(this_file, req, arg);
- if (ret < 0)
- {
- err = -ret;
- goto errout;
- }
+ err = -ret;
+ goto errout;
}
}
return ret;
diff --git a/nuttx/fs/fs_lseek.c b/nuttx/fs/fs_lseek.c
new file mode 100644
index 000000000..8131acf68
--- /dev/null
+++ b/nuttx/fs/fs_lseek.c
@@ -0,0 +1,179 @@
+/****************************************************************************
+ * fs/fs_lseek.c
+ *
+ * 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.
+ *
+ ****************************************************************************/
+
+/****************************************************************************
+ * Compilation Switches
+ ****************************************************************************/
+
+/****************************************************************************
+ * Included Files
+ ****************************************************************************/
+
+#include <nuttx/config.h>
+
+#include <sys/types.h>
+#include <unistd.h>
+#include <sched.h>
+#include <errno.h>
+
+#include "fs_internal.h"
+
+#if CONFIG_NFILE_DESCRIPTORS > 0
+
+/****************************************************************************
+ * Global Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Name: lseek
+ *
+ * Description:
+ * The lseek() function repositions the offset of the open file associated
+ * with the file descriptor fildes to the argument 'offset' according to the
+ * directive 'whence' as follows:
+ *
+ * SEEK_SET
+ * The offset is set to offset bytes.
+ * SEEK_CUR
+ * The offset is set to its current location plus offset bytes.
+ * SEEK_END
+ * The offset is set to the size of the file plus offset bytes.
+ *
+ * The lseek() function allows the file offset to be set beyond the end of the
+ * file (but this does not change the size of the file). If data is later written
+ * at this point, subsequent reads of the data in the gap (a "hole") return null
+ * bytes ('\0') until data is actually written into the gap.
+ *
+ * Parameters:
+ * fd File descriptor of device
+ * offset Defines the offset to position to
+ * whence Defines how to use offset
+ *
+ * Return:
+ * The resulting offset on success. -1 on failure withi errno set properly:
+ *
+ * EBADF fildes is not an open file descriptor.
+ * EINVAL whence is not one of SEEK_SET, SEEK_CUR, SEEK_END; or the
+ * resulting file offset would be negative, or beyond the end of a
+ * seekable device.
+ * EOVERFLOW The resulting file offset cannot be represented in an off_t.
+ * ESPIPE fildes is associated with a pipe, socket, or FIFO.
+ *
+ ****************************************************************************/
+
+off_t lseek(int fd, off_t offset, int whence)
+{
+ FAR struct filelist *list;
+ FAR struct file *filep;
+ FAR struct inode *inode;
+ int err;
+
+ /* Did we get a valid file descriptor? */
+
+ if ((unsigned int)fd >= CONFIG_NFILE_DESCRIPTORS)
+ {
+ err = EBADF;
+ goto errout;
+ }
+
+ /* Get the thread-specific file list */
+
+ list = sched_getfiles();
+ if (!list)
+ {
+ err = EMFILE;
+ goto errout;
+ }
+
+ /* Is a driver registered? */
+
+ filep = &list->fl_files[fd];
+ inode = filep->f_inode;
+
+ if (inode && inode->u.i_ops)
+ {
+ /* Does it support the seek method */
+
+ if (inode->u.i_ops->seek)
+ {
+ /* Yes, then let it perform the seek */
+
+ err = (int)inode->u.i_ops->seek( filep, offset, whence);
+ if (err < 0)
+ {
+ err = -err;
+ goto errout;
+ }
+ }
+ else
+ {
+ /* No... there are a couple of default actions we can take */
+
+ switch (whence)
+ {
+ case SEEK_CUR:
+ offset += filep->f_pos;
+
+ case SEEK_SET:
+ if (offset >= 0)
+ {
+ filep->f_pos = offset; /* Might be beyond the end-of-file */
+ break;
+ }
+ else
+ {
+ err = EINVAL;
+ goto errout;
+ }
+ break;
+
+ case SEEK_END:
+ err = ENOSYS;
+ goto errout;
+
+ default:
+ err = EINVAL;
+ goto errout;
+ }
+ }
+ }
+ return filep->f_pos;
+
+errout:
+ *get_errno_ptr() = err;
+ return (off_t)ERROR;
+}
+#endif
+