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/Documentation/NuttXBanner.html2
-rw-r--r--nuttx/drivers/Makefile2
-rw-r--r--nuttx/drivers/loop.c353
-rw-r--r--nuttx/include/nuttx/fs.h6
6 files changed, 360 insertions, 6 deletions
diff --git a/nuttx/ChangeLog b/nuttx/ChangeLog
index 225347254..110119ca0 100644
--- a/nuttx/ChangeLog
+++ b/nuttx/ChangeLog
@@ -546,4 +546,4 @@
only controls the size of the stack for the IDLE thread. Added CONFIG_USERMAIN_STACKSIZE:
This is the size of stack used with the user_start() thread is created. The two stacks
no longer have to be the same.
-
+ * Add a loop device that converts a file into a block device.
diff --git a/nuttx/Documentation/NuttX.html b/nuttx/Documentation/NuttX.html
index 84ba8a6ef..3f8538cd5 100644
--- a/nuttx/Documentation/NuttX.html
+++ b/nuttx/Documentation/NuttX.html
@@ -1189,6 +1189,7 @@ nuttx-0.3.18 2008-xx-xx Gregory Nutt <spudmonkey@racsa.co.cr>
only controls the size of the stack for the IDLE thread. Added CONFIG_USERMAIN_STACKSIZE:
This is the size of stack used with the user_start() thread is created. The two stacks
no longer have to be the same.
+ * Add a loop device that converts a file into a block device.
pascal-0.1.3 2008-xx-xx Gregory Nutt <spudmonkey@racsa.co.cr>
diff --git a/nuttx/Documentation/NuttXBanner.html b/nuttx/Documentation/NuttXBanner.html
index ee9aaeb19..7b83f46ad 100644
--- a/nuttx/Documentation/NuttXBanner.html
+++ b/nuttx/Documentation/NuttXBanner.html
@@ -30,7 +30,7 @@
</table>
</td>
<td width="100" valign="top">
- <a href="http://groups.yahoo.com/group/nuttx/join">
+ <a href="http://groups.yahoo.com/group/nuttx/join" target="_top">
<img src="http://us.i1.yimg.com/us.yimg.com/i/yg/img/i/us/ui/join.gif"
style="border: 0px;"
alt="Click to join nuttx"/>
diff --git a/nuttx/drivers/Makefile b/nuttx/drivers/Makefile
index 33d9c096a..8d03a1918 100644
--- a/nuttx/drivers/Makefile
+++ b/nuttx/drivers/Makefile
@@ -59,7 +59,7 @@ AOBJS = $(ASRCS:.S=$(OBJEXT))
CSRCS =
ifneq ($(CONFIG_NFILE_DESCRIPTORS),0)
CSRCS += dev_null.c dev_zero.c pipe.c fifo.c pipe_common.c \
- serial.c serialirq.c lowconsole.c can.c
+ loop.c serial.c serialirq.c lowconsole.c can.c
ifneq ($(CONFIG_DISABLE_MOUNTPOINT),y)
CSRCS += ramdisk.c
endif
diff --git a/nuttx/drivers/loop.c b/nuttx/drivers/loop.c
new file mode 100644
index 000000000..79c3795be
--- /dev/null
+++ b/nuttx/drivers/loop.c
@@ -0,0 +1,353 @@
+/****************************************************************************
+ * drivers/loop.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.
+ *
+ ****************************************************************************/
+
+/****************************************************************************
+ * Included Files
+ ****************************************************************************/
+
+#include <nuttx/config.h>
+
+#include <sys/types.h>
+#include <sys/stat.h>
+#include <sys/types.h>
+#include <sys/ioctl.h>
+
+#include <stdio.h>
+#include <stdlib.h>
+#include <unistd.h>
+#include <string.h>
+#include <fcntl.h>
+#include <debug.h>
+#include <errno.h>
+
+#include <nuttx/fs.h>
+
+/****************************************************************************
+ * Private Definitions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Types
+ ****************************************************************************/
+
+struct loop_struct_s
+{
+ uint32 nsectors; /* Number of sectors on device */
+ uint16 sectsize; /* The size of one sector */
+#ifdef CONFIG_FS_WRITABLE
+ boolean writeenabled; /* TRUE: can write to device */
+#endif
+ int fd; /* Descriptor of char device/file */
+};
+
+/****************************************************************************
+ * Private Function Prototypes
+ ****************************************************************************/
+
+static int loop_open(FAR struct inode *inode);
+static int loop_close(FAR struct inode *inode);
+static ssize_t loop_read(FAR struct inode *inode, unsigned char *buffer,
+ size_t start_sector, unsigned int nsectors);
+#ifdef CONFIG_FS_WRITABLE
+static ssize_t loop_write(FAR struct inode *inode, const unsigned char *buffer,
+ size_t start_sector, unsigned int nsectors);
+#endif
+static int loop_geometry(FAR struct inode *inode, struct geometry *geometry);
+
+/****************************************************************************
+ * Private Data
+ ****************************************************************************/
+
+static const struct block_operations g_bops =
+{
+ loop_open, /* open */
+ loop_close, /* close */
+ loop_read, /* read */
+#ifdef CONFIG_FS_WRITABLE
+ loop_write, /* write */
+#else
+ NULL, /* write */
+#endif
+ loop_geometry, /* geometry */
+ NULL /* ioctl */
+};
+
+/****************************************************************************
+ * Private Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Name: loop_open
+ *
+ * Description: Open the block device
+ *
+ ****************************************************************************/
+
+static int loop_open(FAR struct inode *inode)
+{
+ return OK;
+}
+
+/****************************************************************************
+ * Name: loop_closel
+ *
+ * Description: close the block device
+ *
+ ****************************************************************************/
+
+static int loop_close(FAR struct inode *inode)
+{
+ return OK;
+}
+
+/****************************************************************************
+ * Name: loop_read
+ *
+ * Description: Read the specified numer of sectors
+ *
+ ****************************************************************************/
+
+static ssize_t loop_read(FAR struct inode *inode, unsigned char *buffer,
+ size_t start_sector, unsigned int nsectors)
+{
+ struct loop_struct_s *dev;
+ size_t nbytesread;
+ off_t offset;
+ int ret;
+
+ DEBUGASSERT(inode && inode->i_private);
+ dev = (struct loop_struct_s *)inode->i_private;
+
+ /* Calculate the offset to read the sectors and seek to the position */
+
+ offset = start_sector * dev->sectsize;
+ ret = lseek(dev->fd, offset, SEEK_SET);
+ if (ret == (off_t)-1)
+ {
+ dbg("Seek failed for offset=%d: %d\n", (int)offset, errno);
+ }
+
+ /* Then read the requested number of sectors from that position */
+
+ do
+ {
+ nbytesread = read(dev->fd, buffer, nsectors * dev->sectsize);
+ if (nbytesread < 0 && errno != EINTR)
+ {
+ dbg("Read failed: %d\n", errno);
+ return -errno;
+ }
+ }
+ while (nbytesread < 0);
+
+ /* Return the number of sectors read */
+
+ return nbytesread / dev->sectsize;
+}
+
+/****************************************************************************
+ * Name: loop_write
+ *
+ * Description: Write the specified number of sectors
+ *
+ ****************************************************************************/
+
+#ifdef CONFIG_FS_WRITABLE
+static ssize_t loop_write(FAR struct inode *inode, const unsigned char *buffer,
+ size_t start_sector, unsigned int nsectors)
+{
+ struct loop_struct_s *dev;
+ size_t nbyteswritten;
+ off_t offset;
+ int ret;
+
+ DEBUGASSERT(inode && inode->i_private);
+ dev = (struct loop_struct_s *)inode->i_private;
+
+ /* Calculate the offset to write the sectors and seek to the position */
+
+ offset = start_sector * dev->sectsize;
+ ret = lseek(dev->fd, offset, SEEK_SET);
+ if (ret == (off_t)-1)
+ {
+ dbg("Seek failed for offset=%d: %d\n", (int)offset, errno);
+ }
+
+ /* Then write the requested number of sectors to that position */
+
+ do
+ {
+ nbyteswritten = write(dev->fd, buffer, nsectors * dev->sectsize);
+ if (nbyteswritten < 0 && errno != EINTR)
+ {
+ dbg("Write failed: %d\n", errno);
+ return -errno;
+ }
+ }
+ while (nbyteswritten < 0);
+
+ /* Return the number of sectors written */
+
+ return nbyteswritten / dev->sectsize;
+}
+#endif
+
+/****************************************************************************
+ * Name: loop_geometry
+ *
+ * Description: Return device geometry
+ *
+ ****************************************************************************/
+
+static int loop_geometry(FAR struct inode *inode, struct geometry *geometry)
+{
+ struct loop_struct_s *dev;
+
+ DEBUGASSERT(inode);
+ if (geometry)
+ {
+ dev = (struct loop_struct_s *)inode->i_private;
+ geometry->geo_available = TRUE;
+ geometry->geo_mediachanged = FALSE;
+#ifdef CONFIG_FS_WRITABLE
+ geometry->geo_writeenabled = dev->writeenabled;
+#else
+ geometry->geo_writeenabled = FALSE;
+#endif
+ geometry->geo_nsectors = dev->nsectors;
+ geometry->geo_sectorsize = dev->sectsize;
+ return OK;
+ }
+ return -EINVAL;
+}
+
+/****************************************************************************
+ * Public Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Name: losetup
+ *
+ * Description:
+ * Setup the loop device so that it exports the file referenced by 'name'
+ * as a block device.
+ *
+ ****************************************************************************/
+
+int losetup(const char *name, int minor, uint16 sectsize)
+{
+ struct loop_struct_s *dev;
+ struct stat sb;
+ char devname[16];
+ int ret;
+
+ /* Sanity check */
+
+#ifdef CONFIG_DEBUG
+ if (minor < 0 || minor > 255 || !name || !sectsize)
+ {
+ return -EINVAL;
+ }
+#endif
+
+ /* Get the size of the file */
+
+ ret = stat(name, &sb);
+ if (ret < 0)
+ {
+ dbg("Failed to stat %s: %d\n", name, errno);
+ return -errno;
+ }
+
+ /* Check if the file system is big enough for one block */
+
+ if (sb.st_size < sectsize)
+ {
+ dbg("File is too small for blocksize\n");
+ return -ERANGE;
+ }
+
+ /* Allocate a loop device structure */
+
+ dev = (struct loop_struct_s *)malloc(sizeof(struct loop_struct_s));
+ if (!dev)
+ {
+ return -ENOMEM;
+ }
+
+ /* Open the file. First try to open the device W/R */
+
+#ifdef CONFIG_FS_WRITABLE
+ dev->writeenabled = FALSE; /* Assume failure */
+
+ dev->fd = open(name, O_RDWR);
+ if (dev->fd >= 0)
+ {
+ dev->writeenabled = TRUE; /* Success */
+ }
+ else
+#endif
+ {
+ /* If that fails, then try to open the device read-only */
+
+ dev->fd = open(name, O_RDWR);
+ if (dev->fd < 0)
+ {
+ dbg("Failed to open %s: %d\n", name, errno);
+ free(dev);
+ return -errno;
+ }
+ }
+
+ /* Initialize the remaining fields */
+
+ dev->nsectors = sb.st_size / sectsize; /* Number of sectors on device */
+ dev->sectsize = sectsize; /* The size of one sector */
+
+ /* Create a loop device name */
+
+ snprintf(devname, 16, "/dev/loop%d", minor);
+
+ /* Inode private data is a reference to the loop device stgructure */
+
+ ret = register_blockdriver(devname, &g_bops, 0, dev);
+ if (ret < 0)
+ {
+ fdbg("register_blockdriver failed: %d\n", -ret);
+ free(dev);
+ }
+
+ return ret;
+}
diff --git a/nuttx/include/nuttx/fs.h b/nuttx/include/nuttx/fs.h
index 2c933804d..6d5dd7861 100644
--- a/nuttx/include/nuttx/fs.h
+++ b/nuttx/include/nuttx/fs.h
@@ -366,12 +366,12 @@ EXTERN int lib_flushall(FAR struct streamlist *list);
/* drivers ******************************************************************/
-/* Call in of these to register the corresponding default
- * default drivers in the drivers/ subdirectory
+/* Call any of these to register the corresponding drivers in the drivers/
+ * subdirectory
*/
EXTERN void devnull_register(void);
-
+EXTERN int losetup(const char *name, int minor, uint16 sectsize);
#undef EXTERN
#if defined(__cplusplus)