summaryrefslogtreecommitdiff
diff options
context:
space:
mode:
authorpatacongo <patacongo@42af7a65-404d-4744-a932-0658087f49c3>2008-09-12 14:34:06 +0000
committerpatacongo <patacongo@42af7a65-404d-4744-a932-0658087f49c3>2008-09-12 14:34:06 +0000
commit6aef5e8ed36c97406e930f3cf45d259399fc3d59 (patch)
tree98259bf727ccfc4f7cd0589bebd387caf72c0191
parent627dfd23c0a52dc8a5f8b9c2cdaaa6681154f948 (diff)
downloadpx4-nuttx-6aef5e8ed36c97406e930f3cf45d259399fc3d59.tar.gz
px4-nuttx-6aef5e8ed36c97406e930f3cf45d259399fc3d59.tar.bz2
px4-nuttx-6aef5e8ed36c97406e930f3cf45d259399fc3d59.zip
Add ioctl's to support XIP
git-svn-id: svn://svn.code.sf.net/p/nuttx/code/trunk@913 42af7a65-404d-4744-a932-0658087f49c3
-rw-r--r--nuttx/ChangeLog6
-rw-r--r--nuttx/Documentation/NuttX.html7
-rwxr-xr-xnuttx/drivers/lowconsole.c3
-rw-r--r--nuttx/drivers/ramdisk.c85
-rw-r--r--nuttx/fs/romfs/fs_romfs.c121
-rw-r--r--nuttx/fs/romfs/fs_romfs.h11
-rw-r--r--nuttx/fs/romfs/fs_romfsutil.c218
-rw-r--r--nuttx/include/nuttx/ioctl.h20
8 files changed, 332 insertions, 139 deletions
diff --git a/nuttx/ChangeLog b/nuttx/ChangeLog
index fca27df5f..80b498c72 100644
--- a/nuttx/ChangeLog
+++ b/nuttx/ChangeLog
@@ -466,4 +466,10 @@
* Added support for ROMFS filesystem.
* Added a simple test the ROMFS filesystem (examples/romfs)
* NSH: Use ROMFS to provide an option for a start-up script at /etc/init.d/rcS
+ * Add definition of BIOC_XIPBASE ioctl and implement in RAM disk block driver.
+ This is a low level requirement for eXecute In Place (XIP) support.
+ * Add a FIOC_MMAP to perform memory mapping of a file and implemented the
+ ioctl command in the ROMFS filesystem. This is a requirement for eXecute
+ In Place (XIP) support.
+
diff --git a/nuttx/Documentation/NuttX.html b/nuttx/Documentation/NuttX.html
index 3ee7c80b7..b1e1b1c7d 100644
--- a/nuttx/Documentation/NuttX.html
+++ b/nuttx/Documentation/NuttX.html
@@ -8,7 +8,7 @@
<tr align="center" bgcolor="#e4e4e4">
<td>
<h1><big><font color="#3c34ec"><i>NuttX RTOS</i></font></big></h1>
- <p>Last Updated: September 11, 2008</p>
+ <p>Last Updated: September 12, 2008</p>
</td>
</tr>
</table>
@@ -1100,6 +1100,11 @@ nuttx-0.3.15 2008-xx-xx Gregory Nutt &lt;spudmonkey@racsa.co.cr&gt;
* Added support for ROMFS filesystem.
* Added a simple test the ROMFS filesystem (examples/romfs)
* NSH: Use ROMFS to provide an option for a start-up script at /etc/init.d/rcS
+ * Add definition of BIOC_XIPBASE ioctl and implement in RAM disk block driver.
+ This is a low level requirement for eXecute In Place (XIP) support.
+ * Add a FIOC_MMAP to perform memory mapping of a file and implemented the
+ ioctl command in the ROMFS filesystem. This is a requirement for eXecute
+ In Place (XIP) support.
pascal-0.1.3 2008-xx-xx Gregory Nutt &lt;spudmonkey@racsa.co.cr&gt;
diff --git a/nuttx/drivers/lowconsole.c b/nuttx/drivers/lowconsole.c
index 743f09a0a..d627d4d87 100755
--- a/nuttx/drivers/lowconsole.c
+++ b/nuttx/drivers/lowconsole.c
@@ -82,8 +82,7 @@ struct file_operations g_serialops =
static int lowconsole_ioctl(struct file *filep, int cmd, unsigned long arg)
{
- *get_errno_ptr() = ENOTTY;
- return ERROR;
+ return -ENOTTY;
}
/****************************************************************************
diff --git a/nuttx/drivers/ramdisk.c b/nuttx/drivers/ramdisk.c
index 3f261943e..0bb7c1cb0 100644
--- a/nuttx/drivers/ramdisk.c
+++ b/nuttx/drivers/ramdisk.c
@@ -40,6 +40,7 @@
#include <nuttx/config.h>
#include <sys/types.h>
+#include <sys/ioctl.h>
#include <stdio.h>
#include <stdlib.h>
#include <string.h>
@@ -82,6 +83,7 @@ static ssize_t rd_write(FAR struct inode *inode, const unsigned char *buffer,
size_t start_sector, unsigned int nsectors);
#endif
static int rd_geometry(FAR struct inode *inode, struct geometry *geometry);
+static int rd_ioctl(FAR struct inode *inode, int cmd, unsigned long arg);
/****************************************************************************
* Private Data
@@ -98,7 +100,7 @@ static const struct block_operations g_bops =
NULL, /* write */
#endif
rd_geometry, /* geometry */
- NULL /* ioctl */
+ rd_ioctl /* ioctl */
};
/****************************************************************************
@@ -140,18 +142,16 @@ static ssize_t rd_read(FAR struct inode *inode, unsigned char *buffer,
size_t start_sector, unsigned int nsectors)
{
struct rd_struct_s *dev;
- if (inode)
+
+ DEBUGASSERT(inode && inode->i_private);
+ dev = (struct rd_struct_s *)inode->i_private;
+ if (start_sector < dev->rd_nsectors &&
+ start_sector + nsectors <= dev->rd_nsectors)
{
- dev = (struct rd_struct_s *)inode->i_private;
- if (dev &&
- start_sector < dev->rd_nsectors &&
- start_sector + nsectors <= dev->rd_nsectors)
- {
- memcpy(buffer,
- &dev->rd_buffer[start_sector * dev->rd_sectsize],
- nsectors * dev->rd_sectsize);
- return nsectors;
- }
+ memcpy(buffer,
+ &dev->rd_buffer[start_sector * dev->rd_sectsize],
+ nsectors * dev->rd_sectsize);
+ return nsectors;
}
return -EINVAL;
}
@@ -168,26 +168,22 @@ static ssize_t rd_write(FAR struct inode *inode, const unsigned char *buffer,
size_t start_sector, unsigned int nsectors)
{
struct rd_struct_s *dev;
- if (inode)
+
+ DEBUGASSERT(inode && inode->i_private);
+ dev = (struct rd_struct_s *)inode->i_private;
+ if (!dev->rd_writeenabled)
{
- dev = (struct rd_struct_s *)inode->i_private;
- if (dev)
- {
- if (!dev->rd_writeenabled)
- {
- return -EACCES;
- }
- else if (start_sector < dev->rd_nsectors &&
- start_sector + nsectors <= dev->rd_nsectors)
- {
- memcpy(&dev->rd_buffer[start_sector * dev->rd_sectsize],
- buffer,
- nsectors * dev->rd_sectsize);
- return nsectors;
- }
- }
+ return -EACCES;
}
- return -EINVAL;
+ else if (start_sector < dev->rd_nsectors &&
+ start_sector + nsectors <= dev->rd_nsectors)
+ {
+ memcpy(&dev->rd_buffer[start_sector * dev->rd_sectsize],
+ buffer,
+ nsectors * dev->rd_sectsize);
+ return nsectors;
+ }
+ return -EFBIG;
}
#endif
@@ -201,7 +197,9 @@ static ssize_t rd_write(FAR struct inode *inode, const unsigned char *buffer,
static int rd_geometry(FAR struct inode *inode, struct geometry *geometry)
{
struct rd_struct_s *dev;
- if (inode && geometry)
+
+ DEBUGASSERT(inode);
+ if (geometry)
{
dev = (struct rd_struct_s *)inode->i_private;
geometry->geo_available = TRUE;
@@ -219,6 +217,31 @@ static int rd_geometry(FAR struct inode *inode, struct geometry *geometry)
}
/****************************************************************************
+ * Name: rd_geometry
+ *
+ * Description: Return device geometry
+ *
+ ****************************************************************************/
+
+static int rd_ioctl(FAR struct inode *inode, int cmd, unsigned long arg)
+{
+ struct rd_struct_s *dev ;
+ void **ppv = (void**)arg;
+
+ /* Only one ioctl command is supported */
+
+ DEBUGASSERT(inode && inode->i_private);
+ if (cmd == BIOC_XIPBASE && ppv)
+ {
+ dev = (struct rd_struct_s *)inode->i_private;
+ *ppv = (void*)dev->rd_buffer;
+ return OK;
+ }
+
+ return -ENOTTY;
+}
+
+/****************************************************************************
* Public Functions
****************************************************************************/
diff --git a/nuttx/fs/romfs/fs_romfs.c b/nuttx/fs/romfs/fs_romfs.c
index 8b1ecad09..4eb939484 100644
--- a/nuttx/fs/romfs/fs_romfs.c
+++ b/nuttx/fs/romfs/fs_romfs.c
@@ -55,6 +55,7 @@
#include <debug.h>
#include <nuttx/fs.h>
+#include <nuttx/ioctl.h>
#include "fs_romfs.h"
@@ -71,6 +72,7 @@ static int romfs_open(FAR struct file *filep, const char *relpath,
static int romfs_close(FAR struct file *filep);
static ssize_t romfs_read(FAR struct file *filep, char *buffer, size_t buflen);
static off_t romfs_seek(FAR struct file *filep, off_t offset, int whence);
+static int romfs_ioctl(FAR struct file *filep, int cmd, unsigned long arg);
static int romfs_opendir(struct inode *mountpt, const char *relpath,
struct internal_dir_s *dir);
@@ -104,7 +106,7 @@ const struct mountpt_operations romfs_operations =
romfs_read, /* read */
NULL, /* write */
romfs_seek, /* seek */
- NULL, /* ioctl */
+ romfs_ioctl, /* ioctl */
NULL, /* sync */
romfs_opendir, /* opendir */
@@ -135,7 +137,6 @@ static int romfs_open(FAR struct file *filep, const char *relpath,
int oflags, mode_t mode)
{
struct romfs_dirinfo_s dirinfo;
- struct inode *inode;
struct romfs_mountpt_s *rm;
struct romfs_file_s *rf;
int ret;
@@ -144,12 +145,11 @@ static int romfs_open(FAR struct file *filep, const char *relpath,
DEBUGASSERT(filep->f_priv == NULL && filep->f_inode != NULL);
- /* Get the mountpoint inode reference from the file structure and the
- * mountpoint private data from the inode structure
+ /* mountpoint private data from the inode reference from the file
+ * structure
*/
- inode = filep->f_inode;
- rm = (struct romfs_mountpt_s*)inode->i_private;
+ rm = (struct romfs_mountpt_s*)filep->f_inode->i_private;
DEBUGASSERT(rm != NULL);
@@ -211,21 +211,19 @@ static int romfs_open(FAR struct file *filep, const char *relpath,
goto errout_with_semaphore;
}
- /* Create a file buffer to support partial sector accesses */
-
- rf->rf_buffer = (ubyte*)malloc(rm->rm_hwsectorsize);
- if (!rf->rf_buffer)
- {
- ret = -ENOMEM;
- goto errout_with_struct;
- }
-
/* Initialize the file private data (only need to initialize non-zero elements) */
rf->rf_open = TRUE;
rf->rf_startoffset = romfs_datastart(rm, dirinfo.rd_dir.fr_curroffset);
rf->rf_size = dirinfo.rd_size;
- rf->rf_cachesector = (uint32)-1;
+
+ /* Confiure a buffering to support access to this file */
+
+ ret = romfs_fileconfigure(rm, rf);
+ if (ret < 0)
+ {
+ goto errout_with_semaphore;
+ }
/* Attach the private date to the struct file instance */
@@ -243,12 +241,7 @@ static int romfs_open(FAR struct file *filep, const char *relpath,
romfs_semgive(rm);
return OK;
- /* Error exits -- goto's are nasty things, but they sure can make error
- * handling a lot simpler.
- */
-
-errout_with_struct:
- free(rf);
+ /* Error exits */
errout_with_semaphore:
romfs_semgive(rm);
@@ -261,7 +254,6 @@ errout_with_semaphore:
static int romfs_close(FAR struct file *filep)
{
- struct inode *inode;
struct romfs_mountpt_s *rm;
struct romfs_file_s *rf;
int ret = OK;
@@ -273,8 +265,7 @@ static int romfs_close(FAR struct file *filep)
/* Recover our private data from the struct file instance */
rf = filep->f_priv;
- inode = filep->f_inode;
- rm = inode->i_private;
+ rm = filep->f_inode->i_private;
DEBUGASSERT(rm != NULL);
@@ -289,7 +280,7 @@ static int romfs_close(FAR struct file *filep)
* accesses.
*/
- if (rf->rf_buffer)
+ if (!rm->rm_xipbase && rf->rf_buffer)
{
free(rf->rf_buffer);
}
@@ -307,7 +298,6 @@ static int romfs_close(FAR struct file *filep)
static ssize_t romfs_read(FAR struct file *filep, char *buffer, size_t buflen)
{
- struct inode *inode;
struct romfs_mountpt_s *rm;
struct romfs_file_s *rf;
unsigned int bytesread;
@@ -327,8 +317,7 @@ static ssize_t romfs_read(FAR struct file *filep, char *buffer, size_t buflen)
/* Recover our private data from the struct file instance */
rf = filep->f_priv;
- inode = filep->f_inode;
- rm = inode->i_private;
+ rm = filep->f_inode->i_private;
DEBUGASSERT(rm != NULL);
@@ -445,7 +434,6 @@ errout_with_semaphore:
static off_t romfs_seek(FAR struct file *filep, off_t offset, int whence)
{
- struct inode *inode;
struct romfs_mountpt_s *rm;
struct romfs_file_s *rf;
ssize_t position;
@@ -458,12 +446,12 @@ static off_t romfs_seek(FAR struct file *filep, off_t offset, int whence)
/* Recover our private data from the struct file instance */
rf = filep->f_priv;
- inode = filep->f_inode;
- rm = inode->i_private;
+ rm = filep->f_inode->i_private;
DEBUGASSERT(rm != NULL);
/* Map the offset according to the whence option */
+
switch (whence)
{
case SEEK_SET: /* The offset is set to offset bytes. */
@@ -517,9 +505,46 @@ errout_with_semaphore:
}
/****************************************************************************
+ * Name: romfs_ioctl
+ ****************************************************************************/
+
+static int romfs_ioctl(FAR struct file *filep, int cmd, unsigned long arg)
+{
+ struct romfs_mountpt_s *rm;
+ struct romfs_file_s *rf;
+ void **ppv = (void**)arg;
+
+ /* Sanity checks */
+
+ DEBUGASSERT(filep->f_priv != NULL && filep->f_inode != NULL);
+
+ /* Recover our private data from the struct file instance */
+
+ rf = filep->f_priv;
+ rm = filep->f_inode->i_private;
+
+ DEBUGASSERT(rm != NULL);
+
+ /* Only one ioctl command is supported */
+
+ if (cmd == FIOC_MMAP && rm->rm_xipbase && ppv)
+ {
+ /* Return the address on the media corresponding to the start of
+ * the file.
+ */
+
+ *ppv = (void*)(rm->rm_xipbase + rf->rf_startoffset);
+ return OK;
+ }
+
+ return -ENOTTY;
+}
+
+/****************************************************************************
* Name: romfs_opendir
*
- * Description: Open a directory for read access
+ * Description:
+ * Open a directory for read access
*
****************************************************************************/
@@ -743,41 +768,37 @@ static int romfs_bind(FAR struct inode *blkdriver, const void *data,
sem_init(&rm->rm_sem, 0, 0); /* Initialize the semaphore that controls access */
rm->rm_blkdriver = blkdriver; /* Save the block driver reference */
- rm->rm_cachesector = (uint32)-1; /* No sector in the cache */
- /* Get the hardware configuration */
+ /* Get the hardware configuration and setup buffering appropriately */
- ret = romfs_getgeometry(rm);
+ ret = romfs_hwconfigure(rm);
if (ret < 0)
{
goto errout_with_sem;
}
- /* Allocate the device cache buffer */
-
- rm->rm_buffer = (ubyte*)malloc(rm->rm_hwsectorsize);
- if (!rm->rm_buffer)
- {
- ret = -ENOMEM;
- goto errout_with_sem;
- }
-
- /* Then complete the mount */
+ /* Then complete the mount by getting the ROMFS configuratrion from
+ * the ROMF header
+ */
- ret = romfs_mount(rm);
+ ret = romfs_fsconfigure(rm);
if (ret < 0)
{
goto errout_with_buffer;
}
- /* Mounted */
+ /* Mounted! */
*handle = (void*)rm;
romfs_semgive(rm);
return OK;
errout_with_buffer:
- free(rm->rm_buffer);
+ if (!rm->rm_xipbase)
+ {
+ free(rm->rm_buffer);
+ }
+
errout_with_sem:
sem_destroy(&rm->rm_sem);
free(rm);
@@ -841,7 +862,7 @@ static int romfs_unbind(void *handle, FAR struct inode **blkdriver)
/* Release the mountpoint private data */
- if (rm->rm_buffer)
+ if (!rm->rm_xipbase && rm->rm_buffer)
{
free(rm->rm_buffer);
}
diff --git a/nuttx/fs/romfs/fs_romfs.h b/nuttx/fs/romfs/fs_romfs.h
index 607ca3f97..dd14f72e3 100644
--- a/nuttx/fs/romfs/fs_romfs.h
+++ b/nuttx/fs/romfs/fs_romfs.h
@@ -141,7 +141,8 @@ struct romfs_mountpt_s
uint32 rm_hwnsectors; /* HW: The number of sectors reported by the hardware */
uint32 rm_volsize; /* Size of the ROMFS volume */
uint32 rm_cachesector; /* Current sector in the rm_buffer */
- ubyte *rm_buffer; /* Device sector buffer */
+ ubyte *rm_xipbase; /* Base address of directly accessible media */
+ ubyte *rm_buffer; /* Device sector buffer, allocated if rm_xipbase==0 */
};
/* This structure represents on open file under the mountpoint. An instance
@@ -156,7 +157,7 @@ struct romfs_file_s
uint32 rf_startoffset; /* Offset to the start of the file data */
uint32 rf_size; /* Size of the file in bytes */
uint32 rf_cachesector; /* Current sector in the rf_buffer */
- ubyte *rf_buffer; /* File sector buffer */
+ ubyte *rf_buffer; /* File sector buffer, allocated if rm_xipbase==0 */
};
/* This structure is used internally for describing the result of
@@ -201,8 +202,10 @@ EXTERN int romfs_hwread(struct romfs_mountpt_s *rm, ubyte *buffer,
EXTERN int romfs_devcacheread(struct romfs_mountpt_s *rm, uint32 sector);
EXTERN int romfs_filecacheread(struct romfs_mountpt_s *rm,
struct romfs_file_s *rf, uint32 sector);
-EXTERN int romfs_getgeometry(struct romfs_mountpt_s *rm);
-EXTERN int romfs_mount(struct romfs_mountpt_s *rm);
+EXTERN int romfs_hwconfigure(struct romfs_mountpt_s *rm);
+EXTERN int romfs_fsconfigure(struct romfs_mountpt_s *rm);
+EXTERN int romfs_fileconfigure(struct romfs_mountpt_s *rm,
+ struct romfs_file_s *rf);
EXTERN int romfs_checkmount(struct romfs_mountpt_s *rm);
EXTERN int romfs_finddirentry(struct romfs_mountpt_s *rm,
struct romfs_dirinfo_s *dirinfo,
diff --git a/nuttx/fs/romfs/fs_romfsutil.c b/nuttx/fs/romfs/fs_romfsutil.c
index 7b4f43b4b..7ae274cf0 100644
--- a/nuttx/fs/romfs/fs_romfsutil.c
+++ b/nuttx/fs/romfs/fs_romfsutil.c
@@ -42,12 +42,15 @@
#include <nuttx/config.h>
#include <sys/types.h>
+#include <stdlib.h>
#include <string.h>
#include <assert.h>
#include <errno.h>
#include <assert.h>
#include <debug.h>
+#include <nuttx/ioctl.h>
+
#include "fs_romfs.h"
/****************************************************************************
@@ -298,14 +301,28 @@ void romfs_semgive(struct romfs_mountpt_s *rm)
int romfs_hwread(struct romfs_mountpt_s *rm, ubyte *buffer, uint32 sector,
unsigned int nsectors)
{
- struct inode *inode;;
- ssize_t nsectorsread;
int ret = -ENODEV;
- if (rm && rm->rm_blkdriver)
+ /* Check the access mode */
+
+ if (rm->rm_xipbase)
{
- inode = rm->rm_blkdriver;
- if (inode && inode->u.i_bops && inode->u.i_bops->read)
+ /* In XIP mode, we just copy the requested data */
+
+ memcpy(buffer,
+ rm->rm_xipbase + sector*rm->rm_hwsectorsize,
+ nsectors*rm->rm_hwsectorsize);
+ ret = OK;
+ }
+ else
+ {
+ /* In non-XIP mode, we have to read the data from the device */
+
+ struct inode *inode = rm->rm_blkdriver;
+ ssize_t nsectorsread;
+
+ DEBUGASSERT(inode);
+ if (inode->u.i_bops && inode->u.i_bops->read)
{
nsectorsread =
inode->u.i_bops->read(inode, buffer, sector, nsectors);
@@ -335,24 +352,39 @@ int romfs_devcacheread(struct romfs_mountpt_s *rm, uint32 sector)
{
int ret;
- /* rm->rm_cachesector holds the current sector that is buffered in
- * rm->tm_buffer. If the requested sector is the same as this sector, then
- * we do nothing. Otherwise, we will have to read the new sector.
+ /* rm->rm_cachesector holds the current sector that is buffer in or referenced
+ * by rm->tm_buffer. If the requested sector is the same as this sector,
+ * then we do nothing.
*/
if (rm->rm_cachesector != sector)
- {
- ret = romfs_hwread(rm, rm->rm_buffer, sector, 1);
- if (ret < 0)
- {
- return ret;
- }
+ {
+ /* Check the access mode */
+
+ if (rm->rm_xipbase)
+ {
+ /* In XIP mode, rf_buffer is just an offset pointer into the device
+ * address space.
+ */
+
+ rm->rm_buffer = rm->rm_xipbase + sector*rm->rm_hwsectorsize;
+ }
+ else
+ {
+ /* In non-XIP mode, we will have to read the new sector.*/
+
+ ret = romfs_hwread(rm, rm->rm_buffer, sector, 1);
+ if (ret < 0)
+ {
+ return ret;
+ }
+ }
- /* Update the cached sector number */
+ /* Update the cached sector number */
- rm->rm_cachesector = sector;
+ rm->rm_cachesector = sector;
}
- return OK;
+ return OK;
}
/****************************************************************************
@@ -367,35 +399,53 @@ int romfs_filecacheread(struct romfs_mountpt_s *rm, struct romfs_file_s *rf, uin
{
int ret;
- /* rf->rf_cachesector holds the current sector that is buffered in
- * rf->rf_buffer. If the requested sector is the same as this sector, then
- * we do nothing. Otherwise, we will have to read the new sector.
+ /* rf->rf_cachesector holds the current sector that is buffer in or referenced
+ * by rf->rf_buffer. If the requested sector is the same as this sector,
+ * then we do nothing.
*/
if (rf->rf_cachesector != sector)
- {
- ret = romfs_hwread(rm, rf->rf_buffer, sector, 1);
- if (ret < 0)
- {
- return ret;
- }
+ {
+ /* Check the access mode */
+
+ if (rm->rm_xipbase)
+ {
+ /* In XIP mode, rf_buffer is just an offset pointer into the device
+ * address space.
+ */
- /* Update the cached sector number */
+ rf->rf_buffer = rm->rm_xipbase + sector*rm->rm_hwsectorsize;
+ }
+ else
+ {
+ /* In non-XIP mode, we will have to read the new sector.*/
- rf->rf_cachesector = sector;
+ ret = romfs_hwread(rm, rf->rf_buffer, sector, 1);
+ if (ret < 0)
+ {
+ return ret;
+ }
+ }
+
+ /* Update the cached sector number */
+
+ rf->rf_cachesector = sector;
}
- return OK;
+ return OK;
}
/****************************************************************************
- * Name: romfs_getgeometry
+ * Name: romfs_hwconfigure
*
* Desciption:
- * Get the geometry of the device (part of the mount operation)
+ * This function is called as part of the ROMFS mount operation It
+ * configures the ROMFS filestem for use on this block driver. This includes
+ * the accounting for the geometry of the device, setting up any XIP modes
+ * of operation, and/or allocating any cache buffers.
*
****************************************************************************/
-int romfs_getgeometry(struct romfs_mountpt_s *rm)
+int romfs_hwconfigure(struct romfs_mountpt_s *rm)
{
struct inode *inode = rm->rm_blkdriver;
struct geometry geo;
@@ -403,10 +453,12 @@ int romfs_getgeometry(struct romfs_mountpt_s *rm)
/* Get the underlying device geometry */
+#ifdef CONFIG_DEBUG
if (!inode || !inode->u.i_bops || !inode->u.i_bops->geometry)
{
return -ENODEV;
}
+#endif
ret = inode->u.i_bops->geometry(inode, &geo);
if (ret != OK)
@@ -423,18 +475,50 @@ int romfs_getgeometry(struct romfs_mountpt_s *rm)
rm->rm_hwsectorsize = geo.geo_sectorsize;
rm->rm_hwnsectors = geo.geo_nsectors;
+
+ /* Determine if block driver supports the XIP mode of operation */
+
+ rm->rm_cachesector = (uint32)-1;
+
+ if (inode->u.i_bops->ioctl)
+ {
+ ret = inode->u.i_bops->ioctl(inode, BIOC_XIPBASE,
+ (unsigned long)&rm->rm_xipbase);
+ if (ret == OK && rm->rm_xipbase)
+ {
+ /* Yes.. Then we will directly access the media (vs.
+ * copying into an allocated sector buffer.
+ */
+
+ rm->rm_buffer = rm->rm_xipbase;
+ rm->rm_cachesector = 0;
+ return OK;
+ }
+ }
+
+ /* Allocate the device cache buffer for normal sector accesses */
+
+ rm->rm_buffer = (ubyte*)malloc(rm->rm_hwsectorsize);
+ if (!rm->rm_buffer)
+ {
+ return -ENOMEM;
+ }
+
return OK;
}
/****************************************************************************
- * Name: romfs_mount
+ * Name: romfs_fsconfigure
*
* Desciption:
- * Setup ROMFS on the block driver
+ * This function is called as part of the ROMFS mount operation It
+ * sets up the mount structure to include configuration information contained
+ * in the ROMFS header. This is the place where we actually determine if
+ * the media contains a ROMFS filesystem.
*
****************************************************************************/
-int romfs_mount(struct romfs_mountpt_s *rm)
+int romfs_fsconfigure(struct romfs_mountpt_s *rm)
{
const char *name;
int ret;
@@ -472,6 +556,46 @@ int romfs_mount(struct romfs_mountpt_s *rm)
}
/****************************************************************************
+ * Name: romfs_ffileconfigure
+ *
+ * Desciption:
+ * This function is called as part of the ROMFS file open operation It
+ * sets up the file structure to handle buffer appropriately, depending
+ * upon XIP mode or not.
+ *
+ ****************************************************************************/
+
+int romfs_fileconfigure(struct romfs_mountpt_s *rm, struct romfs_file_s *rf)
+{
+ /* Check if XIP access mode is supported. If so, then we do not need
+ * to allocate anything.
+ */
+
+ if (rm->rm_xipbase)
+ {
+ /* We'll put a valid address in rf_buffer just in case. */
+
+ rf->rf_cachesector = 0;
+ rf->rf_buffer = rm->rm_xipbase + rf->rf_startoffset;
+ }
+ else
+ {
+ /* Nothing in the cache buffer */
+
+ rf->rf_cachesector = (uint32)-1;
+
+ /* Create a file buffer to support partial sector accesses */
+
+ rf->rf_buffer = (ubyte*)malloc(rm->rm_hwsectorsize);
+ if (!rf->rf_buffer)
+ {
+ return -ENOMEM;
+ }
+ }
+ return OK;
+}
+
+/****************************************************************************
* Name: romfs_checkmount
*
* Desciption: Check if the mountpoint is still valid.
@@ -482,29 +606,29 @@ int romfs_mount(struct romfs_mountpt_s *rm)
int romfs_checkmount(struct romfs_mountpt_s *rm)
{
+ struct romfs_file_s *file;
+ struct inode *inode;
+ struct geometry geo;
+ int ret;
+
/* If the fs_mounted flag is FALSE, then we have already handled the loss
* of the mount.
*/
- if (rm && rm->rm_mounted)
+ DEBUGASSERT(rm && rm->rm_blkdriver);
+ if (rm->rm_mounted)
{
- struct romfs_file_s *file;
-
/* We still think the mount is healthy. Check an see if this is
* still the case
*/
- if (rm->rm_blkdriver)
+ inode = rm->rm_blkdriver;
+ if (inode->u.i_bops && inode->u.i_bops->geometry)
{
- struct inode *inode = rm->rm_blkdriver;
- if (inode && inode->u.i_bops && inode->u.i_bops->geometry)
+ ret = inode->u.i_bops->geometry(inode, &geo);
+ if (ret == OK && geo.geo_available && !geo.geo_mediachanged)
{
- struct geometry geo;
- int errcode = inode->u.i_bops->geometry(inode, &geo);
- if (errcode == OK && geo.geo_available && !geo.geo_mediachanged)
- {
- return OK;
- }
+ return OK;
}
}
diff --git a/nuttx/include/nuttx/ioctl.h b/nuttx/include/nuttx/ioctl.h
index a61d1108d..6ebfce997 100644
--- a/nuttx/include/nuttx/ioctl.h
+++ b/nuttx/include/nuttx/ioctl.h
@@ -52,6 +52,7 @@
* defined below:
*/
+#define _FIOCBASE (0x8700) /* File system ioctl commands */
#define _BIOCBASE (0x8800) /* Block driver ioctl commands */
#define _SIOCBASE (0x8900) /* Socket ioctl commandss */
@@ -63,14 +64,25 @@
#define _IOC(type,nr) ((type)|(nr))
+/* NuttX file system ioctl definitions */
+
+#define _FIOCVALID(c) (_IOC_TYPE(c)==_FIOCBASE)
+#define _FIOC(nr) _IOC(_FIOCBASE,nr)
+
+#define FIOC_MMAP _FIOC(0x0001) /* IN: None
+ * OUT: If media is directly acccesible,
+ * return (void*) base address
+ * of file */
+
/* NuttX block driver ioctl definitions */
#define _BIOCVALID(c) (_IOC_TYPE(c)==_BIOCBASE)
-#define _BIOC(nr) _IOC(_SIOCBASE,nr)
+#define _BIOC(nr) _IOC(_BIOCBASE,nr)
-#define _BIOC_XIPBASE _BIOC(0x0001) /* IN: None
- * OUT: If underlying is random acccesible,
- * return (void*) base address */
+#define BIOC_XIPBASE _BIOC(0x0001) /* IN: None
+ * OUT: If media is directly acccesible,
+ * return (void*) base address
+ * of device memory */
/****************************************************************************
* Public Type Definitions