summaryrefslogtreecommitdiff
path: root/apps
diff options
context:
space:
mode:
authorGregory Nutt <gnutt@nuttx.org>2013-05-01 08:09:20 -0600
committerGregory Nutt <gnutt@nuttx.org>2013-05-01 08:09:20 -0600
commitd9bd2fca774a5c3499f7b3a258aa1506fdea526f (patch)
tree32d60c5fe512337bbaf5850f9e505ab47c1e5dcd /apps
parentfa71d6461e5b8cc8b3cada0e594c9641e5e21da7 (diff)
downloadpx4-nuttx-d9bd2fca774a5c3499f7b3a258aa1506fdea526f.tar.gz
px4-nuttx-d9bd2fca774a5c3499f7b3a258aa1506fdea526f.tar.bz2
px4-nuttx-d9bd2fca774a5c3499f7b3a258aa1506fdea526f.zip
Add tests for the SMART block driver and file system. From Ken Pettit
Diffstat (limited to 'apps')
-rw-r--r--apps/ChangeLog.txt4
-rw-r--r--apps/examples/Kconfig2
-rw-r--r--apps/examples/Make.defs8
-rw-r--r--apps/examples/Makefile19
-rw-r--r--apps/examples/README.txt30
-rw-r--r--apps/examples/flash_test/.gitignore13
-rw-r--r--apps/examples/flash_test/Kconfig20
-rw-r--r--apps/examples/flash_test/Makefile116
-rw-r--r--apps/examples/flash_test/README.txt18
-rw-r--r--apps/examples/flash_test/flash_test.c307
-rw-r--r--apps/examples/smart_test/.gitignore13
-rw-r--r--apps/examples/smart_test/Kconfig16
-rw-r--r--apps/examples/smart_test/Makefile116
-rw-r--r--apps/examples/smart_test/README.txt17
-rw-r--r--apps/examples/smart_test/smart_test.c373
15 files changed, 1062 insertions, 10 deletions
diff --git a/apps/ChangeLog.txt b/apps/ChangeLog.txt
index ecf71f369..57abd2e6b 100644
--- a/apps/ChangeLog.txt
+++ b/apps/ChangeLog.txt
@@ -541,4 +541,6 @@
* apps/nshlib/nsh_fscmds.c: Add support for the mksmartfs command.
(Ken Petit, 2013-4-30).
* apps/system/flash_eraseall: Add an interface to erase FLASH using a
- flash_eraseall NSH command \ No newline at end of file
+ flash_eraseall NSH command (Ken Pettit, 2013-5-1).
+ * apps/examples/flash_test and apps/examples/smart_test: Add tests of
+ the SMART block driver and file system (Ken Pettit, 2013-5-1).
diff --git a/apps/examples/Kconfig b/apps/examples/Kconfig
index cf70ae53e..b1c7e7793 100644
--- a/apps/examples/Kconfig
+++ b/apps/examples/Kconfig
@@ -47,6 +47,8 @@ source "$APPSDIR/examples/rgmp/Kconfig"
source "$APPSDIR/examples/romfs/Kconfig"
source "$APPSDIR/examples/sendmail/Kconfig"
source "$APPSDIR/examples/serloop/Kconfig"
+source "$APPSDIR/examples/flash_test/Kconfig"
+source "$APPSDIR/examples/smart_test/Kconfig"
source "$APPSDIR/examples/telnetd/Kconfig"
source "$APPSDIR/examples/thttpd/Kconfig"
source "$APPSDIR/examples/tiff/Kconfig"
diff --git a/apps/examples/Make.defs b/apps/examples/Make.defs
index 4026edcbd..eb2b5ed87 100644
--- a/apps/examples/Make.defs
+++ b/apps/examples/Make.defs
@@ -214,6 +214,14 @@ ifeq ($(CONFIG_EXAMPLES_SERLOOP),y)
CONFIGURED_APPS += examples/serloop
endif
+ifeq ($(CONFIG_EXAMPLES_FLASH_TEST),y)
+CONFIGURED_APPS += examples/flash_test
+endif
+
+ifeq ($(CONFIG_EXAMPLES_SMART_TEST),y)
+CONFIGURED_APPS += examples/smart_test
+endif
+
ifeq ($(CONFIG_EXAMPLES_TELNETD),y)
CONFIGURED_APPS += examples/telnetd
endif
diff --git a/apps/examples/Makefile b/apps/examples/Makefile
index 939748075..72a554ed0 100644
--- a/apps/examples/Makefile
+++ b/apps/examples/Makefile
@@ -37,12 +37,13 @@
# Sub-directories
-SUBDIRS = adc buttons can cdcacm composite cxxtest dhcpd discover elf ftpc
-SUBDIRS += ftpd hello helloxx hidkbd igmp json keypadtest lcdrw mm modbus mount
-SUBDIRS += nettest nsh null nx nxconsole nxffs nxflat nxhello nximage
-SUBDIRS += nxlines nxtext ostest pashello pipe poll pwm posix_spawn qencoder
-SUBDIRS += relays rgmp romfs serloop telnetd thttpd tiff touchscreen udp uip
-SUBDIRS += usbserial sendmail usbstorage usbterm watchdog wget wgetjson
+SUBDIRS = adc buttons can cdcacm composite cxxtest dhcpd discover elf
+SUBDIRS += flash_test ftpc ftpd hello helloxx hidkbd igmp json keypadtest
+SUBDIRS += lcdrw mm modbus mount nettest nsh null nx nxconsole nxffs nxflat
+SUBDIRS += nxhello nximage nxlines nxtext ostest pashello pipe poll
+SUBDIRS += posix_spawn pwm qencoder relays rgmp romfs sendmail serloop
+SUBDIRS += smart_test telnetd thttpd tiff touchscreen udp uip usbserial
+SUBDIRS += usbstorage usbterm watchdog wget wgetjson xmlrpc
# Sub-directories that might need context setup. Directories may need
# context setup for a variety of reasons, but the most common is because
@@ -57,9 +58,9 @@ SUBDIRS += usbserial sendmail usbstorage usbterm watchdog wget wgetjson
CNTXTDIRS = pwm
ifeq ($(CONFIG_NSH_BUILTIN_APPS),y)
-CNTXTDIRS += adc can cdcacm composite cxxtest dhcpd discover ftpd hello json
-CNTXTDIRS += keypadtestmodbus nettest nxlines relays qencoder telnetd watchdog
-CNTXTDIRS += wgetjson
+CNTXTDIRS += adc can cdcacm composite cxxtest dhcpd discover flash_test ftpd
+CNTXTDIRS += hello json keypadtestmodbus nettest nxlines relays qencoder
+CNTXTDIRS += smart_test telnetd watchdog wgetjson
endif
ifeq ($(CONFIG_EXAMPLES_HELLOXX_BUILTIN),y)
diff --git a/apps/examples/README.txt b/apps/examples/README.txt
index cd6701e9c..ec9685f4e 100644
--- a/apps/examples/README.txt
+++ b/apps/examples/README.txt
@@ -382,6 +382,23 @@ examples/elf
LDELFFLAGS = -r -e main -T$(TOPDIR)/binfmt/libelf/gnu-elf.ld
+examples/flash_test
+^^^^^^^^^^^^^^^^^^^
+
+ This example performs a SMART flash block device test. This test performs
+ a sector allocate, read, write, free and garbage collection test on a SMART
+ MTD block device.
+
+ * CONFIG_EXAMPLES_FLASH_TEST=y - Enables the FLASH Test
+
+ Dependencies:
+
+ * CONFIG_MTD_SMART=y - SMART block driver support
+ * CONFIG_NSH_BUILTIN_APPS=y - This example can only be built as an NSH
+ command
+ * CONFIG_NUTTX_KERNEL=n - This test uses internal OS interfaces and so
+ is not available in the NUTTX kernel build
+
examples/ftpc
^^^^^^^^^^^^^
@@ -1446,6 +1463,19 @@ examples/serloop
Use C buffered I/O (getchar/putchar) vs. raw console I/O
(read/read).
+examples/smart_test
+^^^^^^^^^^^^^^^^^^^
+
+ Performs a file-based test on a SMART (or any) filesystem. Validates
+ seek, append and seek-with-write operations.
+
+ * CONFIG_EXAMPLES_SMART_TEST=y
+
+ Dependencies:
+
+ * CONFIG_NSH_BUILTIN_APPS=y: This test can be built only as an NSH
+ command
+
examples/telnetd
^^^^^^^^^^^^^^^^
diff --git a/apps/examples/flash_test/.gitignore b/apps/examples/flash_test/.gitignore
new file mode 100644
index 000000000..b3c606091
--- /dev/null
+++ b/apps/examples/flash_test/.gitignore
@@ -0,0 +1,13 @@
+Make.dep
+.depend
+.built
+*.swp
+*.asm
+*.obj
+*.rel
+*.lst
+*.sym
+*.adb
+*.lib
+*.src
+
diff --git a/apps/examples/flash_test/Kconfig b/apps/examples/flash_test/Kconfig
new file mode 100644
index 000000000..49b56dccc
--- /dev/null
+++ b/apps/examples/flash_test/Kconfig
@@ -0,0 +1,20 @@
+#
+# For a description of the syntax of this configuration file,
+# see misc/tools/kconfig-language.txt.
+#
+
+config EXAMPLES_FLASH_TEST
+ bool "SMART FLASH block device test"
+ default n
+ depends on !NUTTX_KERNEL && MTD_SMART && NSH_BUILTIN_APPS
+ ---help---
+ This logic performs a SMART flash block device test. This test
+ performs a sector allocate, read, write, free and garbage collection
+ test on a SMART MTD block device. This test can be built only as an
+ NSH command
+
+ NOTE: This test uses internal OS interfaces and so is not available
+ in the NUTTX kernel build
+
+if EXAMPLES_FLASH_TEST
+endif
diff --git a/apps/examples/flash_test/Makefile b/apps/examples/flash_test/Makefile
new file mode 100644
index 000000000..d8c9e5c74
--- /dev/null
+++ b/apps/examples/flash_test/Makefile
@@ -0,0 +1,116 @@
+############################################################################
+# apps/system/flash_test/Makefile
+#
+# Copyright (C) 2013 Ken Pettit. All rights reserved.
+# Author: Ken Pettit <pettitkd@gmail.com>
+# Greg Nutt
+#
+# Redistribution and use in source and binary forms, with or without
+# modification, are permitted provided that the following conditions
+# are met:
+#
+# 1. Redistributions of source code must retain the above copyright
+# notice, this list of conditions and the following disclaimer.
+# 2. Redistributions in binary form must reproduce the above copyright
+# notice, this list of conditions and the following disclaimer in
+# the documentation and/or other materials provided with the
+# distribution.
+# 3. Neither the name NuttX nor the names of its contributors may be
+# used to endorse or promote products derived from this software
+# without specific prior written permission.
+#
+# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+# "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+# LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+# FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+# COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+# INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+# BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
+# OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
+# AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+# LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+# ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+# POSSIBILITY OF SUCH DAMAGE.
+#
+############################################################################
+
+-include $(TOPDIR)/.config
+-include $(TOPDIR)/Make.defs
+include $(APPDIR)/Make.defs
+
+ifeq ($(WINTOOL),y)
+INCDIROPT = -w
+endif
+
+# SMART FLASH block device test
+
+APPNAME = flash_test
+PRIORITY = SCHED_PRIORITY_DEFAULT
+STACKSIZE = 2048
+
+ASRCS =
+CSRCS = flash_test.c
+
+AOBJS = $(ASRCS:.S=$(OBJEXT))
+COBJS = $(CSRCS:.c=$(OBJEXT))
+
+SRCS = $(ASRCS) $(CSRCS)
+OBJS = $(AOBJS) $(COBJS)
+
+ifeq ($(CONFIG_WINDOWS_NATIVE),y)
+ BIN = ..\..\libapps$(LIBEXT)
+else
+ifeq ($(WINTOOL),y)
+ BIN = ..\\..\\libapps$(LIBEXT)
+else
+ BIN = ../../libapps$(LIBEXT)
+endif
+endif
+
+ROOTDEPPATH = --dep-path .
+
+# Common build
+
+VPATH =
+
+all: .built
+.PHONY: context depend clean distclean
+
+$(AOBJS): %$(OBJEXT): %.S
+ $(call ASSEMBLE, $<, $@)
+
+$(COBJS): %$(OBJEXT): %.c
+ $(call COMPILE, $<, $@)
+
+.built: $(OBJS)
+ $(call ARCHIVE, $(BIN), $(OBJS))
+ $(Q) touch .built
+
+# Register application
+
+ifeq ($(CONFIG_NSH_BUILTIN_APPS),y)
+$(BUILTIN_REGISTRY)$(DELIM)$(APPNAME)_main.bdat: $(DEPCONFIG) Makefile
+ $(call REGISTER,$(APPNAME),$(PRIORITY),$(STACKSIZE),$(APPNAME)_main)
+
+context: $(BUILTIN_REGISTRY)$(DELIM)$(APPNAME)_main.bdat
+else
+context:
+endif
+
+# Create dependencies
+
+.depend: Makefile $(SRCS)
+ $(Q) $(MKDEP) $(ROOTDEPPATH) "$(CC)" -- $(CFLAGS) -- $(SRCS) >Make.dep
+ $(Q) touch $@
+
+depend: .depend
+
+clean:
+ $(call DELFILE, .built)
+ $(call CLEAN)
+
+distclean: clean
+ $(call DELFILE, Make.dep)
+ $(call DELFILE, .depend)
+
+-include Make.dep
diff --git a/apps/examples/flash_test/README.txt b/apps/examples/flash_test/README.txt
new file mode 100644
index 000000000..60fcc4ebb
--- /dev/null
+++ b/apps/examples/flash_test/README.txt
@@ -0,0 +1,18 @@
+
+Install Program
+===============
+
+ Source: NuttX
+ Author: Ken Pettit
+ Date: April 24, 2013
+
+This application performs a SMART flash block device test. This test performs a sector allocate, read, write, free and garbage collection test on a SMART MTD block device. This test can be built only as an NSH command
+
+NOTE: This test uses internal OS interfaces and so is not available in the NUTTX kernel build
+
+Usage:
+ flash_test mtdblock_device
+
+Additional options:
+
+ --force to replace existing installation
diff --git a/apps/examples/flash_test/flash_test.c b/apps/examples/flash_test/flash_test.c
new file mode 100644
index 000000000..105950557
--- /dev/null
+++ b/apps/examples/flash_test/flash_test.c
@@ -0,0 +1,307 @@
+/****************************************************************************
+ * apps/system/flash_test/flash_test.c
+ *
+ * Copyright (C) 2013 Ken Pettit. All rights reserved.
+ * Author: Ken Pettit <pettitkd@gmail.com>
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions
+ * are met:
+ *
+ * 1. Redistributions of source code must retain the above copyright
+ * notice, this list of conditions and the following disclaimer.
+ * 2. Redistributions in binary form must reproduce the above copyright
+ * notice, this list of conditions and the following disclaimer in
+ * the documentation and/or other materials provided with the
+ * distribution.
+ * 3. Neither the name NuttX nor the names of its contributors may be
+ * used to endorse or promote products derived from this software
+ * without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+ * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+ * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+ * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+ * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+ * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+ * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
+ * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
+ * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+ * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+ * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+ * POSSIBILITY OF SUCH DAMAGE.
+ *
+ ****************************************************************************/
+
+/****************************************************************************
+ * Included Files
+ ****************************************************************************/
+
+#include <nuttx/config.h>
+#include <nuttx/progmem.h>
+#include <sys/stat.h>
+
+#include <unistd.h>
+#include <stdio.h>
+#include <stdlib.h>
+#include <string.h>
+#include <nuttx/mtd.h>
+#include <nuttx/smart.h>
+#include <nuttx/fs/ioctl.h>
+
+/****************************************************************************
+ * Pre-processor Definitions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private data
+ ****************************************************************************/
+
+/****************************************************************************
+ * Public Functions
+ ****************************************************************************/
+
+int flash_test_main(int argc, char *argv[])
+{
+ struct inode* inode;
+ int ret;
+ int x;
+ int logsector;
+ uint16_t seq;
+ struct smart_format_s fmt;
+ uint16_t *sectors;
+ uint16_t *seqs;
+ char *buffer;
+ struct smart_read_write_s readwrite;
+
+ /* Argument given? */
+
+ if (argc < 2)
+ {
+ fprintf(stderr, "usage: flash_test flash_block_device\n");
+ return -1;
+ }
+
+ /* Find the inode of the block driver indentified by 'source' */
+
+ ret = open_blockdriver(argv[1], 0, &inode);
+ if (ret < 0)
+ {
+ fprintf(stderr, "Failed to open %s\n", argv[1]);
+ goto errout;
+ }
+
+ /* Get the low-level format from the device. */
+
+ ret = inode->u.i_bops->ioctl(inode, BIOC_GETFORMAT, (unsigned long) &fmt);
+ if (ret != OK)
+ {
+ fprintf(stderr, "Device is not a SMART block device\n");
+ goto errout_with_driver;
+ }
+
+ /* Test if the device is formatted. If not, then we must do a
+ * low-level format first */
+
+ if (!(fmt.flags & SMART_FMT_ISFORMATTED))
+ {
+ /* Perform a low-level format */
+
+ ret = inode->u.i_bops->ioctl(inode, BIOC_LLFORMAT, 0);
+ ret = inode->u.i_bops->ioctl(inode, BIOC_GETFORMAT, (unsigned long) &fmt);
+ }
+
+ if (!(fmt.flags & SMART_FMT_ISFORMATTED))
+ {
+ fprintf(stderr, "Unable to get device format\n");
+ goto errout_with_driver;
+ }
+
+ /* Report the device structure */
+
+ printf("FLASH Test on device with:\n");
+ printf(" Sector size: %10d\n", fmt.sectorsize);
+ printf(" Sector count: %10d\n", fmt.nsectors);
+ printf(" Avail bytes: %10d\n", fmt.availbytes);
+ printf(" Total size: %10d\n", fmt.sectorsize * fmt.nsectors);
+
+ /* Allocate buffers to use */
+
+ buffer = (char *) malloc(fmt.availbytes);
+ if (buffer == NULL)
+ {
+ fprintf(stderr, "Error allocating buffer\n");
+ goto errout_with_driver;
+ }
+
+ seqs = (uint16_t *) malloc(fmt.nsectors << 1);
+ if (seqs == NULL)
+ {
+ (void) free(buffer);
+ fprintf(stderr, "Error allocating seqs buffer\n");
+ goto errout_with_driver;
+ }
+
+ sectors = (uint16_t *) malloc(fmt.nsectors << 1);
+ if (sectors == NULL)
+ {
+ (void) free(seqs);
+ (void) free(buffer);
+ fprintf(stderr, "Error allocating sectors buffer\n");
+ goto errout_with_driver;
+ }
+
+ /* Write a bunch of data to the flash */
+
+ printf("\nAllocating and writing to logical sectors\n");
+
+ seq = 0;
+ for (x = 0; x < fmt.nsectors >> 1; x++)
+ {
+ /* Allocate a new sector */
+
+ logsector = inode->u.i_bops->ioctl(inode, BIOC_ALLOCSECT,
+ (unsigned long) -1);
+ if (logsector < 0)
+ {
+ fprintf(stderr, "Error allocating sector: %d\n", logsector);
+ goto errout_with_driver;
+ }
+
+ /* Save the sector in our array */
+
+ sectors[x] = (uint16_t) logsector;
+ seqs[x] = seq++;
+
+ /* Now write some data to the sector */
+
+ sprintf(buffer, "Logical sector %d sequence %d\n",
+ sectors[x], seqs[x]);
+
+ readwrite.logsector = sectors[x];
+ readwrite.offset = 0;
+ readwrite.count = strlen(buffer) + 1;
+ readwrite.buffer = (uint8_t *) buffer;
+ ret = inode->u.i_bops->ioctl(inode, BIOC_WRITESECT, (unsigned long)
+ &readwrite);
+
+ /* Print the logical sector number */
+
+ printf("\r%d ", sectors[x]);
+ }
+
+ /* Now read the data back to validate everything was written and can
+ * be read. */
+
+ printf("\nDoing read verify test\n");
+ for (x = 0; x < fmt.nsectors >> 1; x++)
+ {
+ /* Read from the logical sector */
+
+ readwrite.logsector = sectors[x];
+ readwrite.offset = 0;
+ readwrite.count = fmt.availbytes;
+ readwrite.buffer = (uint8_t *) buffer;
+ ret = inode->u.i_bops->ioctl(inode, BIOC_READSECT, (unsigned long)
+ &readwrite);
+
+ if (ret != fmt.availbytes)
+ {
+ fprintf(stderr, "Error reading sector %d\n", sectors[x]);
+ goto errout_with_buffers;
+ }
+
+ /* Generate compare string and do the comapre */
+
+ printf("\r%d ", sectors[x]);
+
+ sprintf(&buffer[100], "Logical sector %d sequence %d\n",
+ sectors[x], seqs[x]);
+
+ if (strcmp(buffer, &buffer[100]) != 0)
+ {
+ printf("Sector %d read verify failed\n", sectors[x]);
+ }
+ }
+
+ printf("\nPeforming sector re-write\n");
+
+ /* Overwrite data on the sectors to cause relocation */
+
+ for (x = 0; x < fmt.nsectors >> 1; x++)
+ {
+ /* Save a new sequence number for the sector */
+
+ seqs[x] = seq++;
+
+ /* Now write over the sector data with new data, causing a relocation. */
+
+ sprintf(buffer, "Logical sector %d sequence %d\n", sectors[x], seqs[x]);
+ readwrite.logsector = sectors[x];
+ readwrite.offset = 0;
+ readwrite.count = strlen(buffer) + 1;
+ readwrite.buffer = (uint8_t *) buffer;
+ ret = inode->u.i_bops->ioctl(inode, BIOC_WRITESECT, (unsigned long)
+ &readwrite);
+
+ /* Print the logical sector number */
+
+ printf("\r%d ", sectors[x]);
+ }
+
+ /* Now append data to empty region of sector */
+
+ printf("\nAppending data to empty region of sector\n");
+
+ for (x = 0; x < fmt.nsectors >> 1; x++)
+ {
+ /* Save a new sequence number for the sector */
+
+ seqs[x] = seq++;
+
+ /* Now write over the sector data with new data, causing a relocation. */
+
+ sprintf(buffer, "Appended data in sector %d\n", sectors[x]);
+ readwrite.logsector = sectors[x];
+ readwrite.offset = 64;
+ readwrite.count = strlen(buffer) + 1;
+ readwrite.buffer = (uint8_t *) buffer;
+ ret = inode->u.i_bops->ioctl(inode, BIOC_WRITESECT, (unsigned long)
+ &readwrite);
+
+ /* Print the logical sector number */
+
+ printf("\r%d ", sectors[x]);
+ }
+
+ printf("\nDone\n");
+
+ /* Free all the allocated sectors */
+
+ for (x = 0; x < fmt.nsectors >> 1; x++)
+ {
+ /* Only free the sector if it is still valid */
+
+ if (sectors[x] != 0xFFFF)
+ {
+ ret = inode->u.i_bops->ioctl(inode, BIOC_FREESECT, (unsigned long)
+ sectors[x]);
+ }
+ }
+
+errout_with_buffers:
+ /* Free the allocated buffers */
+
+ (void) free(seqs);
+ (void) free(sectors);
+ (void) free(buffer);
+
+errout_with_driver:
+ /* Now close the block device and exit */
+
+ (void)close_blockdriver(inode);
+
+errout:
+
+ return 0;
+}
diff --git a/apps/examples/smart_test/.gitignore b/apps/examples/smart_test/.gitignore
new file mode 100644
index 000000000..b3c606091
--- /dev/null
+++ b/apps/examples/smart_test/.gitignore
@@ -0,0 +1,13 @@
+Make.dep
+.depend
+.built
+*.swp
+*.asm
+*.obj
+*.rel
+*.lst
+*.sym
+*.adb
+*.lib
+*.src
+
diff --git a/apps/examples/smart_test/Kconfig b/apps/examples/smart_test/Kconfig
new file mode 100644
index 000000000..1fa45493e
--- /dev/null
+++ b/apps/examples/smart_test/Kconfig
@@ -0,0 +1,16 @@
+#
+# For a description of the syntax of this configuration file,
+# see misc/tools/kconfig-language.txt.
+#
+
+config EXAMPLES_SMART_TEST
+ bool "SMART filesystem test tool"
+ default n
+ depends on NSH_BUILTIN_APPS
+ ---help---
+ Performs a file-based test on a SMART (or any) filesystem. Validates
+ seek, append and seek-with-write operations. This test can be built
+ only as an NSH command
+
+if EXAMPLES_SMART_TEST
+endif
diff --git a/apps/examples/smart_test/Makefile b/apps/examples/smart_test/Makefile
new file mode 100644
index 000000000..5864b1cdc
--- /dev/null
+++ b/apps/examples/smart_test/Makefile
@@ -0,0 +1,116 @@
+############################################################################
+# apps/system/smart_test/Makefile
+#
+# Copyright (C) 2013 Ken Pettit. All rights reserved.
+# Author: Ken Pettit <pettitkd@gmail.com>
+# Greg Nutt
+#
+# Redistribution and use in source and binary forms, with or without
+# modification, are permitted provided that the following conditions
+# are met:
+#
+# 1. Redistributions of source code must retain the above copyright
+# notice, this list of conditions and the following disclaimer.
+# 2. Redistributions in binary form must reproduce the above copyright
+# notice, this list of conditions and the following disclaimer in
+# the documentation and/or other materials provided with the
+# distribution.
+# 3. Neither the name NuttX nor the names of its contributors may be
+# used to endorse or promote products derived from this software
+# without specific prior written permission.
+#
+# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+# "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+# LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+# FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+# COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+# INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+# BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
+# OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
+# AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+# LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+# ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+# POSSIBILITY OF SUCH DAMAGE.
+#
+############################################################################
+
+-include $(TOPDIR)/.config
+-include $(TOPDIR)/Make.defs
+include $(APPDIR)/Make.defs
+
+ifeq ($(WINTOOL),y)
+INCDIROPT = -w
+endif
+
+# SMART filesystem test tool
+
+APPNAME = smart_test
+PRIORITY = SCHED_PRIORITY_DEFAULT
+STACKSIZE = 4096
+
+ASRCS =
+CSRCS = smart_test.c
+
+AOBJS = $(ASRCS:.S=$(OBJEXT))
+COBJS = $(CSRCS:.c=$(OBJEXT))
+
+SRCS = $(ASRCS) $(CSRCS)
+OBJS = $(AOBJS) $(COBJS)
+
+ifeq ($(CONFIG_WINDOWS_NATIVE),y)
+ BIN = ..\..\libapps$(LIBEXT)
+else
+ifeq ($(WINTOOL),y)
+ BIN = ..\\..\\libapps$(LIBEXT)
+else
+ BIN = ../../libapps$(LIBEXT)
+endif
+endif
+
+ROOTDEPPATH = --dep-path .
+
+# Common build
+
+VPATH =
+
+all: .built
+.PHONY: context depend clean distclean
+
+$(AOBJS): %$(OBJEXT): %.S
+ $(call ASSEMBLE, $<, $@)
+
+$(COBJS): %$(OBJEXT): %.c
+ $(call COMPILE, $<, $@)
+
+.built: $(OBJS)
+ $(call ARCHIVE, $(BIN), $(OBJS))
+ $(Q) touch .built
+
+# Register application
+
+ifeq ($(CONFIG_NSH_BUILTIN_APPS),y)
+$(BUILTIN_REGISTRY)$(DELIM)$(APPNAME)_main.bdat: $(DEPCONFIG) Makefile
+ $(call REGISTER,$(APPNAME),$(PRIORITY),$(STACKSIZE),$(APPNAME)_main)
+
+context: $(BUILTIN_REGISTRY)$(DELIM)$(APPNAME)_main.bdat
+else
+context:
+endif
+
+# Create dependencies
+
+.depend: Makefile $(SRCS)
+ $(Q) $(MKDEP) $(ROOTDEPPATH) "$(CC)" -- $(CFLAGS) -- $(SRCS) >Make.dep
+ $(Q) touch $@
+
+depend: .depend
+
+clean:
+ $(call DELFILE, .built)
+ $(call CLEAN)
+
+distclean: clean
+ $(call DELFILE, Make.dep)
+ $(call DELFILE, .depend)
+
+-include Make.dep
diff --git a/apps/examples/smart_test/README.txt b/apps/examples/smart_test/README.txt
new file mode 100644
index 000000000..4102df9e7
--- /dev/null
+++ b/apps/examples/smart_test/README.txt
@@ -0,0 +1,17 @@
+
+Install Program
+===============
+
+ Source: NuttX
+ Author: Ken Pettit
+ Date: April 24, 2013
+
+Performs a file-based test on a SMART (or any) filesystem. Validates seek,
+append and seek-with-write operations.
+
+Usage:
+ flash_test mtdblock_device
+
+Additional options:
+
+ --force to replace existing installation
diff --git a/apps/examples/smart_test/smart_test.c b/apps/examples/smart_test/smart_test.c
new file mode 100644
index 000000000..3f8e42449
--- /dev/null
+++ b/apps/examples/smart_test/smart_test.c
@@ -0,0 +1,373 @@
+/****************************************************************************
+ * apps/system/smart_test/smart_test.c
+ *
+ * Copyright (C) 2013 Ken Pettit. All rights reserved.
+ * Author: Ken Pettit <pettitkd@gmail.com>
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions
+ * are met:
+ *
+ * 1. Redistributions of source code must retain the above copyright
+ * notice, this list of conditions and the following disclaimer.
+ * 2. Redistributions in binary form must reproduce the above copyright
+ * notice, this list of conditions and the following disclaimer in
+ * the documentation and/or other materials provided with the
+ * distribution.
+ * 3. Neither the name NuttX nor the names of its contributors may be
+ * used to endorse or promote products derived from this software
+ * without specific prior written permission.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+ * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+ * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+ * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+ * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+ * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+ * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
+ * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
+ * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+ * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+ * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+ * POSSIBILITY OF SUCH DAMAGE.
+ *
+ ****************************************************************************/
+
+/****************************************************************************
+ * Included Files
+ ****************************************************************************/
+
+#include <nuttx/config.h>
+#include <nuttx/progmem.h>
+#include <sys/stat.h>
+
+#include <unistd.h>
+#include <stdio.h>
+#include <stdlib.h>
+#include <string.h>
+#include <fcntl.h>
+#include <errno.h>
+
+/****************************************************************************
+ * Pre-processor Definitions
+ ****************************************************************************/
+
+#define SMART_TEST_LINE_COUNT 2000
+#define SMART_TEST_SEEK_WRITE_COUNT 12000
+
+/****************************************************************************
+ * Private data
+ ****************************************************************************/
+
+static int g_linePos[SMART_TEST_LINE_COUNT];
+static int g_lineLen[SMART_TEST_LINE_COUNT];
+
+/****************************************************************************
+ * Private Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Name: smart_create_test_file
+ *
+ * Description: Creates the test file with test data that we will use
+ * to conduct the test.
+ *
+ ****************************************************************************/
+
+static int smart_create_test_file(char *filename)
+{
+ FILE* fd;
+ int x;
+ char string[80];
+
+ /* Try to open the file */
+
+ printf("Creating file %s for write mode\n", filename);
+
+ fd = fopen(filename, "w+");
+
+ if (fd == NULL)
+ {
+ printf("Unable to create file %s\n", filename);
+ return -ENOENT;
+ }
+
+ /* Write data to the file. The data consists of a bunch of
+ * lines, each with a line number and the offset within the
+ * file where that file starts.
+ */
+
+ printf("Writing test data. %d lines to write\n", SMART_TEST_LINE_COUNT);
+ for (x = 0; x < SMART_TEST_LINE_COUNT; x++)
+ {
+ g_linePos[x] = ftell(fd);
+
+ sprintf(string, "This is line %d at offset %d\n", x, g_linePos[x]);
+ g_lineLen[x] = strlen(string);
+ fprintf(fd, "%s", string);
+
+ printf("\r%d", x);
+ fflush(stdout);
+ }
+
+ /* Close the file */
+
+ printf("\r\nDone.\n");
+
+ fclose(fd);
+
+ return OK;
+}
+
+/****************************************************************************
+ * Name: smart_seek_test
+ *
+ * Description: Conducts a seek test on the file.
+ *
+ ****************************************************************************/
+
+static int smart_seek_test(char *filename)
+{
+ FILE* fd;
+ int x;
+ int index;
+ char readstring[80];
+ char cmpstring[80];
+
+ printf("Performing 2000 random seek tests\n");
+
+ fd = fopen(filename, "r");
+ if (fd == NULL)
+ {
+ printf("Unable to open file %s\n", filename);
+ return -ENOENT;
+ }
+
+ srand(23);
+ for (x = 0; x < 2000; x++)
+ {
+ /* Get random line to seek to */
+
+ index = rand();
+ while (index >= SMART_TEST_LINE_COUNT)
+ {
+ index -= SMART_TEST_LINE_COUNT;
+ }
+
+ fseek(fd, g_linePos[index], SEEK_SET);
+ fread(readstring, 1, g_lineLen[index], fd);
+ readstring[g_lineLen[index]] = '\0';
+
+ sprintf(cmpstring, "This is line %d at offset %d\n",
+ index, g_linePos[index]);
+
+ if (strcmp(readstring, cmpstring) != 0)
+ {
+ printf("\nSeek error on line %d\n", index);
+ }
+
+ printf("\r%d", x);
+ fflush(stdout);
+ }
+
+ fclose(fd);
+
+ return OK;
+}
+
+/****************************************************************************
+ * Name: smart_append_test
+ *
+ * Description: Conducts an append test on the file.
+ *
+ ****************************************************************************/
+
+static int smart_append_test(char *filename)
+{
+ FILE* fd;
+ int pos;
+ char readstring[80];
+
+ fd = fopen(filename, "a+");
+ if (fd == NULL)
+ {
+ printf("Unable to open file %s\n", filename);
+ return -ENOENT;
+ }
+
+ /* Now write some data to the end of the file */
+
+ fprintf(fd, "This is a test of the append.\n");
+ pos = ftell(fd);
+
+ /* Now seek to the end of the file and ensure that is where
+ * pos is.
+ */
+
+ fseek(fd, 0, SEEK_END);
+ if (ftell(fd) != pos)
+ {
+ printf("Error opening for append ... data not at EOF\n");
+ }
+
+ /* Now seek to that position and read the data back */
+
+ fseek(fd, 30, SEEK_END);
+ fread(readstring, 1, 30, fd);
+ readstring[30] = '\0';
+ if (strcmp(readstring, "This is a test of the append.\n") != 0)
+ {
+ printf("Append test failed\n");
+ }
+ else
+ {
+ printf("Append test passed\n");
+ }
+
+ fclose(fd);
+
+ return OK;
+}
+
+/****************************************************************************
+ * Name: smart_seek_with_write_test
+ *
+ * Description: Conducts an append test on the file.
+ *
+ ****************************************************************************/
+
+static int smart_seek_with_write_test(char *filename)
+{
+ FILE* fd;
+ int x;
+ int index;
+ char temp;
+ char readstring[80];
+ char cmpstring[80];
+ int c, s1, s2, len;
+
+ printf("Performing %d random seek with write tests\n",
+ SMART_TEST_SEEK_WRITE_COUNT);
+
+ fd = fopen(filename, "r+");
+ if (fd == NULL)
+ {
+ printf("Unable to open file %s\n", filename);
+ return -ENOENT;
+ }
+
+ index = 0;
+ for (x = 0; x < SMART_TEST_SEEK_WRITE_COUNT; x++)
+ {
+#if 0
+ /* Get a random value */
+
+ index = rand();
+ while (index >= SMART_TEST_LINE_COUNT)
+ {
+ index -= SMART_TEST_LINE_COUNT;
+ }
+#endif
+ /* Read the data into the buffer */
+
+ fseek(fd, g_linePos[index], SEEK_SET);
+ fread(readstring, 1, g_lineLen[index], fd);
+ readstring[g_lineLen[index]] = '\0';
+
+ /* Scramble the data in the line */
+
+ len = strlen(readstring);
+ for (c = 0; c < 100; c++)
+ {
+ s1 = rand() % len;
+ s2 = rand() % len;
+
+ temp = readstring[s1];
+ readstring[s1] = readstring[s2];
+ readstring[s2] = temp;
+ }
+
+ /* Now write the data back to the file */
+
+ fseek(fd, g_linePos[index], SEEK_SET);
+ fwrite(readstring, 1, g_lineLen[index], fd);
+ fflush(fd);
+
+ /* Now read the data back and compare it */
+
+ fseek(fd, g_linePos[index], SEEK_SET);
+ fread(cmpstring, 1, g_lineLen[index], fd);
+ cmpstring[g_lineLen[index]] = '\0';
+
+ if (strcmp(readstring, cmpstring) != 0)
+ {
+ printf("\nCompare failure on line %d\n", index);
+ break;
+ }
+
+ printf("\r%d", x);
+ fflush(stdout);
+
+ /* On to next line */
+
+ if (++index >= SMART_TEST_LINE_COUNT)
+ {
+ index = 0;
+ }
+ }
+
+ printf("\n");
+
+ fclose(fd);
+
+ return OK;
+}
+
+/****************************************************************************
+ * Public Functions
+ ****************************************************************************/
+
+int smart_test_main(int argc, char *argv[])
+{
+ int ret;
+
+ /* Argument given? */
+
+ if (argc < 2)
+ {
+ fprintf(stderr, "usage: smart_test smart_mounted_filename\n");
+ return -1;
+ }
+
+ /* Create a test file */
+
+ if ((ret = smart_create_test_file(argv[1])) < 0)
+ {
+ return ret;
+ }
+
+ /* Conduct a seek test */
+
+ if ((ret = smart_seek_test(argv[1])) < 0)
+ {
+ return ret;
+ }
+
+ /* Conduct an append test */
+
+ if ((ret = smart_append_test(argv[1])) < 0)
+ {
+ return ret;
+ }
+
+ /* Conduct a seek with write test */
+
+ if ((ret = smart_seek_with_write_test(argv[1])) < 0)
+ {
+ return ret;
+ }
+
+ /* Delete the file */
+
+ return 0;
+}