You are viewing a plain text version of this content. The canonical link for it is here.
Posted to commits@mynewt.apache.org by ma...@apache.org on 2015/12/02 21:23:08 UTC

[2/5] incubator-mynewt-larva git commit: Add libs/fs shim layer for accessing files. This allows file access to be independent of underlying filesystem type. Currently supports only one FS present at a time.

Add libs/fs shim layer for accessing files. This allows file access
to be independent of underlying filesystem type.
Currently supports only one FS present at a time.


Project: http://git-wip-us.apache.org/repos/asf/incubator-mynewt-larva/repo
Commit: http://git-wip-us.apache.org/repos/asf/incubator-mynewt-larva/commit/7f8fc747
Tree: http://git-wip-us.apache.org/repos/asf/incubator-mynewt-larva/tree/7f8fc747
Diff: http://git-wip-us.apache.org/repos/asf/incubator-mynewt-larva/diff/7f8fc747

Branch: refs/heads/master
Commit: 7f8fc7471fe4f3f666dabde1660c4958cc3152ee
Parents: 770f4f2
Author: Marko Kiiskila <ma...@runtime.io>
Authored: Wed Dec 2 11:05:49 2015 -0800
Committer: Marko Kiiskila <ma...@runtime.io>
Committed: Wed Dec 2 11:05:49 2015 -0800

----------------------------------------------------------------------
 libs/bootutil/src/bootutil_misc.c       |  33 +-
 libs/bootutil/src/loader.c              |   6 +-
 libs/bootutil/src/test/boot_test.c      |  25 +-
 libs/elua/elua_base/egg.yml             |   2 +-
 libs/elua/elua_base/src/lauxlib.c       |  32 +-
 libs/fs/egg.yml                         |   5 +
 libs/fs/include/fs/fs.h                 |  75 ++++
 libs/fs/include/fs/fs_if.h              |  55 +++
 libs/fs/include/fs/fsutil.h             |  26 ++
 libs/fs/src/fs_cli.c                    |  85 ++++
 libs/fs/src/fs_dirent.c                 |  49 +++
 libs/fs/src/fs_file.c                   |  67 +++
 libs/fs/src/fs_mkdir.c                  |  31 ++
 libs/fs/src/fs_mount.c                  |  35 ++
 libs/fs/src/fs_priv.h                   |  26 ++
 libs/fs/src/fsutil.c                    |  64 +++
 libs/nffs/egg.yml                       |   1 +
 libs/nffs/include/nffs/nffs.h           |  29 +-
 libs/nffs/include/nffs/nffsutil.h       |  26 --
 libs/nffs/src/nffs.c                    | 162 +++++---
 libs/nffs/src/nffs_area.c               |   4 +-
 libs/nffs/src/nffs_block.c              |   6 +-
 libs/nffs/src/nffs_cache.c              |   2 +-
 libs/nffs/src/nffs_crc.c                |   5 +-
 libs/nffs/src/nffs_dir.c                |   6 +-
 libs/nffs/src/nffs_file.c               |  40 +-
 libs/nffs/src/nffs_flash.c              |  18 +-
 libs/nffs/src/nffs_format.c             |   2 +-
 libs/nffs/src/nffs_gc.c                 |  10 +-
 libs/nffs/src/nffs_hash.c               |   2 +-
 libs/nffs/src/nffs_inode.c              |   4 +-
 libs/nffs/src/nffs_misc.c               |  36 +-
 libs/nffs/src/nffs_path.c               |  28 +-
 libs/nffs/src/nffs_priv.h               |   1 +
 libs/nffs/src/nffs_restore.c            |  42 +-
 libs/nffs/src/nffs_write.c              |   8 +-
 libs/nffs/src/nffsutil.c                |  65 ---
 libs/nffs/src/test/arch/sim/nffs_test.c | 586 ++++++++++++++-------------
 libs/shell/include/shell/shell.h        |   2 +
 libs/testreport/src/testreport.c        |   3 +-
 project/ffs2native/src/main.c           |   2 +-
 project/luatest/src/main.c              |  13 +-
 42 files changed, 1100 insertions(+), 619 deletions(-)
----------------------------------------------------------------------


http://git-wip-us.apache.org/repos/asf/incubator-mynewt-larva/blob/7f8fc747/libs/bootutil/src/bootutil_misc.c
----------------------------------------------------------------------
diff --git a/libs/bootutil/src/bootutil_misc.c b/libs/bootutil/src/bootutil_misc.c
index 2b28385..bd69752 100644
--- a/libs/bootutil/src/bootutil_misc.c
+++ b/libs/bootutil/src/bootutil_misc.c
@@ -17,8 +17,8 @@
 #include <string.h>
 #include <inttypes.h>
 #include "hal/hal_flash.h"
-#include "nffs/nffs.h"
-#include "nffs/nffsutil.h"
+#include "fs/fs.h"
+#include "fs/fsutil.h"
 #include "bootutil/crc32.h"
 #include "bootutil/image.h"
 #include "bootutil_priv.h"
@@ -29,7 +29,7 @@ boot_vect_read_one(struct image_version *ver, const char *path)
     uint32_t bytes_read;
     int rc;
 
-    rc = nffsutil_read_file(path, 0, sizeof *ver, ver, &bytes_read);
+    rc = fsutil_read_file(path, 0, sizeof *ver, ver, &bytes_read);
     if (rc != 0 || bytes_read != sizeof *ver) {
         return BOOT_EBADVECT;
     }
@@ -80,7 +80,7 @@ boot_vect_delete_test(void)
 {
     int rc;
 
-    rc = nffs_unlink(BOOT_PATH_TEST);
+    rc = fs_unlink(BOOT_PATH_TEST);
     return rc;
 }
 
@@ -94,7 +94,7 @@ boot_vect_delete_main(void)
 {
     int rc;
 
-    rc = nffs_unlink(BOOT_PATH_MAIN);
+    rc = fs_unlink(BOOT_PATH_MAIN);
     return rc;
 }
 
@@ -168,24 +168,24 @@ boot_read_status(struct boot_status *out_status,
                  struct boot_status_entry *out_entries,
                  int num_areas)
 {
-    struct nffs_file *file;
+    struct fs_file *file;
     uint32_t bytes_read;
     int rc;
     int i;
 
-    rc = nffs_open(BOOT_PATH_STATUS, NFFS_ACCESS_READ, &file);
+    rc = fs_open(BOOT_PATH_STATUS, FS_ACCESS_READ, &file);
     if (rc != 0) {
         rc = BOOT_EBADSTATUS;
         goto done;
     }
 
-    rc = nffs_read(file, sizeof *out_status, out_status, &bytes_read);
+    rc = fs_read(file, sizeof *out_status, out_status, &bytes_read);
     if (rc != 0 || bytes_read != sizeof *out_status) {
         rc = BOOT_EBADSTATUS;
         goto done;
     }
 
-    rc = nffs_read(file, num_areas * sizeof *out_entries, out_entries,
+    rc = fs_read(file, num_areas * sizeof *out_entries, out_entries,
                    &bytes_read);
     if (rc != 0 || bytes_read != num_areas * sizeof *out_entries) {
         rc = BOOT_EBADSTATUS;
@@ -217,7 +217,7 @@ boot_read_status(struct boot_status *out_status,
     rc = 0;
 
 done:
-    nffs_close(file);
+    fs_close(file);
     return rc;
 }
 
@@ -238,23 +238,22 @@ boot_write_status(const struct boot_status *status,
                   const struct boot_status_entry *entries,
                   int num_areas)
 {
-    struct nffs_file *file;
+    struct fs_file *file;
     int rc;
 
-    rc = nffs_open(BOOT_PATH_STATUS, NFFS_ACCESS_WRITE | NFFS_ACCESS_TRUNCATE,
-                   &file);
+    rc = fs_open(BOOT_PATH_STATUS, FS_ACCESS_WRITE | FS_ACCESS_TRUNCATE, &file);
     if (rc != 0) {
         rc = BOOT_EFILE;
         goto done;
     }
 
-    rc = nffs_write(file, status, sizeof *status);
+    rc = fs_write(file, status, sizeof *status);
     if (rc != 0) {
         rc = BOOT_EFILE;
         goto done;
     }
 
-    rc = nffs_write(file, entries, num_areas * sizeof *entries);
+    rc = fs_write(file, entries, num_areas * sizeof *entries);
     if (rc != 0) {
         rc = BOOT_EFILE;
         goto done;
@@ -263,7 +262,7 @@ boot_write_status(const struct boot_status *status,
     rc = 0;
 
 done:
-    nffs_close(file);
+    fs_close(file);
     return rc;
 }
 
@@ -276,5 +275,5 @@ done:
 void
 boot_clear_status(void)
 {
-    nffs_unlink(BOOT_PATH_STATUS);
+    fs_unlink(BOOT_PATH_STATUS);
 }

http://git-wip-us.apache.org/repos/asf/incubator-mynewt-larva/blob/7f8fc747/libs/bootutil/src/loader.c
----------------------------------------------------------------------
diff --git a/libs/bootutil/src/loader.c b/libs/bootutil/src/loader.c
index 05bd474..ecd5899 100644
--- a/libs/bootutil/src/loader.c
+++ b/libs/bootutil/src/loader.c
@@ -21,7 +21,7 @@
 #include "hal/hal_flash.h"
 #include "os/os_malloc.h"
 #include "nffs/nffs.h"
-#include "nffs/nffsutil.h"
+#include "fs/fs.h"
 #include "bootutil/loader.h"
 #include "bootutil/image.h"
 #include "bootutil_priv.h"
@@ -610,7 +610,7 @@ boot_init_flash(void)
     nffs_detect(boot_req->br_area_descs);
 
     /* Create the boot directory if it doesn't already exist. */
-    nffs_mkdir("/boot");
+    fs_mkdir("/boot");
 
     return 0;
 }
@@ -731,7 +731,7 @@ boot_go(const struct boot_req *req, struct boot_rsp *rsp)
     rsp->br_image_addr = image_addrs[0].bil_address;
 
     /* After successful boot, there should not be a status file. */
-    nffs_unlink(BOOT_PATH_STATUS);
+    fs_unlink(BOOT_PATH_STATUS);
 
     /* If an image is being tested, it should only be booted into once. */
     boot_vect_delete_test();

http://git-wip-us.apache.org/repos/asf/incubator-mynewt-larva/blob/7f8fc747/libs/bootutil/src/test/boot_test.c
----------------------------------------------------------------------
diff --git a/libs/bootutil/src/test/boot_test.c b/libs/bootutil/src/test/boot_test.c
index 9ab5df2..801d327 100644
--- a/libs/bootutil/src/test/boot_test.c
+++ b/libs/bootutil/src/test/boot_test.c
@@ -22,8 +22,9 @@
 #include <inttypes.h>
 #include "testutil/testutil.h"
 #include "hal/hal_flash.h"
+#include "fs/fs.h"
+#include "fs/fsutil.h"
 #include "nffs/nffs.h"
-#include "nffs/nffsutil.h"
 #include "bootutil/image.h"
 #include "bootutil/loader.h"
 #include "../src/bootutil_priv.h"
@@ -115,7 +116,7 @@ boot_test_util_init_flash(void)
     rc = nffs_format(boot_test_format_descs);
     TEST_ASSERT(rc == 0);
 
-    rc = nffs_mkdir("/boot");
+    rc = fs_mkdir("/boot");
     TEST_ASSERT(rc == 0);
 }
 
@@ -316,11 +317,11 @@ boot_test_util_verify_area(const struct nffs_area_desc *area_desc,
 static void
 boot_test_util_verify_status_clear(void)
 {
-    struct nffs_file *file;
+    struct fs_file *file;
     int rc;
 
-    rc = nffs_open(BOOT_PATH_STATUS, NFFS_ACCESS_READ, &file);
-    TEST_ASSERT(rc == NFFS_ENOENT);
+    rc = fs_open(BOOT_PATH_STATUS, FS_ACCESS_READ, &file);
+    TEST_ASSERT(rc == FS_ENOENT);
 }
 
 static void
@@ -501,7 +502,7 @@ TEST_CASE(boot_test_vm_ns_10)
     boot_test_util_init_flash();
     boot_test_util_write_image(&hdr, 0);
 
-    rc = nffsutil_write_file(BOOT_PATH_MAIN, &hdr.ih_ver, sizeof hdr.ih_ver);
+    rc = fsutil_write_file(BOOT_PATH_MAIN, &hdr.ih_ver, sizeof hdr.ih_ver);
     TEST_ASSERT(rc == 0);
 
     rc = boot_go(&req, &rsp);
@@ -541,7 +542,7 @@ TEST_CASE(boot_test_vm_ns_01)
     boot_test_util_init_flash();
     boot_test_util_write_image(&hdr, 1);
 
-    rc = nffsutil_write_file(BOOT_PATH_MAIN, &hdr.ih_ver, sizeof hdr.ih_ver);
+    rc = fsutil_write_file(BOOT_PATH_MAIN, &hdr.ih_ver, sizeof hdr.ih_ver);
     TEST_ASSERT(rc == 0);
 
     rc = boot_go(&req, &rsp);
@@ -590,7 +591,7 @@ TEST_CASE(boot_test_vm_ns_11_a)
     boot_test_util_write_image(&hdr0, 0);
     boot_test_util_write_image(&hdr1, 1);
 
-    rc = nffsutil_write_file(BOOT_PATH_MAIN, &hdr0.ih_ver, sizeof hdr0.ih_ver);
+    rc = fsutil_write_file(BOOT_PATH_MAIN, &hdr0.ih_ver, sizeof hdr0.ih_ver);
     TEST_ASSERT(rc == 0);
 
     rc = boot_go(&req, &rsp);
@@ -639,7 +640,7 @@ TEST_CASE(boot_test_vm_ns_11_b)
     boot_test_util_write_image(&hdr0, 0);
     boot_test_util_write_image(&hdr1, 1);
 
-    rc = nffsutil_write_file(BOOT_PATH_MAIN, &hdr1.ih_ver, sizeof hdr1.ih_ver);
+    rc = fsutil_write_file(BOOT_PATH_MAIN, &hdr1.ih_ver, sizeof hdr1.ih_ver);
     TEST_ASSERT(rc == 0);
 
     rc = boot_go(&req, &rsp);
@@ -688,7 +689,7 @@ TEST_CASE(boot_test_vm_ns_11_2areas)
     boot_test_util_write_image(&hdr0, 0);
     boot_test_util_write_image(&hdr1, 1);
 
-    rc = nffsutil_write_file(BOOT_PATH_MAIN, &hdr1.ih_ver, sizeof hdr1.ih_ver);
+    rc = fsutil_write_file(BOOT_PATH_MAIN, &hdr1.ih_ver, sizeof hdr1.ih_ver);
     TEST_ASSERT(rc == 0);
 
     rc = boot_go(&req, &rsp);
@@ -917,10 +918,10 @@ TEST_CASE(boot_test_vb_ns_11)
     boot_test_util_write_image(&hdr0, 0);
     boot_test_util_write_image(&hdr1, 1);
 
-    rc = nffsutil_write_file(BOOT_PATH_MAIN, &hdr0.ih_ver, sizeof hdr0.ih_ver);
+    rc = fsutil_write_file(BOOT_PATH_MAIN, &hdr0.ih_ver, sizeof hdr0.ih_ver);
     TEST_ASSERT(rc == 0);
 
-    rc = nffsutil_write_file(BOOT_PATH_TEST, &hdr1.ih_ver, sizeof hdr1.ih_ver);
+    rc = fsutil_write_file(BOOT_PATH_TEST, &hdr1.ih_ver, sizeof hdr1.ih_ver);
     TEST_ASSERT(rc == 0);
 
     /* First boot should use the test image. */

http://git-wip-us.apache.org/repos/asf/incubator-mynewt-larva/blob/7f8fc747/libs/elua/elua_base/egg.yml
----------------------------------------------------------------------
diff --git a/libs/elua/elua_base/egg.yml b/libs/elua/elua_base/egg.yml
index 3a202b1..4af3263 100644
--- a/libs/elua/elua_base/egg.yml
+++ b/libs/elua/elua_base/egg.yml
@@ -4,5 +4,5 @@ egg.cflags: -DLUA_OPTIMIZE_MEMORY=2 -DLUA_CROSS_COMPILER -DLUA_USE_MKSTEMP -DLUA
 egg.req_caps:
     - console
 egg.deps:
-    - libs/nffs
+    - libs/fs
 

http://git-wip-us.apache.org/repos/asf/incubator-mynewt-larva/blob/7f8fc747/libs/elua/elua_base/src/lauxlib.c
----------------------------------------------------------------------
diff --git a/libs/elua/elua_base/src/lauxlib.c b/libs/elua/elua_base/src/lauxlib.c
index 32ec127..2527e9f 100644
--- a/libs/elua/elua_base/src/lauxlib.c
+++ b/libs/elua/elua_base/src/lauxlib.c
@@ -37,7 +37,7 @@
 #include "devman.h"
 #endif
 #ifdef MYNEWT
-#include <nffs/nffs.h>
+#include <fs/fs.h>
 #endif
 
 #define FREELIST_REF	0	/* free list of references */
@@ -587,7 +587,7 @@ typedef struct LoadF {
 #ifndef MYNEWT
   FILE *f;
 #else
-  struct nffs_file *f;
+  struct fs_file *f;
   int readstatus;
 #endif
   char buff[LUAL_BUFFERSIZE];
@@ -614,7 +614,7 @@ static const char *getF (lua_State *L, void *ud, size_t *size) {
     int rc;
     uint32_t out_len;
 
-    rc = nffs_read(lf->f, sizeof(lf->buff), lf->buff, &out_len);
+    rc = fs_read(lf->f, sizeof(lf->buff), lf->buff, &out_len);
     if (rc || out_len == 0) {
       if (rc) {
         lf->readstatus = rc;
@@ -702,13 +702,13 @@ LUALIB_API int luaL_loadfile (lua_State *L, const char *filename) {
 #else
 
 int
-luaL_nffs_getc(struct nffs_file *nf)
+luaL_fs_getc(struct fs_file *nf)
 {
   int rc;
   uint32_t out_len;
   char ch;
 
-  rc = nffs_read(nf, 1, &ch, &out_len);
+  rc = fs_read(nf, 1, &ch, &out_len);
   if (rc || out_len == 0) {
     return -1;
   }
@@ -718,7 +718,7 @@ luaL_nffs_getc(struct nffs_file *nf)
 LUALIB_API int luaL_loadfile (lua_State *L, const char *filename) {
   LoadF lf;
   int status;
-  struct nffs_file *nf;
+  struct fs_file *nf;
   int rc;
   int c;
   int fnameindex = lua_gettop(L) + 1;  /* index of filename on the stack */
@@ -730,30 +730,30 @@ LUALIB_API int luaL_loadfile (lua_State *L, const char *filename) {
   else {
     lua_pushfstring(L, "@%s", filename);
 
-    rc = nffs_open(filename, NFFS_ACCESS_READ, &nf);
+    rc = fs_open(filename, FS_ACCESS_READ, &nf);
     if (rc || nf == NULL) {
-        return errfile(L, "nffs_open", fnameindex);
+        return errfile(L, "fs_open", fnameindex);
     }
     lf.f = nf;
   }
-  c = luaL_nffs_getc(lf.f);
+  c = luaL_fs_getc(lf.f);
   if (c == '#') {  /* Unix exec. file? */
     lf.extraline = 1;
-    while ((c = luaL_nffs_getc(lf.f)) != -1 && c != '\n') ;/* skip first line */
-    if (c == '\n') c = luaL_nffs_getc(lf.f);
+    while ((c = luaL_fs_getc(lf.f)) != -1 && c != '\n') ;/* skip first line */
+    if (c == '\n') c = luaL_fs_getc(lf.f);
   }
   if (c == LUA_SIGNATURE[0] && filename) {  /* binary file? */
-    rc = nffs_seek(lf.f, 0);  /* move back to beginning */
-    if (rc) return errfile(L, "nffs_seek", fnameindex);
+    rc = fs_seek(lf.f, 0);  /* move back to beginning */
+    if (rc) return errfile(L, "fs_seek", fnameindex);
     /* skip eventual `#!...' */
-   while ((c = luaL_nffs_getc(lf.f)) != -1 && c != LUA_SIGNATURE[0]) ;
+   while ((c = luaL_fs_getc(lf.f)) != -1 && c != LUA_SIGNATURE[0]) ;
     lf.extraline = 0;
   }
-  nffs_seek(lf.f, nffs_getpos(lf.f) - 1);
+  fs_seek(lf.f, fs_getpos(lf.f) - 1);
   lf.readstatus = 0;
   lf.srcp = NULL;
   status = lua_load(L, getF, &lf, lua_tostring(L, -1));
-  if (filename) nffs_close(lf.f);  /* close file (even in case of errors) */
+  if (filename) fs_close(lf.f);  /* close file (even in case of errors) */
   if (lf.readstatus) {
     lua_settop(L, fnameindex);  /* ignore results from `lua_load' */
     return errfile(L, "read", fnameindex);

http://git-wip-us.apache.org/repos/asf/incubator-mynewt-larva/blob/7f8fc747/libs/fs/egg.yml
----------------------------------------------------------------------
diff --git a/libs/fs/egg.yml b/libs/fs/egg.yml
new file mode 100644
index 0000000..ea8f21f
--- /dev/null
+++ b/libs/fs/egg.yml
@@ -0,0 +1,5 @@
+egg.name: libs/fs
+egg.deps.SHELL:
+    - libs/shell
+    - libs/console/full
+egg.cflags.SHELL: -DSHELL_PRESENT

http://git-wip-us.apache.org/repos/asf/incubator-mynewt-larva/blob/7f8fc747/libs/fs/include/fs/fs.h
----------------------------------------------------------------------
diff --git a/libs/fs/include/fs/fs.h b/libs/fs/include/fs/fs.h
new file mode 100644
index 0000000..872b863
--- /dev/null
+++ b/libs/fs/include/fs/fs.h
@@ -0,0 +1,75 @@
+/**
+ * Copyright (c) 2015 Runtime Inc.
+ *
+ * Licensed under the Apache License, Version 2.0 (the "License");
+ * you may not use this file except in compliance with the License.
+ * You may obtain a copy of the License at
+ *
+ *   http://www.apache.org/licenses/LICENSE-2.0
+ *
+ * Unless required by applicable law or agreed to in writing, software
+ * distributed under the License is distributed on an "AS IS" BASIS,
+ * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
+ * See the License for the specific language governing permissions and
+ * limitations under the License.
+ */
+
+#ifndef __FS_H__
+#define __FS_H__
+
+#include <stddef.h>
+#include <inttypes.h>
+
+/*
+ * Common interface to access files.
+ */
+struct fs_file;
+struct fs_dir;
+struct fs_dirent;
+
+int fs_open(const char *filename, uint8_t access_flags, struct fs_file **);
+int fs_close(struct fs_file *);
+int fs_read(struct fs_file *, uint32_t len, void *out_data, uint32_t *out_len);
+int fs_write(struct fs_file *, const void *data, int len);
+int fs_seek(struct fs_file *, uint32_t offset);
+uint32_t fs_getpos(const struct fs_file *);
+int fs_filelen(const struct fs_file *, uint32_t *out_len);
+
+int fs_unlink(const char *filename);
+int fs_rename(const char *from, const char *to);
+int fs_mkdir(const char *path);
+
+int fs_opendir(const char *path, struct fs_dir **);
+int fs_readdir(struct fs_dir *, struct fs_dirent **);
+int fs_closedir(struct fs_dir *);
+int fs_dirent_name(const struct fs_dirent *, size_t max_len,
+  char *out_name, uint8_t *out_name_len);
+int fs_dirent_is_dir(const struct fs_dirent *);
+
+/*
+ * File access flags.
+ */
+#define FS_ACCESS_READ          0x01
+#define FS_ACCESS_WRITE         0x02
+#define FS_ACCESS_APPEND        0x04
+#define FS_ACCESS_TRUNCATE      0x08
+
+/*
+ * File access return codes.
+ */
+#define FS_EOK                  0       /* OK */
+#define FS_ECORRUPT             1       /* Filesystem corrupt */
+#define FS_HW_ERROR             2       /* Error access storage medium */
+#define FS_ERANGE               3
+#define FS_EINVAL               4
+#define FS_ENOMEM               5       /* out of memory */
+#define FS_ENOENT               6       /* no such file */
+#define FS_EEMPTY               7
+#define FS_EFULL                8
+#define FS_EUNEXP               9
+#define FS_EOS                  10
+#define FS_EEXIST               11
+#define FS_EACCESS              12
+#define FS_EUNINIT              13
+
+#endif

http://git-wip-us.apache.org/repos/asf/incubator-mynewt-larva/blob/7f8fc747/libs/fs/include/fs/fs_if.h
----------------------------------------------------------------------
diff --git a/libs/fs/include/fs/fs_if.h b/libs/fs/include/fs/fs_if.h
new file mode 100644
index 0000000..9236cc6
--- /dev/null
+++ b/libs/fs/include/fs/fs_if.h
@@ -0,0 +1,55 @@
+/**
+ * Copyright (c) 2015 Runtime Inc.
+ *
+ * Licensed under the Apache License, Version 2.0 (the "License");
+ * you may not use this file except in compliance with the License.
+ * You may obtain a copy of the License at
+ *
+ *   http://www.apache.org/licenses/LICENSE-2.0
+ *
+ * Unless required by applicable law or agreed to in writing, software
+ * distributed under the License is distributed on an "AS IS" BASIS,
+ * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
+ * See the License for the specific language governing permissions and
+ * limitations under the License.
+ */
+
+#ifndef __FS_IF_H__
+#define __FS_IF_H__
+
+/*
+ * Common interface filesystem(s) provide.
+ */
+struct fs_ops {
+    int (*f_open)(const char *filename, uint8_t access_flags,
+              struct fs_file **out_file);
+    int (*f_close)(struct fs_file *file);
+    int (*f_read)(struct fs_file *file, uint32_t len, void *out_data,
+      uint32_t *out_len);
+    int (*f_write)(struct fs_file *file, const void *data, int len);
+
+    int (*f_seek)(struct fs_file *file, uint32_t offset);
+    uint32_t (*f_getpos)(const struct fs_file *file);
+    int (*f_filelen)(const struct fs_file *file, uint32_t *out_len);
+
+    int (*f_unlink)(const char *filename);
+    int (*f_rename)(const char *from, const char *to);
+    int (*f_mkdir)(const char *path);
+
+    int (*f_opendir)(const char *path, struct fs_dir **out_dir);
+    int (*f_readdir)(struct fs_dir *dir, struct fs_dirent **out_dirent);
+    int (*f_closedir)(struct fs_dir *dir);
+
+    int (*f_dirent_name)(const struct fs_dirent *dirent, size_t max_len,
+      char *out_name, uint8_t *out_name_len);
+    int (*f_dirent_is_dir)(const struct fs_dirent *dirent);
+
+    const char *f_name;
+};
+
+/*
+ * Currently allow only one type of FS, starts at root.
+ */
+int fs_register(const struct fs_ops *);
+
+#endif

http://git-wip-us.apache.org/repos/asf/incubator-mynewt-larva/blob/7f8fc747/libs/fs/include/fs/fsutil.h
----------------------------------------------------------------------
diff --git a/libs/fs/include/fs/fsutil.h b/libs/fs/include/fs/fsutil.h
new file mode 100644
index 0000000..59bfaf3
--- /dev/null
+++ b/libs/fs/include/fs/fsutil.h
@@ -0,0 +1,26 @@
+/**
+ * Copyright (c) 2015 Runtime Inc.
+ *
+ * Licensed under the Apache License, Version 2.0 (the "License");
+ * you may not use this file except in compliance with the License.
+ * You may obtain a copy of the License at
+ * 
+ *   http://www.apache.org/licenses/LICENSE-2.0
+ *
+ * Unless required by applicable law or agreed to in writing, software
+ * distributed under the License is distributed on an "AS IS" BASIS,
+ * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
+ * See the License for the specific language governing permissions and
+ * limitations under the License.
+ */
+
+#ifndef H_FSUTIL_
+#define H_FSUTIL_
+
+#include <inttypes.h>
+
+int fsutil_read_file(const char *path, uint32_t offset, uint32_t len,
+                     void *dst, uint32_t *out_len);
+int fsutil_write_file(const char *path, const void *data, uint32_t len);
+
+#endif

http://git-wip-us.apache.org/repos/asf/incubator-mynewt-larva/blob/7f8fc747/libs/fs/src/fs_cli.c
----------------------------------------------------------------------
diff --git a/libs/fs/src/fs_cli.c b/libs/fs/src/fs_cli.c
new file mode 100644
index 0000000..1435110
--- /dev/null
+++ b/libs/fs/src/fs_cli.c
@@ -0,0 +1,85 @@
+/**
+ * Copyright (c) 2015 Runtime Inc.
+ *
+ * Licensed under the Apache License, Version 2.0 (the "License");
+ * you may not use this file except in compliance with the License.
+ * You may obtain a copy of the License at
+ *
+ *   http://www.apache.org/licenses/LICENSE-2.0
+ *
+ * Unless required by applicable law or agreed to in writing, software
+ * distributed under the License is distributed on an "AS IS" BASIS,
+ * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
+ * See the License for the specific language governing permissions and
+ * limitations under the License.
+ */
+
+#ifdef SHELL_PRESENT
+
+#include <fs/fs.h>
+
+#include <shell/shell.h>
+#include <console/console.h>
+
+static struct shell_cmd fs_ls_struct;
+
+#if 0
+static void
+fs_ls_file(const char *name, struct fs_file *file)
+{
+    uint32_t len;
+
+    len = 0;
+    fs_filelen(file, &len);
+    console_printf("\t%6d %s\n", len, name);
+}
+#endif
+
+static int
+fs_ls_cmd(int argc, char **argv)
+{
+    int rc;
+    char *path;
+    struct fs_file *file;
+    struct fs_dir *dir;
+
+    switch (argc) {
+    case 1:
+        path = NULL;
+        break;
+    case 2:
+        path = argv[1];
+        break;
+    default:
+        console_printf("ls <path>\n");
+        return 1;
+    }
+
+    rc = fs_open(path, FS_ACCESS_READ, &file);
+    if (rc == 0) {
+#if 0
+        fs_ls_file(path, file);
+#endif
+        fs_close(file);
+    }
+    console_printf("fs_open() = %d\n", rc);
+
+    rc = fs_opendir(path, &dir);
+    console_printf("fs_opendir() = %d\n", rc);
+    if (rc == 0) {
+        fs_closedir(dir);
+    }
+    return 0;
+}
+
+void
+fs_cli_init(void)
+{
+    int rc;
+
+    rc = shell_cmd_register(&fs_ls_struct, "ls", fs_ls_cmd);
+    if (rc != 0) {
+        return;
+    }
+}
+#endif /* SHELL_PRESENT */

http://git-wip-us.apache.org/repos/asf/incubator-mynewt-larva/blob/7f8fc747/libs/fs/src/fs_dirent.c
----------------------------------------------------------------------
diff --git a/libs/fs/src/fs_dirent.c b/libs/fs/src/fs_dirent.c
new file mode 100644
index 0000000..e4428de
--- /dev/null
+++ b/libs/fs/src/fs_dirent.c
@@ -0,0 +1,49 @@
+/**
+ * Copyright (c) 2015 Runtime Inc.
+ *
+ * Licensed under the Apache License, Version 2.0 (the "License");
+ * you may not use this file except in compliance with the License.
+ * You may obtain a copy of the License at
+ *
+ *   http://www.apache.org/licenses/LICENSE-2.0
+ *
+ * Unless required by applicable law or agreed to in writing, software
+ * distributed under the License is distributed on an "AS IS" BASIS,
+ * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
+ * See the License for the specific language governing permissions and
+ * limitations under the License.
+ */
+#include <fs/fs.h>
+#include <fs/fs_if.h>
+#include "fs_priv.h"
+
+int
+fs_opendir(const char *path, struct fs_dir **out_dir)
+{
+    return fs_root_ops->f_opendir(path, out_dir);
+}
+
+int
+fs_readdir(struct fs_dir *dir, struct fs_dirent **out_dirent)
+{
+    return fs_root_ops->f_readdir(dir, out_dirent);
+}
+
+int
+fs_closedir(struct fs_dir *dir)
+{
+    return fs_root_ops->f_closedir(dir);
+}
+
+int
+fs_dirent_name(const struct fs_dirent *dirent, size_t max_len,
+  char *out_name, uint8_t *out_name_len)
+{
+    return fs_root_ops->f_dirent_name(dirent, max_len, out_name, out_name_len);
+}
+
+int
+fs_dirent_is_dir(const struct fs_dirent *dirent)
+{
+    return fs_root_ops->f_dirent_is_dir(dirent);
+}

http://git-wip-us.apache.org/repos/asf/incubator-mynewt-larva/blob/7f8fc747/libs/fs/src/fs_file.c
----------------------------------------------------------------------
diff --git a/libs/fs/src/fs_file.c b/libs/fs/src/fs_file.c
new file mode 100644
index 0000000..ec2697b
--- /dev/null
+++ b/libs/fs/src/fs_file.c
@@ -0,0 +1,67 @@
+/**
+ * Copyright (c) 2015 Runtime Inc.
+ *
+ * Licensed under the Apache License, Version 2.0 (the "License");
+ * you may not use this file except in compliance with the License.
+ * You may obtain a copy of the License at
+ *
+ *   http://www.apache.org/licenses/LICENSE-2.0
+ *
+ * Unless required by applicable law or agreed to in writing, software
+ * distributed under the License is distributed on an "AS IS" BASIS,
+ * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
+ * See the License for the specific language governing permissions and
+ * limitations under the License.
+ */
+#include <fs/fs.h>
+#include <fs/fs_if.h>
+
+#include "fs_priv.h"
+
+int
+fs_open(const char *filename, uint8_t access_flags, struct fs_file **out_file)
+{
+    return fs_root_ops->f_open(filename, access_flags, out_file);
+}
+
+int
+fs_close(struct fs_file *file)
+{
+    return fs_root_ops->f_close(file);
+}
+
+int
+fs_read(struct fs_file *file, uint32_t len, void *out_data, uint32_t *out_len)
+{
+    return fs_root_ops->f_read(file, len, out_data, out_len);
+}
+
+int
+fs_write(struct fs_file *file, const void *data, int len)
+{
+    return fs_root_ops->f_write(file, data, len);
+}
+
+int
+fs_seek(struct fs_file *file, uint32_t offset)
+{
+    return fs_root_ops->f_seek(file, offset);
+}
+
+uint32_t
+fs_getpos(const struct fs_file *file)
+{
+    return fs_root_ops->f_getpos(file);
+}
+
+int
+fs_filelen(const struct fs_file *file, uint32_t *out_len)
+{
+    return fs_root_ops->f_filelen(file, out_len);
+}
+
+int
+fs_unlink(const char *filename)
+{
+    return fs_root_ops->f_unlink(filename);
+}

http://git-wip-us.apache.org/repos/asf/incubator-mynewt-larva/blob/7f8fc747/libs/fs/src/fs_mkdir.c
----------------------------------------------------------------------
diff --git a/libs/fs/src/fs_mkdir.c b/libs/fs/src/fs_mkdir.c
new file mode 100644
index 0000000..4be7a0a
--- /dev/null
+++ b/libs/fs/src/fs_mkdir.c
@@ -0,0 +1,31 @@
+/**
+ * Copyright (c) 2015 Runtime Inc.
+ *
+ * Licensed under the Apache License, Version 2.0 (the "License");
+ * you may not use this file except in compliance with the License.
+ * You may obtain a copy of the License at
+ *
+ *   http://www.apache.org/licenses/LICENSE-2.0
+ *
+ * Unless required by applicable law or agreed to in writing, software
+ * distributed under the License is distributed on an "AS IS" BASIS,
+ * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
+ * See the License for the specific language governing permissions and
+ * limitations under the License.
+ */
+#include <fs/fs.h>
+#include <fs/fs_if.h>
+
+#include "fs_priv.h"
+
+int
+fs_rename(const char *from, const char *to)
+{
+    return fs_root_ops->f_rename(from, to);
+}
+
+int
+fs_mkdir(const char *path)
+{
+    return fs_root_ops->f_mkdir(path);
+}

http://git-wip-us.apache.org/repos/asf/incubator-mynewt-larva/blob/7f8fc747/libs/fs/src/fs_mount.c
----------------------------------------------------------------------
diff --git a/libs/fs/src/fs_mount.c b/libs/fs/src/fs_mount.c
new file mode 100644
index 0000000..e452cf2
--- /dev/null
+++ b/libs/fs/src/fs_mount.c
@@ -0,0 +1,35 @@
+/**
+ * Copyright (c) 2015 Runtime Inc.
+ *
+ * Licensed under the Apache License, Version 2.0 (the "License");
+ * you may not use this file except in compliance with the License.
+ * You may obtain a copy of the License at
+ *
+ *   http://www.apache.org/licenses/LICENSE-2.0
+ *
+ * Unless required by applicable law or agreed to in writing, software
+ * distributed under the License is distributed on an "AS IS" BASIS,
+ * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
+ * See the License for the specific language governing permissions and
+ * limitations under the License.
+ */
+#include <fs/fs.h>
+#include <fs/fs_if.h>
+#include "fs_priv.h"
+
+const struct fs_ops *fs_root_ops;
+
+int
+fs_register(const struct fs_ops *fops)
+{
+    if (fs_root_ops) {
+        return FS_EEXIST;
+    }
+    fs_root_ops = fops;
+
+#ifdef SHELL_PRESENT
+    fs_cli_init();
+#endif
+
+    return FS_EOK;
+}

http://git-wip-us.apache.org/repos/asf/incubator-mynewt-larva/blob/7f8fc747/libs/fs/src/fs_priv.h
----------------------------------------------------------------------
diff --git a/libs/fs/src/fs_priv.h b/libs/fs/src/fs_priv.h
new file mode 100644
index 0000000..c3d2ba6
--- /dev/null
+++ b/libs/fs/src/fs_priv.h
@@ -0,0 +1,26 @@
+/**
+ * Copyright (c) 2015 Runtime Inc.
+ *
+ * Licensed under the Apache License, Version 2.0 (the "License");
+ * you may not use this file except in compliance with the License.
+ * You may obtain a copy of the License at
+ *
+ *   http://www.apache.org/licenses/LICENSE-2.0
+ *
+ * Unless required by applicable law or agreed to in writing, software
+ * distributed under the License is distributed on an "AS IS" BASIS,
+ * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
+ * See the License for the specific language governing permissions and
+ * limitations under the License.
+ */
+#ifndef __FS_PRIV_H__
+#define __FS_PRIV_H__
+
+struct fs_ops;
+extern const struct fs_ops *fs_root_ops;
+
+#ifdef SHELL_PRESENT
+void fs_cli_init(void);
+#endif /* SHELL_PRESENT */
+
+#endif

http://git-wip-us.apache.org/repos/asf/incubator-mynewt-larva/blob/7f8fc747/libs/fs/src/fsutil.c
----------------------------------------------------------------------
diff --git a/libs/fs/src/fsutil.c b/libs/fs/src/fsutil.c
new file mode 100644
index 0000000..97fa84a
--- /dev/null
+++ b/libs/fs/src/fsutil.c
@@ -0,0 +1,64 @@
+/**
+ * Copyright (c) 2015 Runtime Inc.
+ *
+ * Licensed under the Apache License, Version 2.0 (the "License");
+ * you may not use this file except in compliance with the License.
+ * You may obtain a copy of the License at
+ * 
+ *   http://www.apache.org/licenses/LICENSE-2.0
+ *
+ * Unless required by applicable law or agreed to in writing, software
+ * distributed under the License is distributed on an "AS IS" BASIS,
+ * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
+ * See the License for the specific language governing permissions and
+ * limitations under the License.
+ */
+
+#include "fs/fs.h"
+
+int
+fsutil_read_file(const char *path, uint32_t offset, uint32_t len, void *dst,
+                 uint32_t *out_len)
+{
+    struct fs_file *file;
+    int rc;
+
+    rc = fs_open(path, FS_ACCESS_READ, &file);
+    if (rc != 0) {
+        goto done;
+    }
+
+    rc = fs_read(file, len, dst, out_len);
+    if (rc != 0) {
+        goto done;
+    }
+
+    rc = 0;
+
+done:
+    fs_close(file);
+    return rc;
+}
+
+int
+fsutil_write_file(const char *path, const void *data, uint32_t len)
+{
+    struct fs_file *file;
+    int rc;
+
+    rc = fs_open(path, FS_ACCESS_WRITE | FS_ACCESS_TRUNCATE, &file);
+    if (rc != 0) {
+        goto done;
+    }
+
+    rc = fs_write(file, data, len);
+    if (rc != 0) {
+        goto done;
+    }
+
+    rc = 0;
+
+done:
+    fs_close(file);
+    return rc;
+}

http://git-wip-us.apache.org/repos/asf/incubator-mynewt-larva/blob/7f8fc747/libs/nffs/egg.yml
----------------------------------------------------------------------
diff --git a/libs/nffs/egg.yml b/libs/nffs/egg.yml
index 0ad83d8..e630132 100644
--- a/libs/nffs/egg.yml
+++ b/libs/nffs/egg.yml
@@ -3,5 +3,6 @@ egg.vers: 0.1
 egg.identities: NFFS
 egg.deps:
     - libs/os
+    - libs/fs
     - libs/testutil
     - hw/hal

http://git-wip-us.apache.org/repos/asf/incubator-mynewt-larva/blob/7f8fc747/libs/nffs/include/nffs/nffs.h
----------------------------------------------------------------------
diff --git a/libs/nffs/include/nffs/nffs.h b/libs/nffs/include/nffs/nffs.h
index 45ed4e2..f57ac80 100644
--- a/libs/nffs/include/nffs/nffs.h
+++ b/libs/nffs/include/nffs/nffs.h
@@ -20,15 +20,17 @@
 #include <stddef.h>
 #include <inttypes.h>
 
+#if 0
 #define NFFS_ACCESS_READ        0x01
 #define NFFS_ACCESS_WRITE       0x02
 #define NFFS_ACCESS_APPEND      0x04
 #define NFFS_ACCESS_TRUNCATE    0x08
+#endif
 
 #define NFFS_FILENAME_MAX_LEN   256  /* Does not require null terminator. */
 
 #define NFFS_MAX_AREAS          256
-
+#if 0
 #define NFFS_EOK                0
 #define NFFS_ECORRUPT           1
 #define NFFS_EFLASH_ERROR       2
@@ -43,7 +45,7 @@
 #define NFFS_EEXIST             11
 #define NFFS_EACCESS            12
 #define NFFS_EUNINIT            13
-
+#endif
 struct nffs_config {
     /** Maximum number of inodes; default=1024. */
     uint32_t nc_num_inodes;
@@ -72,33 +74,10 @@ struct nffs_area_desc {
     uint8_t nad_flash_id;   /* Logical flash id */
 };
 
-struct nffs_file;
-struct nffs_dir;
-struct nffs_dirent;
-
-int nffs_open(const char *filename, uint8_t access_flags,
-              struct nffs_file **out_file);
-int nffs_close(struct nffs_file *file);
 int nffs_init(void);
 int nffs_detect(const struct nffs_area_desc *area_descs);
 int nffs_format(const struct nffs_area_desc *area_descs);
-int nffs_read(struct nffs_file *file, uint32_t len, void *out_data,
-              uint32_t *out_len);
-int nffs_write(struct nffs_file *file, const void *data, int len);
-int nffs_seek(struct nffs_file *file, uint32_t offset);
-uint32_t nffs_getpos(const struct nffs_file *file);
-int nffs_file_len(struct nffs_file *file, uint32_t *out_len);
-int nffs_rename(const char *from, const char *to);
-int nffs_unlink(const char *filename);
-int nffs_mkdir(const char *path);
 int nffs_ready(void);
 
-int nffs_opendir(const char *path, struct nffs_dir **out_dir);
-int nffs_readdir(struct nffs_dir *dir, struct nffs_dirent **out_dirent);
-int nffs_closedir(struct nffs_dir *dir);
-
-int nffs_dirent_name(struct nffs_dirent *dirent, size_t max_len,
-                     char *out_name, uint8_t *out_name_len);
-int nffs_dirent_is_dir(const struct nffs_dirent *dirent);
 
 #endif

http://git-wip-us.apache.org/repos/asf/incubator-mynewt-larva/blob/7f8fc747/libs/nffs/include/nffs/nffsutil.h
----------------------------------------------------------------------
diff --git a/libs/nffs/include/nffs/nffsutil.h b/libs/nffs/include/nffs/nffsutil.h
deleted file mode 100644
index 263b090..0000000
--- a/libs/nffs/include/nffs/nffsutil.h
+++ /dev/null
@@ -1,26 +0,0 @@
-/**
- * Copyright (c) 2015 Runtime Inc.
- *
- * Licensed under the Apache License, Version 2.0 (the "License");
- * you may not use this file except in compliance with the License.
- * You may obtain a copy of the License at
- * 
- *   http://www.apache.org/licenses/LICENSE-2.0
- *
- * Unless required by applicable law or agreed to in writing, software
- * distributed under the License is distributed on an "AS IS" BASIS,
- * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
- * See the License for the specific language governing permissions and
- * limitations under the License.
- */
-
-#ifndef H_NFFSUTIL_
-#define H_NFFSUTIL_
-
-#include <inttypes.h>
-
-int nffsutil_read_file(const char *path, uint32_t offset, uint32_t len,
-                       void *dst, uint32_t *out_len);
-int nffsutil_write_file(const char *path, const void *data, uint32_t len);
-
-#endif

http://git-wip-us.apache.org/repos/asf/incubator-mynewt-larva/blob/7f8fc747/libs/nffs/src/nffs.c
----------------------------------------------------------------------
diff --git a/libs/nffs/src/nffs.c b/libs/nffs/src/nffs.c
index 3aaad22..2aa3df4 100644
--- a/libs/nffs/src/nffs.c
+++ b/libs/nffs/src/nffs.c
@@ -24,6 +24,7 @@
 #include "os/os_malloc.h"
 #include "nffs_priv.h"
 #include "nffs/nffs.h"
+#include "fs/fs_if.h"
 
 struct nffs_area *nffs_areas;
 uint8_t nffs_num_areas;
@@ -49,6 +50,49 @@ struct nffs_inode_entry *nffs_lost_found_dir;
 
 static struct os_mutex nffs_mutex;
 
+static int nffs_open(const char *path, uint8_t access_flags,
+  struct fs_file **out_file);
+static int nffs_close(struct fs_file *fs_file);
+static int nffs_read(struct fs_file *fs_file, uint32_t len, void *out_data,
+  uint32_t *out_len);
+static int nffs_write(struct fs_file *fs_file, const void *data, int len);
+static int nffs_seek(struct fs_file *fs_file, uint32_t offset);
+static uint32_t nffs_getpos(const struct fs_file *fs_file);
+static int nffs_file_len(const struct fs_file *fs_file, uint32_t *out_len);
+static int nffs_unlink(const char *path);
+static int nffs_rename(const char *from, const char *to);
+static int nffs_mkdir(const char *path);
+static int nffs_opendir(const char *path, struct fs_dir **out_fs_dir);
+static int nffs_readdir(struct fs_dir *dir, struct fs_dirent **out_dirent);
+static int nffs_closedir(struct fs_dir *dir);
+static int nffs_dirent_name(const struct fs_dirent *fs_dirent, size_t max_len,
+  char *out_name, uint8_t *out_name_len);
+static int nffs_dirent_is_dir(const struct fs_dirent *fs_dirent);
+
+static const struct fs_ops nffs_ops = {
+    .f_open = nffs_open,
+    .f_close = nffs_close,
+    .f_read = nffs_read,
+    .f_write = nffs_write,
+
+    .f_seek = nffs_seek,
+    .f_getpos = nffs_getpos,
+    .f_filelen = nffs_file_len,
+
+    .f_unlink = nffs_unlink,
+    .f_rename = nffs_rename,
+    .f_mkdir = nffs_mkdir,
+
+    .f_opendir = nffs_opendir,
+    .f_readdir = nffs_readdir,
+    .f_closedir = nffs_closedir,
+
+    .f_dirent_name = nffs_dirent_name,
+    .f_dirent_is_dir = nffs_dirent_is_dir,
+
+    .f_name = "nffs"
+};
+
 static void
 nffs_lock(void)
 {
@@ -74,12 +118,12 @@ nffs_unlock(void)
  *
  * The mode strings passed to fopen() map to nffs_open()'s access flags as
  * follows:
- *   "r"  -  NFFS_ACCESS_READ
- *   "r+" -  NFFS_ACCESS_READ | NFFS_ACCESS_WRITE
- *   "w"  -  NFFS_ACCESS_WRITE | NFFS_ACCESS_TRUNCATE
- *   "w+" -  NFFS_ACCESS_READ | NFFS_ACCESS_WRITE | NFFS_ACCESS_TRUNCATE
- *   "a"  -  NFFS_ACCESS_WRITE | NFFS_ACCESS_APPEND
- *   "a+" -  NFFS_ACCESS_READ | NFFS_ACCESS_WRITE | NFFS_ACCESS_APPEND
+ *   "r"  -  FS_ACCESS_READ
+ *   "r+" -  FS_ACCESS_READ | FS_ACCESS_WRITE
+ *   "w"  -  FS_ACCESS_WRITE | FS_ACCESS_TRUNCATE
+ *   "w+" -  FS_ACCESS_READ | FS_ACCESS_WRITE | FS_ACCESS_TRUNCATE
+ *   "a"  -  FS_ACCESS_WRITE | FS_ACCESS_APPEND
+ *   "a+" -  FS_ACCESS_READ | FS_ACCESS_WRITE | FS_ACCESS_APPEND
  *
  * @param path              The path of the file to open.
  * @param access_flags      Flags controlling file access; see above table.
@@ -88,27 +132,28 @@ nffs_unlock(void)
  *
  * @return                  0 on success; nonzero on failure.
  */
-int
-nffs_open(const char *path, uint8_t access_flags, struct nffs_file **out_file)
+static int
+nffs_open(const char *path, uint8_t access_flags, struct fs_file **out_fs_file)
 {
     int rc;
+    struct nffs_file *out_file;
 
     nffs_lock();
 
     if (!nffs_ready()) {
-        rc = NFFS_EUNINIT;
+        rc = FS_EUNINIT;
         goto done;
     }
 
-    rc = nffs_file_open(out_file, path, access_flags);
+    rc = nffs_file_open(&out_file, path, access_flags);
     if (rc != 0) {
         goto done;
     }
-
+    *out_fs_file = (struct fs_file *)out_file;
 done:
     nffs_unlock();
     if (rc != 0) {
-        *out_file = NULL;
+        *out_fs_file = NULL;
     }
     return rc;
 }
@@ -122,10 +167,11 @@ done:
  *
  * @return                  0 on success; nonzero on failure.
  */
-int
-nffs_close(struct nffs_file *file)
+static int
+nffs_close(struct fs_file *fs_file)
 {
     int rc;
+    struct nffs_file *file = (struct nffs_file *)fs_file;
 
     if (file == NULL) {
         return 0;
@@ -148,10 +194,11 @@ nffs_close(struct nffs_file *file)
  *
  * @return                  0 on success; nonzero on failure.
  */
-int
-nffs_seek(struct nffs_file *file, uint32_t offset)
+static int
+nffs_seek(struct fs_file *fs_file, uint32_t offset)
 {
     int rc;
+    struct nffs_file *file = (struct nffs_file *)fs_file;
 
     nffs_lock();
     rc = nffs_file_seek(file, offset);
@@ -167,10 +214,11 @@ nffs_seek(struct nffs_file *file, uint32_t offset)
  *
  * @return                  The file offset, in bytes.
  */
-uint32_t
-nffs_getpos(const struct nffs_file *file)
+static uint32_t
+nffs_getpos(const struct fs_file *fs_file)
 {
     uint32_t offset;
+    const struct nffs_file *file = (const struct nffs_file *)fs_file;
 
     nffs_lock();
     offset = file->nf_offset;
@@ -188,10 +236,11 @@ nffs_getpos(const struct nffs_file *file)
  *
  * @return                  0 on success; nonzero on failure.
  */
-int
-nffs_file_len(struct nffs_file *file, uint32_t *out_len)
+static int
+nffs_file_len(const struct fs_file *fs_file, uint32_t *out_len)
 {
     int rc;
+    const struct nffs_file *file = (const struct nffs_file *)fs_file;
 
     nffs_lock();
     rc = nffs_inode_data_len(file->nf_inode_entry, out_len);
@@ -213,11 +262,12 @@ nffs_file_len(struct nffs_file *file, uint32_t *out_len)
  *
  * @return                  0 on success; nonzero on failure.
  */
-int
-nffs_read(struct nffs_file *file, uint32_t len, void *out_data,
+static int
+nffs_read(struct fs_file *fs_file, uint32_t len, void *out_data,
           uint32_t *out_len)
 {
     int rc;
+    struct nffs_file *file = (struct nffs_file *)fs_file;
 
     nffs_lock();
     rc = nffs_file_read(file, len, out_data, out_len);
@@ -235,15 +285,16 @@ nffs_read(struct nffs_file *file, uint32_t len, void *out_data,
  *
  * @return                  0 on success; nonzero on failure.
  */
-int
-nffs_write(struct nffs_file *file, const void *data, int len)
+static int
+nffs_write(struct fs_file *fs_file, const void *data, int len)
 {
     int rc;
+    struct nffs_file *file = (struct nffs_file *)fs_file;
 
     nffs_lock();
 
     if (!nffs_ready()) {
-        rc = NFFS_EUNINIT;
+        rc = FS_EUNINIT;
         goto done;
     }
 
@@ -269,7 +320,7 @@ done:
  *
  * @return                  0 on success; nonzero on failure.
  */
-int
+static int
 nffs_unlink(const char *path)
 {
     int rc;
@@ -277,7 +328,7 @@ nffs_unlink(const char *path)
     nffs_lock();
 
     if (!nffs_ready()) {
-        rc = NFFS_EUNINIT;
+        rc = FS_EUNINIT;
         goto done;
     }
 
@@ -309,7 +360,7 @@ done:
  * @return                  0 on success;
  *                          nonzero on failure.
  */
-int
+static int
 nffs_rename(const char *from, const char *to)
 {
     int rc;
@@ -317,7 +368,7 @@ nffs_rename(const char *from, const char *to)
     nffs_lock();
 
     if (!nffs_ready()) {
-        rc = NFFS_EUNINIT;
+        rc = FS_EUNINIT;
         goto done;
     }
 
@@ -343,7 +394,7 @@ done:
  * @return                      0 on success;
  *                              nonzero on failure.
  */
-int
+static int
 nffs_mkdir(const char *path)
 {
     int rc;
@@ -351,7 +402,7 @@ nffs_mkdir(const char *path)
     nffs_lock();
 
     if (!nffs_ready()) {
-        rc = NFFS_EUNINIT;
+        rc = FS_EUNINIT;
         goto done;
     }
 
@@ -377,19 +428,20 @@ done:
  * @param out_dir               On success, points to the directory handle.
  *
  * @return                      0 on success;
- *                              NFFS_ENOENT if the specified directory does not
+ *                              FS_ENOENT if the specified directory does not
  *                                  exist;
  *                              other nonzero on error.
  */
-int
-nffs_opendir(const char *path, struct nffs_dir **out_dir)
+static int
+nffs_opendir(const char *path, struct fs_dir **out_fs_dir)
 {
     int rc;
+    struct nffs_dir **out_dir = (struct nffs_dir **)out_fs_dir;
 
     nffs_lock();
 
     if (!nffs_ready()) {
-        rc = NFFS_EUNINIT;
+        rc = FS_EUNINIT;
         goto done;
     }
 
@@ -408,14 +460,16 @@ done:
  *                                  the specified directory.
  *
  * @return                      0 on success;
- *                              NFFS_ENOENT if there are no more entries in the
+ *                              FS_ENOENT if there are no more entries in the
  *                                  parent directory;
  *                              other nonzero on error.
  */
-int
-nffs_readdir(struct nffs_dir *dir, struct nffs_dirent **out_dirent)
+static int
+nffs_readdir(struct fs_dir *fs_dir, struct fs_dirent **out_fs_dirent)
 {
     int rc;
+    struct nffs_dir *dir = (struct nffs_dir *)fs_dir;
+    struct nffs_dirent **out_dirent = (struct nffs_dirent **)out_fs_dirent;
 
     nffs_lock();
     rc = nffs_dir_read(dir, out_dirent);
@@ -431,10 +485,11 @@ nffs_readdir(struct nffs_dir *dir, struct nffs_dirent **out_dirent)
  *
  * @return                      0 on success; nonzero on failure.
  */
-int
-nffs_closedir(struct nffs_dir *dir)
+static int
+nffs_closedir(struct fs_dir *fs_dir)
 {
     int rc;
+    struct nffs_dir *dir = (struct nffs_dir *)fs_dir;
 
     nffs_lock();
     rc = nffs_dir_close(dir);
@@ -459,11 +514,12 @@ nffs_closedir(struct nffs_dir *dir)
  *
  * @return                      0 on success; nonzero on failure.
  */
-int
-nffs_dirent_name(struct nffs_dirent *dirent, size_t max_len,
+static int
+nffs_dirent_name(const struct fs_dirent *fs_dirent, size_t max_len,
                  char *out_name, uint8_t *out_name_len)
 {
     int rc;
+    struct nffs_dirent *dirent = (struct nffs_dirent *)fs_dirent;
 
     nffs_lock();
 
@@ -485,10 +541,11 @@ nffs_dirent_name(struct nffs_dirent *dirent, size_t max_len,
  * @return                      1: The entry is a directory;
  *                              0: The entry is a regular file.
  */
-int
-nffs_dirent_is_dir(const struct nffs_dirent *dirent)
+static int
+nffs_dirent_is_dir(const struct fs_dirent *fs_dirent)
 {
     uint32_t id;
+    const struct nffs_dirent *dirent = (const struct nffs_dirent *)fs_dirent;
 
     nffs_lock();
 
@@ -531,7 +588,7 @@ nffs_format(const struct nffs_area_desc *area_descs)
  *                              terminated with a 0-length area.
  *
  * @return                  0 on success;
- *                          NFFS_ECORRUPT if no valid file system was detected;
+ *                          FS_ECORRUPT if no valid file system was detected;
  *                          other nonzero on error.
  */
 int
@@ -575,14 +632,14 @@ nffs_init(void)
 
     rc = os_mutex_init(&nffs_mutex);
     if (rc != 0) {
-        return NFFS_EOS;
+        return FS_EOS;
     }
 
     free(nffs_file_mem);
     nffs_file_mem = malloc(
         OS_MEMPOOL_BYTES(nffs_config.nc_num_files, sizeof (struct nffs_file)));
     if (nffs_file_mem == NULL) {
-        return NFFS_ENOMEM;
+        return FS_ENOMEM;
     }
 
     free(nffs_inode_mem);
@@ -590,7 +647,7 @@ nffs_init(void)
         OS_MEMPOOL_BYTES(nffs_config.nc_num_inodes,
                         sizeof (struct nffs_inode_entry)));
     if (nffs_inode_mem == NULL) {
-        return NFFS_ENOMEM;
+        return FS_ENOMEM;
     }
 
     free(nffs_block_entry_mem);
@@ -598,7 +655,7 @@ nffs_init(void)
         OS_MEMPOOL_BYTES(nffs_config.nc_num_blocks,
                          sizeof (struct nffs_hash_entry)));
     if (nffs_block_entry_mem == NULL) {
-        return NFFS_ENOMEM;
+        return FS_ENOMEM;
     }
 
     free(nffs_cache_inode_mem);
@@ -606,7 +663,7 @@ nffs_init(void)
         OS_MEMPOOL_BYTES(nffs_config.nc_num_cache_inodes,
                          sizeof (struct nffs_cache_inode)));
     if (nffs_cache_inode_mem == NULL) {
-        return NFFS_ENOMEM;
+        return FS_ENOMEM;
     }
 
     free(nffs_cache_block_mem);
@@ -614,7 +671,7 @@ nffs_init(void)
         OS_MEMPOOL_BYTES(nffs_config.nc_num_cache_blocks,
                          sizeof (struct nffs_cache_block)));
     if (nffs_cache_block_mem == NULL) {
-        return NFFS_ENOMEM;
+        return FS_ENOMEM;
     }
 
     free(nffs_dir_mem);
@@ -622,7 +679,7 @@ nffs_init(void)
         OS_MEMPOOL_BYTES(nffs_config.nc_num_dirs,
                          sizeof (struct nffs_dir)));
     if (nffs_dir_mem == NULL) {
-        return NFFS_ENOMEM;
+        return FS_ENOMEM;
     }
 
     rc = nffs_misc_reset();
@@ -630,5 +687,6 @@ nffs_init(void)
         return rc;
     }
 
+    fs_register(&nffs_ops);
     return 0;
 }

http://git-wip-us.apache.org/repos/asf/incubator-mynewt-larva/blob/7f8fc747/libs/nffs/src/nffs_area.c
----------------------------------------------------------------------
diff --git a/libs/nffs/src/nffs_area.c b/libs/nffs/src/nffs_area.c
index e818a39..82163db 100644
--- a/libs/nffs/src/nffs_area.c
+++ b/libs/nffs/src/nffs_area.c
@@ -73,7 +73,7 @@ nffs_area_free_space(const struct nffs_area *area)
  *                                  area gets written here.
  *
  * @return                      0 if a corrupt scratch area was identified;
- *                              NFFS_ENOENT if one was not found.
+ *                              FS_ENOENT if one was not found.
  */
 int
 nffs_area_find_corrupt_scratch(uint16_t *out_good_idx, uint16_t *out_bad_idx)
@@ -105,5 +105,5 @@ nffs_area_find_corrupt_scratch(uint16_t *out_good_idx, uint16_t *out_bad_idx)
         }
     }
 
-    return NFFS_ENOENT;
+    return FS_ENOENT;
 }

http://git-wip-us.apache.org/repos/asf/incubator-mynewt-larva/blob/7f8fc747/libs/nffs/src/nffs_block.c
----------------------------------------------------------------------
diff --git a/libs/nffs/src/nffs_block.c b/libs/nffs/src/nffs_block.c
index b745913..6221664 100644
--- a/libs/nffs/src/nffs_block.c
+++ b/libs/nffs/src/nffs_block.c
@@ -63,7 +63,7 @@ nffs_block_read_disk(uint8_t area_idx, uint32_t area_offset,
         return rc;
     }
     if (out_disk_block->ndb_magic != NFFS_BLOCK_MAGIC) {
-        return NFFS_EUNEXP;
+        return FS_EUNEXP;
     }
 
     return 0;
@@ -138,13 +138,13 @@ nffs_block_from_disk(struct nffs_block *out_block,
 
     out_block->nb_inode_entry = nffs_hash_find_inode(disk_block->ndb_inode_id);
     if (out_block->nb_inode_entry == NULL) {
-        return NFFS_ECORRUPT;
+        return FS_ECORRUPT;
     }
 
     if (disk_block->ndb_prev_id != NFFS_ID_NONE) {
         out_block->nb_prev = nffs_hash_find_block(disk_block->ndb_prev_id);
         if (out_block->nb_prev == NULL) {
-            return NFFS_ECORRUPT;
+            return FS_ECORRUPT;
         }
     }
 

http://git-wip-us.apache.org/repos/asf/incubator-mynewt-larva/blob/7f8fc747/libs/nffs/src/nffs_cache.c
----------------------------------------------------------------------
diff --git a/libs/nffs/src/nffs_cache.c b/libs/nffs/src/nffs_cache.c
index c415985..32a42eb 100644
--- a/libs/nffs/src/nffs_cache.c
+++ b/libs/nffs/src/nffs_cache.c
@@ -319,7 +319,7 @@ nffs_cache_seek(struct nffs_cache_inode *cache_inode, uint32_t seek_offset,
 
     /* Empty files have no blocks that can be cached. */
     if (cache_inode->nci_file_size == 0) {
-        return NFFS_ENOENT;
+        return FS_ENOENT;
     }
 
     nffs_cache_inode_range(cache_inode, &cache_start, &cache_end);

http://git-wip-us.apache.org/repos/asf/incubator-mynewt-larva/blob/7f8fc747/libs/nffs/src/nffs_crc.c
----------------------------------------------------------------------
diff --git a/libs/nffs/src/nffs_crc.c b/libs/nffs/src/nffs_crc.c
index 2e15d39..97d6b47 100644
--- a/libs/nffs/src/nffs_crc.c
+++ b/libs/nffs/src/nffs_crc.c
@@ -14,6 +14,7 @@
  * limitations under the License.
  */
 
+
 #include "nffs_priv.h"
 #include "crc16.h"
 
@@ -93,7 +94,7 @@ nffs_crc_disk_block_validate(const struct nffs_disk_block *disk_block,
     }
 
     if (crc != disk_block->ndb_crc16) {
-        return NFFS_ECORRUPT;
+        return FS_ECORRUPT;
     }
 
     return 0;
@@ -153,7 +154,7 @@ nffs_crc_disk_inode_validate(const struct nffs_disk_inode *disk_inode,
     }
 
     if (crc != disk_inode->ndi_crc16) {
-        return NFFS_ECORRUPT;
+        return FS_ECORRUPT;
     }
 
     return 0;

http://git-wip-us.apache.org/repos/asf/incubator-mynewt-larva/blob/7f8fc747/libs/nffs/src/nffs_dir.c
----------------------------------------------------------------------
diff --git a/libs/nffs/src/nffs_dir.c b/libs/nffs/src/nffs_dir.c
index cc69133..c8b9bcf 100644
--- a/libs/nffs/src/nffs_dir.c
+++ b/libs/nffs/src/nffs_dir.c
@@ -40,7 +40,7 @@ nffs_dir_free(struct nffs_dir *dir)
     if (dir != NULL) {
         rc = os_memblock_put(&nffs_dir_pool, dir);
         if (rc != 0) {
-            return NFFS_EOS;
+            return FS_EOS;
         }
     }
 
@@ -55,7 +55,7 @@ nffs_dir_open(const char *path, struct nffs_dir **out_dir)
 
     dir = nffs_dir_alloc();
     if (dir == NULL) {
-        return NFFS_ENOMEM;
+        return FS_ENOMEM;
     }
 
     rc = nffs_path_find_inode_entry(path, &dir->nd_parent_inode_entry);
@@ -91,7 +91,7 @@ nffs_dir_read(struct nffs_dir *dir, struct nffs_dirent **out_dirent)
 
     if (child == NULL) {
         *out_dirent = NULL;
-        return NFFS_ENOENT;
+        return FS_ENOENT;
     }
 
     child->nie_refcnt++;

http://git-wip-us.apache.org/repos/asf/incubator-mynewt-larva/blob/7f8fc747/libs/nffs/src/nffs_file.c
----------------------------------------------------------------------
diff --git a/libs/nffs/src/nffs_file.c b/libs/nffs/src/nffs_file.c
index c01753c..7056346 100644
--- a/libs/nffs/src/nffs_file.c
+++ b/libs/nffs/src/nffs_file.c
@@ -40,7 +40,7 @@ nffs_file_free(struct nffs_file *file)
     if (file != NULL) {
         rc = os_memblock_put(&nffs_file_pool, file);
         if (rc != 0) {
-            return NFFS_EOS;
+            return FS_EOS;
         }
     }
 
@@ -74,7 +74,7 @@ nffs_file_new(struct nffs_inode_entry *parent, const char *filename,
 
     inode_entry = nffs_inode_entry_alloc();
     if (inode_entry == NULL) {
-        rc = NFFS_ENOMEM;
+        rc = FS_ENOMEM;
         goto err;
     }
 
@@ -153,34 +153,34 @@ nffs_file_open(struct nffs_file **out_file, const char *path,
     file = NULL;
 
     /* Reject invalid access flag combinations. */
-    if (!(access_flags & (NFFS_ACCESS_READ | NFFS_ACCESS_WRITE))) {
-        rc = NFFS_EINVAL;
+    if (!(access_flags & (FS_ACCESS_READ | FS_ACCESS_WRITE))) {
+        rc = FS_EINVAL;
         goto err;
     }
-    if (access_flags & (NFFS_ACCESS_APPEND | NFFS_ACCESS_TRUNCATE) &&
-        !(access_flags & NFFS_ACCESS_WRITE)) {
+    if (access_flags & (FS_ACCESS_APPEND | FS_ACCESS_TRUNCATE) &&
+        !(access_flags & FS_ACCESS_WRITE)) {
 
-        rc = NFFS_EINVAL;
+        rc = FS_EINVAL;
         goto err;
     }
-    if (access_flags & NFFS_ACCESS_APPEND &&
-        access_flags & NFFS_ACCESS_TRUNCATE) {
+    if (access_flags & FS_ACCESS_APPEND &&
+        access_flags & FS_ACCESS_TRUNCATE) {
 
-        rc = NFFS_EINVAL;
+        rc = FS_EINVAL;
         goto err;
     }
 
     file = nffs_file_alloc();
     if (file == NULL) {
-        rc = NFFS_ENOMEM;
+        rc = FS_ENOMEM;
         goto err;
     }
 
     nffs_path_parser_new(&parser, path);
     rc = nffs_path_find(&parser, &inode, &parent);
-    if (rc == NFFS_ENOENT) {
+    if (rc == FS_ENOENT) {
         /* The file does not exist.  This is an error for read-only opens. */
-        if (!(access_flags & NFFS_ACCESS_WRITE)) {
+        if (!(access_flags & FS_ACCESS_WRITE)) {
             goto err;
         }
 
@@ -200,11 +200,11 @@ nffs_file_open(struct nffs_file **out_file, const char *path,
 
         /* Reject an attempt to open a directory. */
         if (parser.npp_token_type != NFFS_PATH_TOKEN_LEAF) {
-            rc = NFFS_EINVAL;
+            rc = FS_EINVAL;
             goto err;
         }
 
-        if (access_flags & NFFS_ACCESS_TRUNCATE) {
+        if (access_flags & FS_ACCESS_TRUNCATE) {
             /* The user is truncating the file.  Unlink the old file and create
              * a new one in its place.
              */
@@ -222,7 +222,7 @@ nffs_file_open(struct nffs_file **out_file, const char *path,
         }
     }
 
-    if (access_flags & NFFS_ACCESS_APPEND) {
+    if (access_flags & FS_ACCESS_APPEND) {
         rc = nffs_inode_data_len(file->nf_inode_entry, &file->nf_offset);
         if (rc != 0) {
             goto err;
@@ -264,7 +264,7 @@ nffs_file_seek(struct nffs_file *file, uint32_t offset)
     }
 
     if (offset > len) {
-        return NFFS_ERANGE;
+        return FS_ERANGE;
     }
 
     file->nf_offset = offset;
@@ -292,11 +292,11 @@ nffs_file_read(struct nffs_file *file, uint32_t len, void *out_data,
     int rc;
 
     if (!nffs_ready()) {
-        return NFFS_EUNINIT;
+        return FS_EUNINIT;
     }
 
-    if (!(file->nf_access_flags & NFFS_ACCESS_READ)) {
-        return NFFS_EACCESS;
+    if (!(file->nf_access_flags & FS_ACCESS_READ)) {
+        return FS_EACCESS;
     }
 
     rc = nffs_inode_read(file->nf_inode_entry, file->nf_offset, len, out_data,

http://git-wip-us.apache.org/repos/asf/incubator-mynewt-larva/blob/7f8fc747/libs/nffs/src/nffs_flash.c
----------------------------------------------------------------------
diff --git a/libs/nffs/src/nffs_flash.c b/libs/nffs/src/nffs_flash.c
index a5cbae6..94456b4 100644
--- a/libs/nffs/src/nffs_flash.c
+++ b/libs/nffs/src/nffs_flash.c
@@ -32,9 +32,9 @@ uint8_t nffs_flash_buf[NFFS_FLASH_BUF_SZ];
  * @param len                   The number of bytes to read.
  *
  * @return                      0 on success;
- *                              NFFS_ERANGE on an attempt to read an invalid
+ *                              FS_ERANGE on an attempt to read an invalid
  *                                  address range;
- *                              NFFS_EFLASH_ERROR on flash error.
+ *                              FS_HW_ERROR on flash error.
  */
 int
 nffs_flash_read(uint8_t area_idx, uint32_t area_offset, void *data,
@@ -48,13 +48,13 @@ nffs_flash_read(uint8_t area_idx, uint32_t area_offset, void *data,
     area = nffs_areas + area_idx;
 
     if (area_offset + len > area->na_length) {
-        return NFFS_ERANGE;
+        return FS_ERANGE;
     }
 
     rc = hal_flash_read(area->na_flash_id, area->na_offset + area_offset, data,
                         len);
     if (rc != 0) {
-        return NFFS_EFLASH_ERROR;
+        return FS_HW_ERROR;
     }
 
     return 0;
@@ -69,10 +69,10 @@ nffs_flash_read(uint8_t area_idx, uint32_t area_offset, void *data,
  * @param len                   The number of bytes to write.
  *
  * @return                      0 on success;
- *                              NFFS_ERANGE on an attempt to write to an
+ *                              FS_ERANGE on an attempt to write to an
  *                                  invalid address range, or on an attempt to
  *                                  perform a non-strictly-sequential write;
- *                              NFFS_EFLASH_ERROR on flash error.
+ *                              FS_EFLASH_ERROR on flash error.
  */
 int
 nffs_flash_write(uint8_t area_idx, uint32_t area_offset, const void *data,
@@ -85,17 +85,17 @@ nffs_flash_write(uint8_t area_idx, uint32_t area_offset, const void *data,
     area = nffs_areas + area_idx;
 
     if (area_offset + len > area->na_length) {
-        return NFFS_ERANGE;
+        return FS_ERANGE;
     }
 
     if (area_offset < area->na_cur) {
-        return NFFS_ERANGE;
+        return FS_ERANGE;
     }
 
     rc = hal_flash_write(area->na_flash_id, area->na_offset + area_offset, data,
                          len);
     if (rc != 0) {
-        return NFFS_EFLASH_ERROR;
+        return FS_HW_ERROR;
     }
 
     area->na_cur = area_offset + len;

http://git-wip-us.apache.org/repos/asf/incubator-mynewt-larva/blob/7f8fc747/libs/nffs/src/nffs_format.c
----------------------------------------------------------------------
diff --git a/libs/nffs/src/nffs_format.c b/libs/nffs/src/nffs_format.c
index 795d530..56a040f 100644
--- a/libs/nffs/src/nffs_format.c
+++ b/libs/nffs/src/nffs_format.c
@@ -113,7 +113,7 @@ nffs_format_full(const struct nffs_area_desc *area_descs)
     nffs_scratch_area_idx = 0;
     for (i = 1; area_descs[i].nad_length != 0; i++) {
         if (i >= NFFS_MAX_AREAS) {
-            rc = NFFS_EINVAL;
+            rc = FS_EINVAL;
             goto err;
         }
 

http://git-wip-us.apache.org/repos/asf/incubator-mynewt-larva/blob/7f8fc747/libs/nffs/src/nffs_gc.c
----------------------------------------------------------------------
diff --git a/libs/nffs/src/nffs_gc.c b/libs/nffs/src/nffs_gc.c
index fd861ff..a51460e 100644
--- a/libs/nffs/src/nffs_gc.c
+++ b/libs/nffs/src/nffs_gc.c
@@ -156,7 +156,7 @@ nffs_gc_block_chain_copy(struct nffs_hash_entry *last_entry, uint32_t data_len,
  *                                  that should be processed.
  *
  * @return                      0 on success;
- *                              NFFS_ENOMEM if there is insufficient heap;
+ *                              FS_ENOMEM if there is insufficient heap;
  *                              other nonzero on failure.
  */
 static int
@@ -177,7 +177,7 @@ nffs_gc_block_chain_collate(struct nffs_hash_entry *last_entry,
 
     data = malloc(data_len);
     if (data == NULL) {
-        rc = NFFS_ENOMEM;
+        rc = FS_ENOMEM;
         goto done;
     }
 
@@ -284,7 +284,7 @@ nffs_gc_block_chain(struct nffs_hash_entry *last_entry, int multiple_blocks,
     } else {
         rc = nffs_gc_block_chain_collate(last_entry, data_len, to_area_idx,
                                          inout_next);
-        if (rc == NFFS_ENOMEM) {
+        if (rc == FS_ENOMEM) {
             /* Insufficient heap for collation; just copy each block one by
              * one.
              */
@@ -498,7 +498,7 @@ nffs_gc(uint8_t *out_area_idx)
  *                                  accommodate the necessary data.
  *
  * @return                      0 on success;
- *                              NFFS_EFULL if the necessary space could not be
+ *                              FS_EFULL if the necessary space could not be
  *                                  freed.
  *                              nonzero on other failure.
  */
@@ -519,5 +519,5 @@ nffs_gc_until(uint32_t space, uint8_t *out_area_idx)
         }
     }
 
-    return NFFS_EFULL;
+    return FS_EFULL;
 }

http://git-wip-us.apache.org/repos/asf/incubator-mynewt-larva/blob/7f8fc747/libs/nffs/src/nffs_hash.c
----------------------------------------------------------------------
diff --git a/libs/nffs/src/nffs_hash.c b/libs/nffs/src/nffs_hash.c
index 5e49563..4d6bff2 100644
--- a/libs/nffs/src/nffs_hash.c
+++ b/libs/nffs/src/nffs_hash.c
@@ -139,7 +139,7 @@ nffs_hash_init(void)
 
     nffs_hash = malloc(NFFS_HASH_SIZE * sizeof *nffs_hash);
     if (nffs_hash == NULL) {
-        return NFFS_ENOMEM;
+        return FS_ENOMEM;
     }
 
     for (i = 0; i < NFFS_HASH_SIZE; i++) {

http://git-wip-us.apache.org/repos/asf/incubator-mynewt-larva/blob/7f8fc747/libs/nffs/src/nffs_inode.c
----------------------------------------------------------------------
diff --git a/libs/nffs/src/nffs_inode.c b/libs/nffs/src/nffs_inode.c
index d19f76f..f4d1e46 100644
--- a/libs/nffs/src/nffs_inode.c
+++ b/libs/nffs/src/nffs_inode.c
@@ -74,7 +74,7 @@ nffs_inode_read_disk(uint8_t area_idx, uint32_t offset,
         return rc;
     }
     if (out_disk_inode->ndi_magic != NFFS_INODE_MAGIC) {
-        return NFFS_EUNEXP;
+        return FS_EUNEXP;
     }
 
     return 0;
@@ -719,7 +719,7 @@ nffs_inode_seek(struct nffs_inode_entry *inode_entry, uint32_t offset,
     }
 
     if (offset > cache_inode->nci_file_size) {
-        return NFFS_ERANGE;
+        return FS_ERANGE;
     }
     if (offset == cache_inode->nci_file_size) {
         memset(&out_seek_info->nsi_last_block, 0,

http://git-wip-us.apache.org/repos/asf/incubator-mynewt-larva/blob/7f8fc747/libs/nffs/src/nffs_misc.c
----------------------------------------------------------------------
diff --git a/libs/nffs/src/nffs_misc.c b/libs/nffs/src/nffs_misc.c
index eab0db6..e613b2c 100644
--- a/libs/nffs/src/nffs_misc.c
+++ b/libs/nffs/src/nffs_misc.c
@@ -27,7 +27,7 @@
  *     o No parent inode.
  *
  * @return                      0 if there is a valid root directory;
- *                              NFFS_ECORRUPT if there is not a valid root
+ *                              FS_ECORRUPT if there is not a valid root
  *                                  directory;
  *                              nonzero on other error.
  */
@@ -38,11 +38,11 @@ nffs_misc_validate_root_dir(void)
     int rc;
 
     if (nffs_root_dir == NULL) {
-        return NFFS_ECORRUPT;
+        return FS_ECORRUPT;
     }
 
     if (nffs_root_dir->nie_hash_entry.nhe_id != NFFS_ID_ROOT_DIR) {
-        return NFFS_ECORRUPT;
+        return FS_ECORRUPT;
     }
 
     rc = nffs_inode_from_entry(&inode, nffs_root_dir);
@@ -51,7 +51,7 @@ nffs_misc_validate_root_dir(void)
     }
 
     if (inode.ni_parent != NULL) {
-        return NFFS_ECORRUPT;
+        return FS_ECORRUPT;
     }
 
     return 0;
@@ -63,7 +63,7 @@ nffs_misc_validate_root_dir(void)
  * system.
  *
  * @return                      0 if there is a valid scratch area;
- *                              NFFS_ECORRUPT otherwise.
+ *                              FS_ECORRUPT otherwise.
  */
 int
 nffs_misc_validate_scratch(void)
@@ -73,13 +73,13 @@ nffs_misc_validate_scratch(void)
 
     if (nffs_scratch_area_idx == NFFS_AREA_ID_NONE) {
         /* No scratch area. */
-        return NFFS_ECORRUPT;
+        return FS_ECORRUPT;
     }
 
     scratch_len = nffs_areas[nffs_scratch_area_idx].na_length;
     for (i = 0; i < nffs_num_areas; i++) {
         if (nffs_areas[i].na_length > scratch_len) {
-            return NFFS_ECORRUPT;
+            return FS_ECORRUPT;
         }
     }
 
@@ -95,7 +95,7 @@ nffs_misc_validate_scratch(void)
  *                                  written here.
  *
  * @return                      0 on success;
- *                              NFFS_EFULL if the area has insufficient free
+ *                              FS_EFULL if the area has insufficient free
  *                                  space.
  */
 static int
@@ -112,7 +112,7 @@ nffs_misc_reserve_space_area(uint8_t area_idx, uint16_t space,
         return 0;
     }
 
-    return NFFS_EFULL;
+    return FS_EFULL;
 }
 
 /**
@@ -175,7 +175,7 @@ nffs_misc_set_num_areas(uint8_t num_areas)
     } else {
         nffs_areas = realloc(nffs_areas, num_areas * sizeof *nffs_areas);
         if (nffs_areas == NULL) {
-            return NFFS_ENOMEM;
+            return FS_ENOMEM;
         }
     }
 
@@ -237,7 +237,7 @@ nffs_misc_set_max_block_data_len(uint16_t min_data_len)
 
     /* Don't allow a data block size bigger than the smallest area. */
     if (nffs_misc_area_capacity_one(smallest_area) < min_data_len) {
-        return NFFS_ECORRUPT;
+        return FS_ECORRUPT;
     }
 
     half_smallest = nffs_misc_area_capacity_two(smallest_area);
@@ -264,7 +264,7 @@ nffs_misc_create_lost_found_dir(void)
     case 0:
         return 0;
 
-    case NFFS_EEXIST:
+    case FS_EEXIST:
         rc = nffs_path_find_inode_entry("/lost+found", &nffs_lost_found_dir);
         return rc;
 
@@ -290,21 +290,21 @@ nffs_misc_reset(void)
                          sizeof (struct nffs_file), nffs_file_mem,
                          "nffs_file_pool");
     if (rc != 0) {
-        return NFFS_EOS;
+        return FS_EOS;
     }
 
     rc = os_mempool_init(&nffs_inode_entry_pool, nffs_config.nc_num_inodes,
                          sizeof (struct nffs_inode_entry), nffs_inode_mem,
                          "nffs_inode_entry_pool");
     if (rc != 0) {
-        return NFFS_EOS;
+        return FS_EOS;
     }
 
     rc = os_mempool_init(&nffs_block_entry_pool, nffs_config.nc_num_blocks,
                          sizeof (struct nffs_hash_entry), nffs_block_entry_mem,
                          "nffs_block_entry_pool");
     if (rc != 0) {
-        return NFFS_EOS;
+        return FS_EOS;
     }
 
     rc = os_mempool_init(&nffs_cache_inode_pool,
@@ -312,7 +312,7 @@ nffs_misc_reset(void)
                          sizeof (struct nffs_cache_inode),
                          nffs_cache_inode_mem, "nffs_cache_inode_pool");
     if (rc != 0) {
-        return NFFS_EOS;
+        return FS_EOS;
     }
 
     rc = os_mempool_init(&nffs_cache_block_pool,
@@ -320,7 +320,7 @@ nffs_misc_reset(void)
                          sizeof (struct nffs_cache_block),
                          nffs_cache_block_mem, "nffs_cache_block_pool");
     if (rc != 0) {
-        return NFFS_EOS;
+        return FS_EOS;
     }
 
     rc = os_mempool_init(&nffs_dir_pool,
@@ -328,7 +328,7 @@ nffs_misc_reset(void)
                          sizeof (struct nffs_dir),
                          nffs_dir_mem, "nffs_dir_pool");
     if (rc != 0) {
-        return NFFS_EOS;
+        return FS_EOS;
     }
 
     rc = nffs_hash_init();

http://git-wip-us.apache.org/repos/asf/incubator-mynewt-larva/blob/7f8fc747/libs/nffs/src/nffs_path.c
----------------------------------------------------------------------
diff --git a/libs/nffs/src/nffs_path.c b/libs/nffs/src/nffs_path.c
index 8ab7f53..1dc9289 100644
--- a/libs/nffs/src/nffs_path.c
+++ b/libs/nffs/src/nffs_path.c
@@ -27,13 +27,13 @@ nffs_path_parse_next(struct nffs_path_parser *parser)
     int token_len;
 
     if (parser->npp_token_type == NFFS_PATH_TOKEN_LEAF) {
-        return NFFS_EINVAL;
+        return FS_EINVAL;
     }
 
     slash_start = strchr(parser->npp_path + parser->npp_off, '/');
     if (slash_start == NULL) {
         if (parser->npp_token_type == NFFS_PATH_TOKEN_NONE) {
-            return NFFS_EINVAL;
+            return FS_EINVAL;
         }
         parser->npp_token_type = NFFS_PATH_TOKEN_LEAF;
         token_len = strlen(parser->npp_path + parser->npp_off);
@@ -44,7 +44,7 @@ nffs_path_parse_next(struct nffs_path_parser *parser)
     }
 
     if (token_len > NFFS_FILENAME_MAX_LEN) {
-        return NFFS_EINVAL;
+        return FS_EINVAL;
     }
 
     parser->npp_token = parser->npp_path + parser->npp_off;
@@ -92,7 +92,7 @@ nffs_path_find_child(struct nffs_inode_entry *parent,
         }
     }
 
-    return NFFS_ENOENT;
+    return FS_ENOENT;
 }
 
 int
@@ -122,7 +122,7 @@ nffs_path_find(struct nffs_path_parser *parser,
             if (parent == NULL) {
                 /* First directory must be root. */
                 if (parser->npp_token_len != 0) {
-                    return NFFS_ENOENT;
+                    return FS_ENOENT;
                 }
 
                 inode_entry = nffs_root_dir;
@@ -142,7 +142,7 @@ nffs_path_find(struct nffs_path_parser *parser,
         case NFFS_PATH_TOKEN_LEAF:
             if (parent == NULL) {
                 /* First token must be root directory. */
-                return NFFS_ENOENT;
+                return FS_ENOENT;
             }
 
             if (parser->npp_token_len == 0) {
@@ -258,7 +258,7 @@ nffs_path_rename(const char *from, const char *to)
             nffs_hash_id_is_dir(to_inode_entry->nie_hash_entry.nhe_id)) {
 
             /* Cannot clobber one type of file with another. */
-            return NFFS_EINVAL;
+            return FS_EINVAL;
         }
 
         rc = nffs_inode_from_entry(&inode, to_inode_entry);
@@ -272,11 +272,11 @@ nffs_path_rename(const char *from, const char *to)
         }
         break;
 
-    case NFFS_ENOENT:
+    case FS_ENOENT:
         assert(to_parent != NULL);
         if (parser.npp_token_type != NFFS_PATH_TOKEN_LEAF) {
             /* Intermediate directory doesn't exist. */
-            return NFFS_EINVAL;
+            return FS_EINVAL;
         }
         break;
 
@@ -298,9 +298,9 @@ nffs_path_rename(const char *from, const char *to)
  * @param path                  The path of the directory to create.
  *
  * @return                      0 on success;
- *                              NFFS_EEXIST if there is another file or
+ *                              FS_EEXIST if there is another file or
  *                                  directory at the specified path.
- *                              NFFS_ENONT if a required intermediate directory
+ *                              FS_ENONT if a required intermediate directory
  *                                  does not exist.
  */
 int
@@ -314,13 +314,13 @@ nffs_path_new_dir(const char *path, struct nffs_inode_entry **out_inode_entry)
     nffs_path_parser_new(&parser, path);
     rc = nffs_path_find(&parser, &inode_entry, &parent);
     if (rc == 0) {
-        return NFFS_EEXIST;
+        return FS_EEXIST;
     }
-    if (rc != NFFS_ENOENT) {
+    if (rc != FS_ENOENT) {
         return rc;
     }
     if (parser.npp_token_type != NFFS_PATH_TOKEN_LEAF || parent == NULL) {
-        return NFFS_ENOENT;
+        return FS_ENOENT;
     }
 
     rc = nffs_file_new(parent, parser.npp_token, parser.npp_token_len, 1, 

http://git-wip-us.apache.org/repos/asf/incubator-mynewt-larva/blob/7f8fc747/libs/nffs/src/nffs_priv.h
----------------------------------------------------------------------
diff --git a/libs/nffs/src/nffs_priv.h b/libs/nffs/src/nffs_priv.h
index ee778ab..d8d1dd0 100644
--- a/libs/nffs/src/nffs_priv.h
+++ b/libs/nffs/src/nffs_priv.h
@@ -21,6 +21,7 @@
 #include "os/queue.h"
 #include "os/os_mempool.h"
 #include "nffs/nffs.h"
+#include "fs/fs.h"
 
 #define NFFS_HASH_SIZE               256
 

http://git-wip-us.apache.org/repos/asf/incubator-mynewt-larva/blob/7f8fc747/libs/nffs/src/nffs_restore.c
----------------------------------------------------------------------
diff --git a/libs/nffs/src/nffs_restore.c b/libs/nffs/src/nffs_restore.c
index f776717..b94b5fb 100644
--- a/libs/nffs/src/nffs_restore.c
+++ b/libs/nffs/src/nffs_restore.c
@@ -37,7 +37,7 @@ static uint16_t nffs_restore_largest_block_data_len;
  *                                  the chain.
  *
  * @return                      0 if the block chain is OK;
- *                              NFFS_ECORRUPT if corruption is detected;
+ *                              FS_ECORRUPT if corruption is detected;
  *                              nonzero on other error.
  */
 static int
@@ -135,7 +135,7 @@ nffs_restore_migrate_orphan_children(struct nffs_inode_entry *inode_entry)
     u32toa(&buf[strlen(buf)], inode_entry->nie_hash_entry.nhe_id);
 
     rc = nffs_path_new_dir(buf, &lost_found_sub);
-    if (rc != 0 && rc != NFFS_EEXIST) {
+    if (rc != 0 && rc != FS_EEXIST) {
         return rc;
     }
 
@@ -193,7 +193,7 @@ nffs_restore_should_sweep_inode_entry(struct nffs_inode_entry *inode_entry,
     if (nffs_hash_id_is_file(inode_entry->nie_hash_entry.nhe_id)) {
         rc = nffs_restore_validate_block_chain(
                 inode_entry->nie_last_block_entry);
-        if (rc == NFFS_ECORRUPT) {
+        if (rc == FS_ECORRUPT) {
             *out_should_sweep = 1;
             return 0;
         } else if (rc != 0) {
@@ -316,7 +316,7 @@ nffs_restore_dummy_inode(uint32_t id,
 
     inode_entry = nffs_inode_entry_alloc();
     if (inode_entry == NULL) {
-        return NFFS_ENOMEM;
+        return FS_ENOMEM;
     }
     inode_entry->nie_hash_entry.nhe_id = id;
     inode_entry->nie_hash_entry.nhe_flash_loc = NFFS_FLASH_LOC_NONE;
@@ -373,7 +373,7 @@ nffs_restore_inode_gets_replaced(struct nffs_inode_entry *old_inode_entry,
          * happen.
          */
         *out_should_replace = 0;
-        return NFFS_ECORRUPT;
+        return FS_ECORRUPT;
     }
 
     *out_should_replace = 0;
@@ -436,7 +436,7 @@ nffs_restore_inode(const struct nffs_disk_inode *disk_inode, uint8_t area_idx,
     } else {
         inode_entry = nffs_inode_entry_alloc();
         if (inode_entry == NULL) {
-            rc = NFFS_ENOMEM;
+            rc = FS_ENOMEM;
             goto err;
         }
         new_inode = 1;
@@ -525,7 +525,7 @@ nffs_restore_block_gets_replaced(const struct nffs_block *old_block,
         /* This is a duplicate of an previously-read inode.  This should never
          * happen.
          */
-        return NFFS_ECORRUPT;
+        return FS_ECORRUPT;
     }
 
     *out_should_replace = 0;
@@ -585,7 +585,7 @@ nffs_restore_block(const struct nffs_disk_block *disk_block, uint8_t area_idx,
 
     entry = nffs_block_entry_alloc();
     if (entry == NULL) {
-        rc = NFFS_ENOMEM;
+        rc = FS_ENOMEM;
         goto err;
     }
     new_block = 1;
@@ -658,7 +658,7 @@ nffs_restore_object(const struct nffs_disk_object *disk_object)
 
     default:
         assert(0);
-        rc = NFFS_EINVAL;
+        rc = FS_EINVAL;
         break;
     }
 
@@ -701,11 +701,11 @@ nffs_restore_disk_object(int area_idx, uint32_t area_offset,
         break;
 
     case 0xffffffff:
-        rc = NFFS_EEMPTY;
+        rc = FS_EEMPTY;
         break;
 
     default:
-        rc = NFFS_ECORRUPT;
+        rc = FS_ECORRUPT;
         break;
     }
 
@@ -769,13 +769,13 @@ nffs_restore_area_contents(int area_idx)
             area->na_cur += nffs_restore_disk_object_size(&disk_object);
             break;
 
-        case NFFS_ECORRUPT:
+        case FS_ECORRUPT:
             /* Invalid object; keep scanning for a valid magic number. */
             area->na_cur++;
             break;
 
-        case NFFS_EEMPTY:
-        case NFFS_ERANGE:
+        case FS_EEMPTY:
+        case FS_ERANGE:
             /* End of disk encountered; area fully restored. */
             return 0;
 
@@ -806,11 +806,11 @@ nffs_restore_detect_one_area(uint8_t flash_id, uint32_t area_offset,
     rc = hal_flash_read(flash_id, area_offset, out_disk_area,
                         sizeof *out_disk_area);
     if (rc != 0) {
-        return NFFS_EFLASH_ERROR;
+        return FS_HW_ERROR;
     }
 
     if (!nffs_area_magic_is_set(out_disk_area)) {
-        return NFFS_ECORRUPT;
+        return FS_ECORRUPT;
     }
 
     return 0;
@@ -903,7 +903,7 @@ nffs_restore_corrupt_scratch(void)
  *                              terminated with a 0-length area.
  *
  * @return                  0 on success;
- *                          NFFS_ECORRUPT if no valid file system was detected;
+ *                          FS_ECORRUPT if no valid file system was detected;
  *                          other nonzero on error.
  */
 int
@@ -925,7 +925,7 @@ nffs_restore_full(const struct nffs_area_desc *area_descs)
     /* Read each area from flash. */
     for (i = 0; area_descs[i].nad_length != 0; i++) {
         if (i > NFFS_MAX_AREAS) {
-            rc = NFFS_EINVAL;
+            rc = FS_EINVAL;
             goto err;
         }
 
@@ -937,7 +937,7 @@ nffs_restore_full(const struct nffs_area_desc *area_descs)
             use_area = 1;
             break;
 
-        case NFFS_ECORRUPT:
+        case FS_ECORRUPT:
             use_area = 0;
             break;
 
@@ -988,8 +988,8 @@ nffs_restore_full(const struct nffs_area_desc *area_descs)
          */
         rc = nffs_restore_corrupt_scratch();
         if (rc != 0) {
-            if (rc == NFFS_ENOENT) {
-                rc = NFFS_ECORRUPT;
+            if (rc == FS_ENOENT) {
+                rc = FS_ECORRUPT;
             }
             goto err;
         }

http://git-wip-us.apache.org/repos/asf/incubator-mynewt-larva/blob/7f8fc747/libs/nffs/src/nffs_write.c
----------------------------------------------------------------------
diff --git a/libs/nffs/src/nffs_write.c b/libs/nffs/src/nffs_write.c
index 60bca89..3d5325b 100644
--- a/libs/nffs/src/nffs_write.c
+++ b/libs/nffs/src/nffs_write.c
@@ -218,7 +218,7 @@ nffs_write_append(struct nffs_cache_inode *cache_inode, const void *data,
 
     entry = nffs_block_entry_alloc();
     if (entry == NULL) {
-        return NFFS_ENOMEM;
+        return FS_ENOMEM;
     }
 
     inode_entry = cache_inode->nci_inode.ni_inode_entry;
@@ -353,8 +353,8 @@ nffs_write_to_file(struct nffs_file *file, const void *data, int len)
     uint16_t chunk_size;
     int rc;
 
-    if (!(file->nf_access_flags & NFFS_ACCESS_WRITE)) {
-        return NFFS_EACCESS;
+    if (!(file->nf_access_flags & FS_ACCESS_WRITE)) {
+        return FS_EACCESS;
     }
 
     if (len == 0) {
@@ -369,7 +369,7 @@ nffs_write_to_file(struct nffs_file *file, const void *data, int len)
     /* The append flag forces all writes to the end of the file, regardless of
      * seek position.
      */
-    if (file->nf_access_flags & NFFS_ACCESS_APPEND) {
+    if (file->nf_access_flags & FS_ACCESS_APPEND) {
         file->nf_offset = cache_inode->nci_file_size;
     }
 

http://git-wip-us.apache.org/repos/asf/incubator-mynewt-larva/blob/7f8fc747/libs/nffs/src/nffsutil.c
----------------------------------------------------------------------
diff --git a/libs/nffs/src/nffsutil.c b/libs/nffs/src/nffsutil.c
deleted file mode 100644
index 05d0114..0000000
--- a/libs/nffs/src/nffsutil.c
+++ /dev/null
@@ -1,65 +0,0 @@
-/**
- * Copyright (c) 2015 Runtime Inc.
- *
- * Licensed under the Apache License, Version 2.0 (the "License");
- * you may not use this file except in compliance with the License.
- * You may obtain a copy of the License at
- * 
- *   http://www.apache.org/licenses/LICENSE-2.0
- *
- * Unless required by applicable law or agreed to in writing, software
- * distributed under the License is distributed on an "AS IS" BASIS,
- * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
- * See the License for the specific language governing permissions and
- * limitations under the License.
- */
-
-#include "nffs/nffs.h"
-#include "nffs/nffsutil.h"
-
-int
-nffsutil_read_file(const char *path, uint32_t offset, uint32_t len, void *dst,
-                   uint32_t *out_len)
-{
-    struct nffs_file *file;
-    int rc;
-
-    rc = nffs_open(path, NFFS_ACCESS_READ, &file);
-    if (rc != 0) {
-        goto done;
-    }
-
-    rc = nffs_read(file, len, dst, out_len);
-    if (rc != 0) {
-        goto done;
-    }
-
-    rc = 0;
-
-done:
-    nffs_close(file);
-    return rc;
-}
-
-int
-nffsutil_write_file(const char *path, const void *data, uint32_t len)
-{
-    struct nffs_file *file;
-    int rc;
-
-    rc = nffs_open(path, NFFS_ACCESS_WRITE | NFFS_ACCESS_TRUNCATE, &file);
-    if (rc != 0) {
-        goto done;
-    }
-
-    rc = nffs_write(file, data, len);
-    if (rc != 0) {
-        goto done;
-    }
-
-    rc = 0;
-
-done:
-    nffs_close(file);
-    return rc;
-}