summaryrefslogtreecommitdiff
path: root/nuttx/fs
diff options
context:
space:
mode:
authorpatacongo <patacongo@42af7a65-404d-4744-a932-0658087f49c3>2011-05-08 14:42:42 +0000
committerpatacongo <patacongo@42af7a65-404d-4744-a932-0658087f49c3>2011-05-08 14:42:42 +0000
commita261e0bd080530c6a9f4c766c6650729bb75d0d1 (patch)
tree1607a8e3544808fc3a506a2b946916d91b08f796 /nuttx/fs
parent0a30a23cf0bb5a2abf1f02c5f120641e75067fae (diff)
downloadpx4-nuttx-a261e0bd080530c6a9f4c766c6650729bb75d0d1.tar.gz
px4-nuttx-a261e0bd080530c6a9f4c766c6650729bb75d0d1.tar.bz2
px4-nuttx-a261e0bd080530c6a9f4c766c6650729bb75d0d1.zip
Complets ram mapping logic
git-svn-id: svn://svn.code.sf.net/p/nuttx/code/trunk@3578 42af7a65-404d-4744-a932-0658087f49c3
Diffstat (limited to 'nuttx/fs')
-rwxr-xr-xnuttx/fs/mmap/README.txt78
-rw-r--r--nuttx/fs/mmap/fs_mmap.c30
-rw-r--r--nuttx/fs/mmap/fs_munmap.c71
-rw-r--r--nuttx/fs/mmap/fs_rammap.c68
-rw-r--r--nuttx/fs/mmap/fs_rammap.h42
5 files changed, 225 insertions, 64 deletions
diff --git a/nuttx/fs/mmap/README.txt b/nuttx/fs/mmap/README.txt
new file mode 100755
index 000000000..cf4c51e9e
--- /dev/null
+++ b/nuttx/fs/mmap/README.txt
@@ -0,0 +1,78 @@
+fs/mmap README File
+===================
+
+NuttX operates in a flat open address space and is focused on MCUs that do
+support Memory Management Units (MMUs). Therefore, NuttX generally does not
+require mmap() functionality and the MCUs generally cannot support true
+memory-mapped files.
+
+However, memory mapping of files is the mechanism used by NXFLAT, the NuttX
+tiny binary format, to get files into memory in order to execute them.
+mmap() support is therefore required to support NXFLAT. There are two
+conditions where mmap() can be supported:
+
+1. mmap can be used to support eXecute In Place (XIP) on random access media
+ under the following very restrictive conditions:
+
+ a. The filesystem supports the FIOC_MMAP ioctl command. Any file
+ system that maps files contiguously on the media should support
+ this ioctl. (vs. file system that scatter files over the media
+ in non-contiguous sectors). As of this writing, ROMFS is the
+ only file system that meets this requirement.
+
+ b. The underlying block driver supports the BIOC_XIPBASE ioctl
+ command that maps the underlying media to a randomly accessible
+ address. At present, only the RAM/ROM disk driver does this.
+
+ Some limitations of this approach are as follows:
+
+ a. Since no real mapping occurs, all of the file contents are "mapped"
+ into memory.
+
+ b. All mapped files are read-only.
+
+ c. There are no access privileges.
+
+2. If CONFIG_FS_RAMMAP is defined in the configuration, then mmap() will
+ support simulation of memory mapped files by copying files whole
+ into RAM. These copied files have some of the properties of
+ standard memory mapped files. There are many, many exceptions
+ exceptions, however. Some of these include:
+
+ a. The goal is to have a single region of memory that represents a single
+ file and can be shared by many threads. That is, given a filename a
+ thread should be able to open the file, get a file descriptor, and
+ call mmap() to get a memory region. Different file descriptors opened
+ with the same file path should get the same memory region when mapped.
+
+ The limitation in the current design is that there is insufficient
+ knowledge to know that these different file descriptors correspond to
+ the same file. So, for the time being, a new memory region is created
+ each time that rammap() is called. Not very useful!
+
+ b. The entire mapped portion of the file must be present in memory.
+ Since it is assumed the the MCU does not have an MMU, on-demanding
+ paging in of file blocks cannot be supported. Since the while mapped
+ portion of the file must be present in memory, there are limitations
+ in the size of files that may be memory mapped (especially on MCUs
+ with no significant RAM resources).
+
+ c. All mapped files are read-only. You can write to the in-memory image,
+ but the file contents will not change.
+
+ d. There are no access privileges.
+
+ e. Since there are no processes in NuttX, all mmap() and munmap()
+ operations have immediate, global effects. Under Linux, for example,
+ munmap() would eliminate only the mapping with a process; the mappings
+ to the same file in other processes would not be effected.
+
+ f. Like true mapped file, the region will persist after closing the file
+ descriptor. However, at present, these ram copied file regions are
+ *not* automatically "unmapped" (i.e., freed) when a thread is terminated.
+ This is primarily because it is not possible to know how many users
+ of the mapped region there are and, therefore, when would be the
+ appropriate time to free the region (other than when munmap is called).
+
+ NOTE: Note, if the design limitation of a) were solved, then it would be
+ easy to solve exception d) as well.
diff --git a/nuttx/fs/mmap/fs_mmap.c b/nuttx/fs/mmap/fs_mmap.c
index 3a69e5167..5764b16f1 100644
--- a/nuttx/fs/mmap/fs_mmap.c
+++ b/nuttx/fs/mmap/fs_mmap.c
@@ -47,6 +47,7 @@
#include <debug.h>
#include "fs_internal.h"
+#include "fs_rammap.h"
/****************************************************************************
* Global Functions
@@ -135,16 +136,15 @@ FAR void *mmap(FAR void *start, size_t length, int prot, int flags,
(flags & (MAP_PRIVATE|MAP_FIXED|MAP_ANONYMOUS|MAP_DENYWRITE)) != 0)
{
fdbg("Unsupported options, prot=%x flags=%04x\n", prot, flags);
- ret = ENOSYS;
- goto errout_with_ret;
+ errno = ENOSYS;
+ return MAP_FAILED;
}
- if (length == 0 ||
- (flags & MAP_SHARED) == 0)
+ if (length == 0 || (flags & MAP_SHARED) == 0)
{
fdbg("Invalid options, lengt=%d flags=%04x\n", length, flags);
- ret = EINVAL;
- goto errout_with_ret;
+ errno = EINVAL;
+ return MAP_FAILED;
}
#endif
@@ -161,24 +161,14 @@ FAR void *mmap(FAR void *start, size_t length, int prot, int flags,
if (ret < 0)
{
#ifdef CONFIG_FS_RAMMAP
- ret = rammap(fd, length, offset, &addr);
- if (ret < 0)
+ return rammap(fd, length, offset);
+#else
+ fdbg("ioctl(FIOC_MMAP) failed: %d\n", errno);
+ return MAP_FAILED;
#endif
- {
- fdbg("ioctl(FIOC_MMAP) failed: %d\n", errno);
- goto errout;
- }
}
/* Return the offset address */
return (void*)(((uint8_t*)addr) + offset);
-
-#ifdef CONFIG_DEBUG
-errout_with_ret:
- errno = ret;
-#endif
-
-errout:
- return MAP_FAILED;
}
diff --git a/nuttx/fs/mmap/fs_munmap.c b/nuttx/fs/mmap/fs_munmap.c
index df0f471ac..a4b9dc609 100644
--- a/nuttx/fs/mmap/fs_munmap.c
+++ b/nuttx/fs/mmap/fs_munmap.c
@@ -44,9 +44,13 @@
#include <stdint.h>
#include <errno.h>
+#include <assert.h>
#include <debug.h>
+#include <nuttx/kmalloc.h>
+
#include "fs_internal.h"
+#include "fs_rammap.h"
#ifdef CONFIG_FS_RAMMAP
@@ -60,8 +64,8 @@
* Description:
*
* munmap() system call deletes mappings for the specified address range.
- * The region is also automatically unmapped when the process is terminated.
- * On the other hand, closing the file descriptor does not unmap the region.
+ * All memory starting with 'start' and continuing for a length of 'length'
+ * bytes are removed.
*
* NuttX operates in a flat open address space. Therefore, it generally
* does not require mmap() and, hence, munmap functionality. There are
@@ -96,8 +100,7 @@
* simplified munmap() implementation, the *must* be the start
* address of the memory region (the same address returned by
* mmap()).
- * length The length region to be umapped. Ignored. The entire underlying
- * media is always freed.
+ * length The length region to be umapped.
*
* Returned Value:
* On success, munmap() returns 0, on failure -1, and errno is set
@@ -110,13 +113,14 @@ int munmap(FAR void *start, size_t length)
FAR struct fs_rammap_s *prev;
FAR struct fs_rammap_s *curr;
FAR void *newaddr;
+ unsigned int offset;
int ret;
int err;
/* Find a region containing this start and length in the list of regions */
-#warning "Missing semaphore initialization"
- ret = sem_wait(g_rammaps.exclsem);
+ rammap_initialize();
+ ret = sem_wait(&g_rammaps.exclsem);
if (ret < 0)
{
return ERROR;
@@ -124,7 +128,7 @@ int munmap(FAR void *start, size_t length)
/* Seach the list of regions */
- for (prev = NULL, curr = g_rammaps.head; prev = curr, curr = curr->flink)
+ for (prev = NULL, curr = g_rammaps.head; curr; prev = curr, curr = curr->flink)
{
/* Does this region include any part of the specified range? */
@@ -144,32 +148,63 @@ int munmap(FAR void *start, size_t length)
goto errout_with_semaphore;
}
- /* There is not yet any support for freeing memory at the beginning of the
- * region or for increasing the size of the mapped region.
+ /* Get the offset from the beginning of the region and the actual number
+ * of bytes to "unmap". All mappings must extend to the end of the region.
+ * There is no support for free a block of memory but leaving a block of
+ * memory at the end. This is a consequence of using realloc() to
+ * simulate the unmapping.
*/
- if (start != curr->addr || length > curr->length)
+ offset = start - curr->addr;
+ if (offset + length < curr->length)
{
- fdbg("Unmapping at offset/Extending not supported\n");
+ fdbg("Cannot umap without unmapping to the end\n");
err = ENOSYS;
goto errout_with_semaphore;
}
- /* Otherwise, we can simply realloc the region. Since we are reducing
- * the size of the region, this should not change the start addres.
+ /* Okay.. the region is beging umapped to the end. Make sure the length
+ * indicates that.
+ */
+
+ length = curr->length - offset;
+
+ /* Are we unmapping the entire region (offset == 0)? */
+
+ if (length >= curr->length)
+ {
+ /* Yes.. remove the mapping from the list */
+
+ if (prev)
+ {
+ prev->flink = curr->flink;
+ }
+ else
+ {
+ g_rammaps.head = curr->flink;
+ }
+
+ /* Then free the region */
+
+ kfree(curr);
+ }
+
+ /* No.. We have been asked to "unmap' only a portion of the memory
+ * (offset > 0).
*/
- if (length < curr->length)
+ else
{
- newaddr = realloc(curr->addr, length);
- DEBUGASSERT(newaddr == curr->addr);
+ newaddr = krealloc(curr->addr, sizeof(struct fs_rammap_s) + length);
+ DEBUGASSERT(newaddr == (FAR void*)(curr->addr));
+ curr->length = length;
}
- sem_post(g_rammaps.exclsem);
+ sem_post(&g_rammaps.exclsem);
return OK;
errout_with_semaphore:
- sem_post(g_rammaps.exclsem);
+ sem_post(&g_rammaps.exclsem);
errno = err;
return ERROR;
}
diff --git a/nuttx/fs/mmap/fs_rammap.c b/nuttx/fs/mmap/fs_rammap.c
index 4136882af..0eaf313b5 100644
--- a/nuttx/fs/mmap/fs_rammap.c
+++ b/nuttx/fs/mmap/fs_rammap.c
@@ -40,20 +40,56 @@
#include <nuttx/config.h>
#include <sys/types.h>
+#include <sys/mman.h>
+#include <string.h>
#include <unistd.h>
#include <errno.h>
#include <debug.h>
+#include <nuttx/kmalloc.h>
+
#include "fs_internal.h"
+#include "fs_rammap.h"
#ifdef CONFIG_FS_RAMMAP
/****************************************************************************
+ * Global Data
+ ****************************************************************************/
+
+/* This is the list of all mapped files */
+
+struct fs_allmaps_s g_rammaps;
+
+/****************************************************************************
* Global Functions
****************************************************************************/
/****************************************************************************
+ * Name: rammap_initialize
+ *
+ * Description:
+ * Verified that this capability has been initialized.
+ *
+ * Input Parameters:
+ * None
+ *
+ * Returned Value:
+ * None
+ *
+ ****************************************************************************/
+
+void rammap_initialize(void)
+{
+ if (!g_rammaps.initialized)
+ {
+ sem_init(&g_rammaps.exclsem, 0, 1);
+ g_rammaps.initialized = true;
+ }
+}
+
+/****************************************************************************
* Name: rammmap
*
* Description:
@@ -78,9 +114,9 @@
*
****************************************************************************/
-int rammap(int fd, size_t length, off_t offset, FAR void **addr)
+FAR void *rammap(int fd, size_t length, off_t offset)
{
- FAR struct fs_rammap_s *rammap;
+ FAR struct fs_rammap_s *map;
FAR uint8_t *alloc;
FAR uint8_t *rdbuffer;
ssize_t nread;
@@ -113,11 +149,11 @@ int rammap(int fd, size_t length, off_t offset, FAR void **addr)
/* Initialize the region */
- rammap = (FAR struct fs_rammap_s *)alloc;
- memset(rammap, 0, sizeof(struct fs_rammap_s));
- rammap->addr = alloc + sizeof(struct fs_rammap_s);
- rammap->length = length;
- rammap->offset = offset;
+ map = (FAR struct fs_rammap_s *)alloc;
+ memset(map, 0, sizeof(struct fs_rammap_s));
+ map->addr = alloc + sizeof(struct fs_rammap_s);
+ map->length = length;
+ map->offset = offset;
/* Seek to the specified file offset */
@@ -135,7 +171,7 @@ int rammap(int fd, size_t length, off_t offset, FAR void **addr)
/* Read the file data into the memory region */
- rdbuffer = rammap->addr;
+ rdbuffer = map->addr;
while (length > 0)
{
nread = read(fd, rdbuffer, length);
@@ -175,18 +211,18 @@ int rammap(int fd, size_t length, off_t offset, FAR void **addr)
/* Add the buffer to the list of regions */
-#warning "Missing semaphore initialization"
- ret = sem_wait(g_rammaps.exclsem);
+ rammap_initialize();
+ ret = sem_wait(&g_rammaps.exclsem);
if (ret < 0)
{
goto errout_with_errno;
}
- rammap->flink = g_rammaps.head;
- g_rammaps.head = rammap;
+ map->flink = g_rammaps.head;
+ g_rammaps.head = map;
- sem_post(g_rammaps.exclsem);
- return rammap->addr;
+ sem_post(&g_rammaps.exclsem);
+ return map->addr;
errout_with_region:
kfree(alloc);
@@ -195,8 +231,8 @@ errout:
return MAP_FAILED;
errout_with_errno:
- kfree(alloc)
- returm MAP_FAILED;
+ kfree(alloc);
+ return MAP_FAILED;
}
#endif /* CONFIG_FS_RAMMAP */
diff --git a/nuttx/fs/mmap/fs_rammap.h b/nuttx/fs/mmap/fs_rammap.h
index db19f215c..9076d7343 100644
--- a/nuttx/fs/mmap/fs_rammap.h
+++ b/nuttx/fs/mmap/fs_rammap.h
@@ -64,25 +64,31 @@
* blocks of a file.
*
* This copied file has many of the properties of a standard memory mapped
- * file except for all of the file must be present in memory. This limits
- * the size of files that may be memory mapped (especially on MCUs with
- * no significant RAM resources).
+ * file except:
+ *
+ * - All of the file must be present in memory. This limits the size of
+ * files that may be memory mapped (especially on MCUs with no significant
+ * RAM resources).
+ * - All mapped files are read-only. You can write to the in-memory image,
+ * but the file contents will not change.
+ * - There are not access privileges.
*/
struct fs_rammap_s
{
- struct fs_rammap_s *flink; /* Implements a singly linked list */
- FAR void *addr; /* Start of allocated memory */
- size_t length; /* Length of region */
- off_t offset; /* File offset */
+ struct fs_rammap_s *flink; /* Implements a singly linked list */
+ FAR void *addr; /* Start of allocated memory */
+ size_t length; /* Length of region */
+ off_t offset; /* File offset */
};
/* This structure defines all "mapped" files */
struct fs_allmaps_s
{
- sem_t exclsem; /* Provides exclusive access the list */
- struct fs_rammap_s *maps; /* List of mapped files */
+ bool initialized; /* True: This structure has been initialized */
+ sem_t exclsem; /* Provides exclusive access the list */
+ struct fs_rammap_s *head; /* List of mapped files */
};
/****************************************************************************
@@ -98,6 +104,22 @@ extern struct fs_allmaps_s g_rammaps;
****************************************************************************/
/****************************************************************************
+ * Name: rammap_initialize
+ *
+ * Description:
+ * Verified that this capability has been initialized.
+ *
+ * Input Parameters:
+ * None
+ *
+ * Returned Value:
+ * None
+ *
+ ****************************************************************************/
+
+extern void rammap_initialize(void);
+
+/****************************************************************************
* Name: rammmap
*
* Description:
@@ -122,7 +144,7 @@ extern struct fs_allmaps_s g_rammaps;
*
****************************************************************************/
-extern int rammap(int fd, size_t length, off_t offset, FAR void **addr);
+extern FAR void *rammap(int fd, size_t length, off_t offset);
#endif /* CONFIG_FS_RAMMAP */
#endif /* __FS_MMAP_RAMMAP_H */