summaryrefslogtreecommitdiff
path: root/nuttx/configs/olimex-lpc1766stk
diff options
context:
space:
mode:
authorpatacongo <patacongo@42af7a65-404d-4744-a932-0658087f49c3>2011-03-20 18:18:19 +0000
committerpatacongo <patacongo@42af7a65-404d-4744-a932-0658087f49c3>2011-03-20 18:18:19 +0000
commiteafaeb9398216dacb92de69683ccdda6007efb1d (patch)
treee513e4fd791670d9b74d33821682d4059ed73098 /nuttx/configs/olimex-lpc1766stk
parentf68c474e8ae9cfa5c9124a6eb92ec06fe2bf40a1 (diff)
downloadpx4-nuttx-eafaeb9398216dacb92de69683ccdda6007efb1d.tar.gz
px4-nuttx-eafaeb9398216dacb92de69683ccdda6007efb1d.tar.bz2
px4-nuttx-eafaeb9398216dacb92de69683ccdda6007efb1d.zip
Move nuttx/examples to apps/examples
git-svn-id: svn://svn.code.sf.net/p/nuttx/code/trunk@3405 42af7a65-404d-4744-a932-0658087f49c3
Diffstat (limited to 'nuttx/configs/olimex-lpc1766stk')
-rw-r--r--nuttx/configs/olimex-lpc1766stk/hidkbd/appconfig39
-rwxr-xr-xnuttx/configs/olimex-lpc1766stk/hidkbd/defconfig2
-rw-r--r--nuttx/configs/olimex-lpc1766stk/nettest/appconfig81
-rwxr-xr-xnuttx/configs/olimex-lpc1766stk/nettest/defconfig2
-rw-r--r--nuttx/configs/olimex-lpc1766stk/nsh/appconfig102
-rwxr-xr-xnuttx/configs/olimex-lpc1766stk/nsh/defconfig2
-rw-r--r--nuttx/configs/olimex-lpc1766stk/nx/appconfig39
-rwxr-xr-xnuttx/configs/olimex-lpc1766stk/nx/defconfig2
-rw-r--r--nuttx/configs/olimex-lpc1766stk/ostest/appconfig39
-rwxr-xr-xnuttx/configs/olimex-lpc1766stk/ostest/defconfig2
-rw-r--r--nuttx/configs/olimex-lpc1766stk/slip-httpd/appconfig83
-rwxr-xr-xnuttx/configs/olimex-lpc1766stk/slip-httpd/defconfig2
-rw-r--r--nuttx/configs/olimex-lpc1766stk/thttpd/appconfig83
-rwxr-xr-xnuttx/configs/olimex-lpc1766stk/thttpd/defconfig2
-rw-r--r--nuttx/configs/olimex-lpc1766stk/usbserial/appconfig39
-rwxr-xr-xnuttx/configs/olimex-lpc1766stk/usbserial/defconfig2
-rw-r--r--nuttx/configs/olimex-lpc1766stk/usbstorage/appconfig39
-rwxr-xr-xnuttx/configs/olimex-lpc1766stk/usbstorage/defconfig2
-rw-r--r--nuttx/configs/olimex-lpc1766stk/wlan/appconfig39
-rwxr-xr-xnuttx/configs/olimex-lpc1766stk/wlan/defconfig2
20 files changed, 429 insertions, 174 deletions
diff --git a/nuttx/configs/olimex-lpc1766stk/hidkbd/appconfig b/nuttx/configs/olimex-lpc1766stk/hidkbd/appconfig
new file mode 100644
index 000000000..861d75654
--- /dev/null
+++ b/nuttx/configs/olimex-lpc1766stk/hidkbd/appconfig
@@ -0,0 +1,39 @@
+############################################################################
+# configs/olimex-lpc1766stk/hidkbd/appconfig
+#
+# Copyright (C) 2011 Gregory Nutt. All rights reserved.
+# Author: Gregory Nutt <spudmonkey@racsa.co.cr>
+#
+# Redistribution and use in source and binary forms, with or without
+# modification, are permitted provided that the following conditions
+# are met:
+#
+# 1. Redistributions of source code must retain the above copyright
+# notice, this list of conditions and the following disclaimer.
+# 2. Redistributions in binary form must reproduce the above copyright
+# notice, this list of conditions and the following disclaimer in
+# the documentation and/or other materials provided with the
+# distribution.
+# 3. Neither the name NuttX nor the names of its contributors may be
+# used to endorse or promote products derived from this software
+# without specific prior written permission.
+#
+# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+# "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+# LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+# FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+# COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+# INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+# BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
+# OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
+# AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+# LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+# ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+# POSSIBILITY OF SUCH DAMAGE.
+#
+############################################################################
+
+# Path to example in apps/examples containing the user_start entry point
+
+CONFIGURED_APPS += examples/hidkbd=.built_always
+
diff --git a/nuttx/configs/olimex-lpc1766stk/hidkbd/defconfig b/nuttx/configs/olimex-lpc1766stk/hidkbd/defconfig
index e3267eafe..78f50af03 100755
--- a/nuttx/configs/olimex-lpc1766stk/hidkbd/defconfig
+++ b/nuttx/configs/olimex-lpc1766stk/hidkbd/defconfig
@@ -326,7 +326,7 @@ CONFIG_HAVE_LIBM=n
# CONFIG_SIG_SIGWORK - The signal number that will be used to wake-up
# the worker thread. Default: 4
#
-CONFIG_APP_DIR=examples/hidkbd
+#CONFIG_APP_DIR=
CONFIG_DEBUG=n
CONFIG_DEBUG_VERBOSE=n
CONFIG_DEBUG_SYMBOLS=n
diff --git a/nuttx/configs/olimex-lpc1766stk/nettest/appconfig b/nuttx/configs/olimex-lpc1766stk/nettest/appconfig
index 8fb8f8bcf..3c6bb4729 100644
--- a/nuttx/configs/olimex-lpc1766stk/nettest/appconfig
+++ b/nuttx/configs/olimex-lpc1766stk/nettest/appconfig
@@ -1,38 +1,43 @@
-############################################################################
-# olimex-lpc1766stk/nettest/appconfig
-#
-# Copyright (C) 2011 Gregory Nutt. All rights reserved.
-# Author: Gregory Nutt <spudmonkey@racsa.co.cr>
-#
-# Redistribution and use in source and binary forms, with or without
-# modification, are permitted provided that the following conditions
-# are met:
-#
-# 1. Redistributions of source code must retain the above copyright
-# notice, this list of conditions and the following disclaimer.
-# 2. Redistributions in binary form must reproduce the above copyright
-# notice, this list of conditions and the following disclaimer in
-# the documentation and/or other materials provided with the
-# distribution.
-# 3. Neither the name NuttX nor the names of its contributors may be
-# used to endorse or promote products derived from this software
-# without specific prior written permission.
-#
-# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
-# "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
-# LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
-# FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
-# COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
-# INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
-# BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
-# OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
-# AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
-# LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
-# ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
-# POSSIBILITY OF SUCH DAMAGE.
-#
-############################################################################
-
-# Networking support
-
-CONFIGURED_APPS += netutils/uiplib=.built_always
+############################################################################
+# configs/olimex-lpc1766stk/nettest/appconfig
+#
+# Copyright (C) 2011 Gregory Nutt. All rights reserved.
+# Author: Gregory Nutt <spudmonkey@racsa.co.cr>
+#
+# Redistribution and use in source and binary forms, with or without
+# modification, are permitted provided that the following conditions
+# are met:
+#
+# 1. Redistributions of source code must retain the above copyright
+# notice, this list of conditions and the following disclaimer.
+# 2. Redistributions in binary form must reproduce the above copyright
+# notice, this list of conditions and the following disclaimer in
+# the documentation and/or other materials provided with the
+# distribution.
+# 3. Neither the name NuttX nor the names of its contributors may be
+# used to endorse or promote products derived from this software
+# without specific prior written permission.
+#
+# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+# "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+# LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+# FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+# COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+# INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+# BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
+# OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
+# AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+# LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+# ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+# POSSIBILITY OF SUCH DAMAGE.
+#
+############################################################################
+
+# Path to example in apps/examples containing the user_start entry point
+
+CONFIGURED_APPS += examples/nettest=.built_always
+
+
+# Networking support
+
+CONFIGURED_APPS += netutils/uiplib=.built_always
diff --git a/nuttx/configs/olimex-lpc1766stk/nettest/defconfig b/nuttx/configs/olimex-lpc1766stk/nettest/defconfig
index 0c2c1b0a6..20153e310 100755
--- a/nuttx/configs/olimex-lpc1766stk/nettest/defconfig
+++ b/nuttx/configs/olimex-lpc1766stk/nettest/defconfig
@@ -326,7 +326,7 @@ CONFIG_HAVE_LIBM=n
# CONFIG_SIG_SIGWORK - The signal number that will be used to wake-up
# the worker thread. Default: 4
#
-CONFIG_APP_DIR=examples/nettest
+#CONFIG_APP_DIR=
CONFIG_DEBUG=n
CONFIG_DEBUG_VERBOSE=n
CONFIG_DEBUG_SYMBOLS=n
diff --git a/nuttx/configs/olimex-lpc1766stk/nsh/appconfig b/nuttx/configs/olimex-lpc1766stk/nsh/appconfig
index 70363f99a..e8bb51cb8 100644
--- a/nuttx/configs/olimex-lpc1766stk/nsh/appconfig
+++ b/nuttx/configs/olimex-lpc1766stk/nsh/appconfig
@@ -1,48 +1,54 @@
-############################################################################
-# olimex-lpc1766stk/nsh/appconfig
-#
-# Copyright (C) 2011 Gregory Nutt. All rights reserved.
-# Author: Gregory Nutt <spudmonkey@racsa.co.cr>
-#
-# Redistribution and use in source and binary forms, with or without
-# modification, are permitted provided that the following conditions
-# are met:
-#
-# 1. Redistributions of source code must retain the above copyright
-# notice, this list of conditions and the following disclaimer.
-# 2. Redistributions in binary form must reproduce the above copyright
-# notice, this list of conditions and the following disclaimer in
-# the documentation and/or other materials provided with the
-# distribution.
-# 3. Neither the name NuttX nor the names of its contributors may be
-# used to endorse or promote products derived from this software
-# without specific prior written permission.
-#
-# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
-# "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
-# LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
-# FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
-# COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
-# INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
-# BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
-# OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
-# AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
-# LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
-# ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
-# POSSIBILITY OF SUCH DAMAGE.
-#
-############################################################################
-
-# NSH library
-
-CONFIGURED_APPS += nshlib=.built_always
-
-# Networking support
-
-ifeq ($(CONFIG_NET),y)
-CONFIGURED_APPS += netutils/uiplib=.built_always
-CONFIGURED_APPS += netutils/dhcpc=.built_always
-CONFIGURED_APPS += netutils/resolv=.built_always
-CONFIGURED_APPS += netutils/tftp=.built_always
-CONFIGURED_APPS += netutils/webclient=.built_always
-endif
+############################################################################
+# configs/olimex-lpc1766stk/nsh/appconfig
+#
+# Copyright (C) 2011 Gregory Nutt. All rights reserved.
+# Author: Gregory Nutt <spudmonkey@racsa.co.cr>
+#
+# Redistribution and use in source and binary forms, with or without
+# modification, are permitted provided that the following conditions
+# are met:
+#
+# 1. Redistributions of source code must retain the above copyright
+# notice, this list of conditions and the following disclaimer.
+# 2. Redistributions in binary form must reproduce the above copyright
+# notice, this list of conditions and the following disclaimer in
+# the documentation and/or other materials provided with the
+# distribution.
+# 3. Neither the name NuttX nor the names of its contributors may be
+# used to endorse or promote products derived from this software
+# without specific prior written permission.
+#
+# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+# "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+# LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+# FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+# COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+# INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+# BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
+# OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
+# AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+# LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+# ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+# POSSIBILITY OF SUCH DAMAGE.
+#
+############################################################################
+
+# Path to example in apps/examples containing the user_start entry point
+
+CONFIGURED_APPS += examples/nsh=.built_always
+
+# NSH library
+
+CONFIGURED_APPS += nshlib=.built_always
+
+# Networking support
+
+ifeq ($(CONFIG_NET),y)
+CONFIGURED_APPS += netutils/uiplib=.built_always
+CONFIGURED_APPS += netutils/dhcpc=.built_always
+CONFIGURED_APPS += netutils/resolv=.built_always
+CONFIGURED_APPS += netutils/tftpc=.built_always
+CONFIGURED_APPS += netutils/webclient=.built_always
+endif
+
+
diff --git a/nuttx/configs/olimex-lpc1766stk/nsh/defconfig b/nuttx/configs/olimex-lpc1766stk/nsh/defconfig
index 1e2c074e8..b16abf38f 100755
--- a/nuttx/configs/olimex-lpc1766stk/nsh/defconfig
+++ b/nuttx/configs/olimex-lpc1766stk/nsh/defconfig
@@ -326,7 +326,7 @@ CONFIG_HAVE_LIBM=n
# CONFIG_SIG_SIGWORK - The signal number that will be used to wake-up
# the worker thread. Default: 4
#
-CONFIG_APP_DIR=examples/nsh
+#CONFIG_APP_DIR=
CONFIG_DEBUG=n
CONFIG_DEBUG_VERBOSE=n
CONFIG_DEBUG_SYMBOLS=n
diff --git a/nuttx/configs/olimex-lpc1766stk/nx/appconfig b/nuttx/configs/olimex-lpc1766stk/nx/appconfig
new file mode 100644
index 000000000..7c6a69478
--- /dev/null
+++ b/nuttx/configs/olimex-lpc1766stk/nx/appconfig
@@ -0,0 +1,39 @@
+############################################################################
+# configs/olimex-lpc1766stk/nx/appconfig
+#
+# Copyright (C) 2011 Gregory Nutt. All rights reserved.
+# Author: Gregory Nutt <spudmonkey@racsa.co.cr>
+#
+# Redistribution and use in source and binary forms, with or without
+# modification, are permitted provided that the following conditions
+# are met:
+#
+# 1. Redistributions of source code must retain the above copyright
+# notice, this list of conditions and the following disclaimer.
+# 2. Redistributions in binary form must reproduce the above copyright
+# notice, this list of conditions and the following disclaimer in
+# the documentation and/or other materials provided with the
+# distribution.
+# 3. Neither the name NuttX nor the names of its contributors may be
+# used to endorse or promote products derived from this software
+# without specific prior written permission.
+#
+# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+# "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+# LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+# FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+# COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+# INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+# BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
+# OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
+# AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+# LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+# ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+# POSSIBILITY OF SUCH DAMAGE.
+#
+############################################################################
+
+# Path to example in apps/examples containing the user_start entry point
+
+CONFIGURED_APPS += examples/nx=.built_always
+
diff --git a/nuttx/configs/olimex-lpc1766stk/nx/defconfig b/nuttx/configs/olimex-lpc1766stk/nx/defconfig
index 565337548..d45d7a296 100755
--- a/nuttx/configs/olimex-lpc1766stk/nx/defconfig
+++ b/nuttx/configs/olimex-lpc1766stk/nx/defconfig
@@ -325,7 +325,7 @@ CONFIG_SPI_CMDDATA=n
# CONFIG_SIG_SIGWORK - The signal number that will be used to wake-up
# the worker thread. Default: 4
#
-CONFIG_APP_DIR=examples/nx
+#CONFIG_APP_DIR=
CONFIG_DEBUG=n
CONFIG_DEBUG_VERBOSE=n
diff --git a/nuttx/configs/olimex-lpc1766stk/ostest/appconfig b/nuttx/configs/olimex-lpc1766stk/ostest/appconfig
new file mode 100644
index 000000000..b046927b3
--- /dev/null
+++ b/nuttx/configs/olimex-lpc1766stk/ostest/appconfig
@@ -0,0 +1,39 @@
+############################################################################
+# configs/olimex-lpc1766stk/ostest/appconfig
+#
+# Copyright (C) 2011 Gregory Nutt. All rights reserved.
+# Author: Gregory Nutt <spudmonkey@racsa.co.cr>
+#
+# Redistribution and use in source and binary forms, with or without
+# modification, are permitted provided that the following conditions
+# are met:
+#
+# 1. Redistributions of source code must retain the above copyright
+# notice, this list of conditions and the following disclaimer.
+# 2. Redistributions in binary form must reproduce the above copyright
+# notice, this list of conditions and the following disclaimer in
+# the documentation and/or other materials provided with the
+# distribution.
+# 3. Neither the name NuttX nor the names of its contributors may be
+# used to endorse or promote products derived from this software
+# without specific prior written permission.
+#
+# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+# "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+# LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+# FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+# COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+# INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+# BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
+# OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
+# AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+# LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+# ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+# POSSIBILITY OF SUCH DAMAGE.
+#
+############################################################################
+
+# Path to example in apps/examples containing the user_start entry point
+
+CONFIGURED_APPS += examples/ostest=.built_always
+
diff --git a/nuttx/configs/olimex-lpc1766stk/ostest/defconfig b/nuttx/configs/olimex-lpc1766stk/ostest/defconfig
index 561eba638..f5b46927c 100755
--- a/nuttx/configs/olimex-lpc1766stk/ostest/defconfig
+++ b/nuttx/configs/olimex-lpc1766stk/ostest/defconfig
@@ -320,7 +320,7 @@ CONFIG_HAVE_LIBM=n
# CONFIG_SIG_SIGWORK - The signal number that will be used to wake-up
# the worker thread. Default: 4
#
-CONFIG_APP_DIR=examples/ostest
+#CONFIG_APP_DIR=
CONFIG_DEBUG=n
CONFIG_DEBUG_VERBOSE=n
CONFIG_DEBUG_SYMBOLS=n
diff --git a/nuttx/configs/olimex-lpc1766stk/slip-httpd/appconfig b/nuttx/configs/olimex-lpc1766stk/slip-httpd/appconfig
index ab3406381..9be22e90e 100644
--- a/nuttx/configs/olimex-lpc1766stk/slip-httpd/appconfig
+++ b/nuttx/configs/olimex-lpc1766stk/slip-httpd/appconfig
@@ -1,39 +1,44 @@
-############################################################################
-# olimex-lpc1766stk/slip-httpd/appconfig
-#
-# Copyright (C) 2011 Gregory Nutt. All rights reserved.
-# Author: Gregory Nutt <spudmonkey@racsa.co.cr>
-#
-# Redistribution and use in source and binary forms, with or without
-# modification, are permitted provided that the following conditions
-# are met:
-#
-# 1. Redistributions of source code must retain the above copyright
-# notice, this list of conditions and the following disclaimer.
-# 2. Redistributions in binary form must reproduce the above copyright
-# notice, this list of conditions and the following disclaimer in
-# the documentation and/or other materials provided with the
-# distribution.
-# 3. Neither the name NuttX nor the names of its contributors may be
-# used to endorse or promote products derived from this software
-# without specific prior written permission.
-#
-# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
-# "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
-# LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
-# FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
-# COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
-# INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
-# BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
-# OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
-# AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
-# LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
-# ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
-# POSSIBILITY OF SUCH DAMAGE.
-#
-############################################################################
-
-# Networking support
-
-CONFIGURED_APPS += netutils/uiplib=.built_always
-CONFIGURED_APPS += netutils/thttpd=.built_always
+############################################################################
+# configs/olimex-lpc1766stk/slip-httpd/appconfig
+#
+# Copyright (C) 2011 Gregory Nutt. All rights reserved.
+# Author: Gregory Nutt <spudmonkey@racsa.co.cr>
+#
+# Redistribution and use in source and binary forms, with or without
+# modification, are permitted provided that the following conditions
+# are met:
+#
+# 1. Redistributions of source code must retain the above copyright
+# notice, this list of conditions and the following disclaimer.
+# 2. Redistributions in binary form must reproduce the above copyright
+# notice, this list of conditions and the following disclaimer in
+# the documentation and/or other materials provided with the
+# distribution.
+# 3. Neither the name NuttX nor the names of its contributors may be
+# used to endorse or promote products derived from this software
+# without specific prior written permission.
+#
+# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+# "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+# LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+# FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+# COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+# INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+# BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
+# OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
+# AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+# LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+# ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+# POSSIBILITY OF SUCH DAMAGE.
+#
+############################################################################
+
+# Path to example in apps/examples containing the user_start entry point
+
+CONFIGURED_APPS += examples/thttpd=.built_always
+
+
+# Networking support
+
+CONFIGURED_APPS += netutils/uiplib=.built_always
+CONFIGURED_APPS += netutils/thttpd=.built_always
diff --git a/nuttx/configs/olimex-lpc1766stk/slip-httpd/defconfig b/nuttx/configs/olimex-lpc1766stk/slip-httpd/defconfig
index 81978e279..b7c6f1731 100755
--- a/nuttx/configs/olimex-lpc1766stk/slip-httpd/defconfig
+++ b/nuttx/configs/olimex-lpc1766stk/slip-httpd/defconfig
@@ -322,7 +322,7 @@ CONFIG_HAVE_LIBM=n
# CONFIG_SIG_SIGWORK - The signal number that will be used to wake-up
# the worker thread. Default: 4
#
-CONFIG_APP_DIR=examples/thttpd
+#CONFIG_APP_DIR=
CONFIG_DEBUG=n
CONFIG_DEBUG_VERBOSE=n
CONFIG_DEBUG_SYMBOLS=n
diff --git a/nuttx/configs/olimex-lpc1766stk/thttpd/appconfig b/nuttx/configs/olimex-lpc1766stk/thttpd/appconfig
index 87766510d..6eea7ea59 100644
--- a/nuttx/configs/olimex-lpc1766stk/thttpd/appconfig
+++ b/nuttx/configs/olimex-lpc1766stk/thttpd/appconfig
@@ -1,39 +1,44 @@
-############################################################################
-# olimex-lpc1766stk/thttpd/appconfig
-#
-# Copyright (C) 2011 Gregory Nutt. All rights reserved.
-# Author: Gregory Nutt <spudmonkey@racsa.co.cr>
-#
-# Redistribution and use in source and binary forms, with or without
-# modification, are permitted provided that the following conditions
-# are met:
-#
-# 1. Redistributions of source code must retain the above copyright
-# notice, this list of conditions and the following disclaimer.
-# 2. Redistributions in binary form must reproduce the above copyright
-# notice, this list of conditions and the following disclaimer in
-# the documentation and/or other materials provided with the
-# distribution.
-# 3. Neither the name NuttX nor the names of its contributors may be
-# used to endorse or promote products derived from this software
-# without specific prior written permission.
-#
-# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
-# "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
-# LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
-# FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
-# COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
-# INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
-# BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
-# OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
-# AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
-# LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
-# ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
-# POSSIBILITY OF SUCH DAMAGE.
-#
-############################################################################
-
-# Networking support
-
-CONFIGURED_APPS += netutils/uiplib=.built_always
-CONFIGURED_APPS += netutils/thttpd=.built_always
+############################################################################
+# configs/olimex-lpc1766stk/thttpd/appconfig
+#
+# Copyright (C) 2011 Gregory Nutt. All rights reserved.
+# Author: Gregory Nutt <spudmonkey@racsa.co.cr>
+#
+# Redistribution and use in source and binary forms, with or without
+# modification, are permitted provided that the following conditions
+# are met:
+#
+# 1. Redistributions of source code must retain the above copyright
+# notice, this list of conditions and the following disclaimer.
+# 2. Redistributions in binary form must reproduce the above copyright
+# notice, this list of conditions and the following disclaimer in
+# the documentation and/or other materials provided with the
+# distribution.
+# 3. Neither the name NuttX nor the names of its contributors may be
+# used to endorse or promote products derived from this software
+# without specific prior written permission.
+#
+# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+# "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+# LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+# FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+# COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+# INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+# BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
+# OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
+# AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+# LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+# ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+# POSSIBILITY OF SUCH DAMAGE.
+#
+############################################################################
+
+# Path to example in apps/examples containing the user_start entry point
+
+CONFIGURED_APPS += examples/thttpd=.built_always
+
+
+# Networking support
+
+CONFIGURED_APPS += netutils/uiplib=.built_always
+CONFIGURED_APPS += netutils/thttpd=.built_always
diff --git a/nuttx/configs/olimex-lpc1766stk/thttpd/defconfig b/nuttx/configs/olimex-lpc1766stk/thttpd/defconfig
index 118444517..a7f8a9f25 100755
--- a/nuttx/configs/olimex-lpc1766stk/thttpd/defconfig
+++ b/nuttx/configs/olimex-lpc1766stk/thttpd/defconfig
@@ -320,7 +320,7 @@ CONFIG_HAVE_LIBM=n
# CONFIG_SIG_SIGWORK - The signal number that will be used to wake-up
# the worker thread. Default: 4
#
-CONFIG_APP_DIR=examples/thttpd
+#CONFIG_APP_DIR=
CONFIG_DEBUG=n
CONFIG_DEBUG_VERBOSE=n
CONFIG_DEBUG_SYMBOLS=n
diff --git a/nuttx/configs/olimex-lpc1766stk/usbserial/appconfig b/nuttx/configs/olimex-lpc1766stk/usbserial/appconfig
new file mode 100644
index 000000000..49cc61e03
--- /dev/null
+++ b/nuttx/configs/olimex-lpc1766stk/usbserial/appconfig
@@ -0,0 +1,39 @@
+############################################################################
+# configs/olimex-lpc1766stk/usbserial/appconfig
+#
+# Copyright (C) 2011 Gregory Nutt. All rights reserved.
+# Author: Gregory Nutt <spudmonkey@racsa.co.cr>
+#
+# Redistribution and use in source and binary forms, with or without
+# modification, are permitted provided that the following conditions
+# are met:
+#
+# 1. Redistributions of source code must retain the above copyright
+# notice, this list of conditions and the following disclaimer.
+# 2. Redistributions in binary form must reproduce the above copyright
+# notice, this list of conditions and the following disclaimer in
+# the documentation and/or other materials provided with the
+# distribution.
+# 3. Neither the name NuttX nor the names of its contributors may be
+# used to endorse or promote products derived from this software
+# without specific prior written permission.
+#
+# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+# "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+# LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+# FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+# COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+# INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+# BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
+# OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
+# AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+# LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+# ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+# POSSIBILITY OF SUCH DAMAGE.
+#
+############################################################################
+
+# Path to example in apps/examples containing the user_start entry point
+
+CONFIGURED_APPS += examples/usbserial=.built_always
+
diff --git a/nuttx/configs/olimex-lpc1766stk/usbserial/defconfig b/nuttx/configs/olimex-lpc1766stk/usbserial/defconfig
index cf7d7cb99..436ca1ea6 100755
--- a/nuttx/configs/olimex-lpc1766stk/usbserial/defconfig
+++ b/nuttx/configs/olimex-lpc1766stk/usbserial/defconfig
@@ -320,7 +320,7 @@ CONFIG_HAVE_LIBM=n
# CONFIG_SIG_SIGWORK - The signal number that will be used to wake-up
# the worker thread. Default: 4
#
-CONFIG_APP_DIR=examples/usbserial
+#CONFIG_APP_DIR=
CONFIG_DEBUG=n
CONFIG_DEBUG_VERBOSE=n
CONFIG_DEBUG_SYMBOLS=n
diff --git a/nuttx/configs/olimex-lpc1766stk/usbstorage/appconfig b/nuttx/configs/olimex-lpc1766stk/usbstorage/appconfig
new file mode 100644
index 000000000..d4f33077e
--- /dev/null
+++ b/nuttx/configs/olimex-lpc1766stk/usbstorage/appconfig
@@ -0,0 +1,39 @@
+############################################################################
+# configs/olimex-lpc1766stk/usbstorage/appconfig
+#
+# Copyright (C) 2011 Gregory Nutt. All rights reserved.
+# Author: Gregory Nutt <spudmonkey@racsa.co.cr>
+#
+# Redistribution and use in source and binary forms, with or without
+# modification, are permitted provided that the following conditions
+# are met:
+#
+# 1. Redistributions of source code must retain the above copyright
+# notice, this list of conditions and the following disclaimer.
+# 2. Redistributions in binary form must reproduce the above copyright
+# notice, this list of conditions and the following disclaimer in
+# the documentation and/or other materials provided with the
+# distribution.
+# 3. Neither the name NuttX nor the names of its contributors may be
+# used to endorse or promote products derived from this software
+# without specific prior written permission.
+#
+# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+# "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+# LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+# FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+# COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+# INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+# BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
+# OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
+# AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+# LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+# ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+# POSSIBILITY OF SUCH DAMAGE.
+#
+############################################################################
+
+# Path to example in apps/examples containing the user_start entry point
+
+CONFIGURED_APPS += examples/usbstorage=.built_always
+
diff --git a/nuttx/configs/olimex-lpc1766stk/usbstorage/defconfig b/nuttx/configs/olimex-lpc1766stk/usbstorage/defconfig
index 85918740c..4b56fb1fe 100755
--- a/nuttx/configs/olimex-lpc1766stk/usbstorage/defconfig
+++ b/nuttx/configs/olimex-lpc1766stk/usbstorage/defconfig
@@ -320,7 +320,7 @@ CONFIG_HAVE_LIBM=n
# CONFIG_SIG_SIGWORK - The signal number that will be used to wake-up
# the worker thread. Default: 4
#
-CONFIG_APP_DIR=examples/usbstorage
+#CONFIG_APP_DIR=
CONFIG_DEBUG=n
CONFIG_DEBUG_VERBOSE=n
CONFIG_DEBUG_SYMBOLS=n
diff --git a/nuttx/configs/olimex-lpc1766stk/wlan/appconfig b/nuttx/configs/olimex-lpc1766stk/wlan/appconfig
new file mode 100644
index 000000000..2a9f4be40
--- /dev/null
+++ b/nuttx/configs/olimex-lpc1766stk/wlan/appconfig
@@ -0,0 +1,39 @@
+############################################################################
+# configs/olimex-lpc1766stk/wlan/appconfig
+#
+# Copyright (C) 2011 Gregory Nutt. All rights reserved.
+# Author: Gregory Nutt <spudmonkey@racsa.co.cr>
+#
+# Redistribution and use in source and binary forms, with or without
+# modification, are permitted provided that the following conditions
+# are met:
+#
+# 1. Redistributions of source code must retain the above copyright
+# notice, this list of conditions and the following disclaimer.
+# 2. Redistributions in binary form must reproduce the above copyright
+# notice, this list of conditions and the following disclaimer in
+# the documentation and/or other materials provided with the
+# distribution.
+# 3. Neither the name NuttX nor the names of its contributors may be
+# used to endorse or promote products derived from this software
+# without specific prior written permission.
+#
+# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+# "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+# LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
+# FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
+# COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
+# INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
+# BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
+# OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
+# AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+# LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
+# ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
+# POSSIBILITY OF SUCH DAMAGE.
+#
+############################################################################
+
+# Path to example in apps/examples containing the user_start entry point
+
+CONFIGURED_APPS += examples/wlan=.built_always
+
diff --git a/nuttx/configs/olimex-lpc1766stk/wlan/defconfig b/nuttx/configs/olimex-lpc1766stk/wlan/defconfig
index 43d281570..61cd0085e 100755
--- a/nuttx/configs/olimex-lpc1766stk/wlan/defconfig
+++ b/nuttx/configs/olimex-lpc1766stk/wlan/defconfig
@@ -325,7 +325,7 @@ CONFIG_HAVE_LIBM=n
# CONFIG_SIG_SIGWORK - The signal number that will be used to wake-up
# the worker thread. Default: 4
#
-CONFIG_APP_DIR=examples/wlan
+#CONFIG_APP_DIR=
CONFIG_DEBUG=n
CONFIG_DEBUG_VERBOSE=n
CONFIG_DEBUG_SYMBOLS=n