summaryrefslogtreecommitdiff
path: root/nuttx
diff options
context:
space:
mode:
authorpatacongo <patacongo@42af7a65-404d-4744-a932-0658087f49c3>2012-11-28 14:08:09 +0000
committerpatacongo <patacongo@42af7a65-404d-4744-a932-0658087f49c3>2012-11-28 14:08:09 +0000
commit0db70c6895320b8a835d544e5583f6c8714a9675 (patch)
tree2d9d54a6a1311b78ec221ed45c30f08d7b8beaf3 /nuttx
parent160d9118067fae079ef2e9980f7870f98346d13b (diff)
downloadpx4-nuttx-0db70c6895320b8a835d544e5583f6c8714a9675.tar.gz
px4-nuttx-0db70c6895320b8a835d544e5583f6c8714a9675.tar.bz2
px4-nuttx-0db70c6895320b8a835d544e5583f6c8714a9675.zip
configs/many/Make.defs: Fix typo -wstrict-prototypes; Add Calypso keypad driver (Denis Cariki)
git-svn-id: svn://svn.code.sf.net/p/nuttx/code/trunk@5395 42af7a65-404d-4744-a932-0658087f49c3
Diffstat (limited to 'nuttx')
-rw-r--r--nuttx/ChangeLog4
-rw-r--r--nuttx/arch/arm/src/calypso/Make.defs26
-rw-r--r--nuttx/arch/arm/src/calypso/calypso_keypad.c370
-rw-r--r--nuttx/configs/c5471evm/httpd/Make.defs2
-rw-r--r--nuttx/configs/c5471evm/nettest/Make.defs2
-rw-r--r--nuttx/configs/c5471evm/nsh/Make.defs2
-rw-r--r--nuttx/configs/c5471evm/ostest/Make.defs2
-rw-r--r--nuttx/configs/compal_e88/nsh_highram/Make.defs2
-rw-r--r--nuttx/configs/compal_e99/nsh_compalram/Make.defs2
-rw-r--r--nuttx/configs/compal_e99/nsh_highram/Make.defs2
-rw-r--r--nuttx/configs/ez80f910200kitg/ostest/Make.defs2
-rw-r--r--nuttx/configs/ez80f910200zco/dhcpd/Make.defs2
-rw-r--r--nuttx/configs/ez80f910200zco/httpd/Make.defs2
-rw-r--r--nuttx/configs/ez80f910200zco/nettest/Make.defs2
-rw-r--r--nuttx/configs/ez80f910200zco/nsh/Make.defs2
-rw-r--r--nuttx/configs/ez80f910200zco/ostest/Make.defs2
-rw-r--r--nuttx/configs/ez80f910200zco/poll/Make.defs2
-rw-r--r--nuttx/configs/m68332evb/Make.defs2
-rw-r--r--nuttx/configs/pjrc-8051/Make.defs2
-rw-r--r--nuttx/configs/us7032evb1/nsh/Make.defs2
-rw-r--r--nuttx/configs/us7032evb1/ostest/Make.defs2
-rw-r--r--nuttx/configs/xtrs/nsh/Make.defs2
-rw-r--r--nuttx/configs/xtrs/ostest/Make.defs2
-rw-r--r--nuttx/configs/xtrs/pashello/Make.defs2
-rw-r--r--nuttx/configs/z16f2800100zcog/ostest/Make.defs2
-rw-r--r--nuttx/configs/z16f2800100zcog/pashello/Make.defs2
-rw-r--r--nuttx/configs/z80sim/nsh/Make.defs2
-rw-r--r--nuttx/configs/z80sim/ostest/Make.defs2
-rw-r--r--nuttx/configs/z80sim/pashello/Make.defs2
-rw-r--r--nuttx/configs/z8encore000zco/ostest/Make.defs2
-rw-r--r--nuttx/configs/z8f64200100kit/ostest/Make.defs2
31 files changed, 415 insertions, 41 deletions
diff --git a/nuttx/ChangeLog b/nuttx/ChangeLog
index 4b0992680..170a55453 100644
--- a/nuttx/ChangeLog
+++ b/nuttx/ChangeLog
@@ -3702,4 +3702,8 @@
but should be in arch/arm/src/stm32 where they can be used from any board.
* sched/work_thread.c: Fix backward conditional compilation. This might
has caused a memory leadk. From Freddie Chopin.
+ * configs/<many>/Make.defs: Fix typo -wstrict-prototypes should be
+ -Wstrict-prototypes (From Denis Cariki).
+ * arch/arm/src/calapyso/calypso_keypad.c: Add Calypso keypad driver. From
+ Denis Cariki.
diff --git a/nuttx/arch/arm/src/calypso/Make.defs b/nuttx/arch/arm/src/calypso/Make.defs
index db37ef02b..4b53c3b7c 100644
--- a/nuttx/arch/arm/src/calypso/Make.defs
+++ b/nuttx/arch/arm/src/calypso/Make.defs
@@ -36,22 +36,22 @@
#
############################################################################
-HEAD_ASRC = calypso_head.S
+HEAD_ASRC = calypso_head.S
-CMN_ASRCS = up_saveusercontext.S up_fullcontextrestore.S up_vectors.S \
- up_nommuhead.S
-CMN_CSRCS = up_allocateheap.c up_assert.c up_blocktask.c up_copystate.c \
- up_createstack.c up_dataabort.c up_mdelay.c up_udelay.c up_doirq.c \
- up_exit.c up_idle.c up_initialstate.c up_initialize.c \
- up_interruptcontext.c up_prefetchabort.c up_releasepending.c \
- up_releasestack.c up_reprioritizertr.c up_schedulesigaction.c \
- up_sigdeliver.c up_syscall.c up_unblocktask.c \
- up_undefinedinsn.c up_usestack.c calypso_power.c
+CMN_ASRCS = up_saveusercontext.S up_fullcontextrestore.S up_vectors.S \
+ up_nommuhead.S
+CMN_CSRCS = up_allocateheap.c up_assert.c up_blocktask.c up_copystate.c \
+ up_createstack.c up_dataabort.c up_mdelay.c up_udelay.c up_doirq.c \
+ up_exit.c up_idle.c up_initialstate.c up_initialize.c \
+ up_interruptcontext.c up_prefetchabort.c up_releasepending.c \
+ up_releasestack.c up_reprioritizertr.c up_schedulesigaction.c \
+ up_sigdeliver.c up_syscall.c up_unblocktask.c \
+ up_undefinedinsn.c up_usestack.c calypso_power.c
ifeq ($(CONFIG_ELF),y)
CMN_CSRCS += up_elf.c
endif
-CHIP_ASRCS = calypso_lowputc.S
-CHIP_CSRCS = calypso_irq.c calypso_timer.c calypso_heap.c \
- calypso_serial.c calypso_spi.c clock.c calypso_uwire.c
+CHIP_ASRCS = calypso_lowputc.S
+CHIP_CSRCS = calypso_irq.c calypso_timer.c calypso_heap.c calypso_serial.c \
+ calypso_spi.c clock.c calypso_uwire.c calypso_armio.c calypso_keypad.c
diff --git a/nuttx/arch/arm/src/calypso/calypso_keypad.c b/nuttx/arch/arm/src/calypso/calypso_keypad.c
new file mode 100644
index 000000000..aeb16eb4d
--- /dev/null
+++ b/nuttx/arch/arm/src/calypso/calypso_keypad.c
@@ -0,0 +1,370 @@
+/****************************************************************************
+ * Driver for Calypso keypad hardware
+ *
+ * Copyright (C) 2011 Stefan Richter. All rights reserved.
+ * Author: Stefan Richter <ichgeh@l--putt.de>
+ *
+ * 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 <nuttx/config.h>
+
+#include <nuttx/arch.h>
+#include <nuttx/irq.h>
+#include <nuttx/fs/fs.h>
+
+#include <stdint.h>
+#include <semaphore.h>
+#include <errno.h>
+#include <unistd.h>
+#include <sched.h>
+
+#include <arch/calypso/defines.h>
+#include <arch/calypso/memory.h>
+#include <arch/calypso/timer.h>
+
+/****************************************************************************
+ * HW access
+ ****************************************************************************/
+
+#define BASE_ADDR_ARMIO 0xfffe4800
+#define ARMIO_REG(x) ((void *)BASE_ADDR_ARMIO + (x))
+
+enum armio_reg
+{
+ LATCH_IN = 0x00,
+ LATCH_OUT = 0x02,
+ IO_CNTL = 0x04,
+ CNTL_REG = 0x06,
+ LOAD_TIM = 0x08,
+ KBR_LATCH_REG = 0x0a,
+ KBC_REG = 0x0c,
+ BUZZ_LIGHT_REG = 0x0e,
+ LIGHT_LEVEL = 0x10,
+ BUZZER_LEVEL = 0x12,
+ GPIO_EVENT_MODE = 0x14,
+ KBD_GPIO_INT = 0x16,
+ KBD_GPIO_MASKIT = 0x18,
+ GPIO_DEBOUNCING = 0x1a,
+ GPIO_LATCH = 0x1c,
+};
+
+#define KBD_INT (1 << 0)
+#define GPIO_INT (1 << 1)
+
+/****************************************************************************
+ * Decoder functions for matrix and power button
+ ****************************************************************************/
+
+static int btn_dec(uint32_t * btn_state, uint8_t col, uint8_t reg,
+ char *buf, size_t buflen, size_t * len)
+{
+ uint8_t diff = (*btn_state ^ reg) & 0x1f;
+
+ while (diff)
+ {
+ uint8_t val = diff & ~(diff - 1);
+ uint8_t sc = val >> 1;
+ sc |= sc << 2;
+ sc += col;
+ sc += (sc & 0x20) ? 0x26 : 0x3f;
+
+ if (reg & val)
+ {
+ sc |= 0x20;
+ }
+
+ /* Check for space in buffer and dispatch */
+
+ if (*len < buflen)
+ {
+ buf[(*len)++] = sc;
+ }
+ else
+ {
+ break;
+ }
+
+ /* Only change diff if dispatched/buffer not full */
+
+ diff ^= val;
+ }
+
+ /* Store new state of the buttons (but only if they where dispatch) */
+
+ *btn_state >>= 5;
+#ifdef INCLUDE_ALL_COLS
+ *btn_state |= (reg ^ diff) << 20;
+#else
+ *btn_state |= (reg ^ diff) << 15;
+#endif
+ return diff;
+}
+
+static int pwr_btn_dec(uint32_t * state, uint8_t reg, char *buf, size_t * len)
+{
+ if (reg)
+ {
+ /* Check for pressed power button. If pressed, ignore other
+ * buttons since it collides with an entire row.
+ */
+
+ if (~*state & 0x80000000)
+ {
+ buf[0] = 'z';
+ *len = 1;
+ *state |= 0x80000000;
+ }
+
+ return 1; // break loop in caller
+ }
+ else
+ {
+ /* Check for released power button. */
+
+ if (*state & 0x80000000)
+ {
+ buf[0] = 'Z';
+ *len = 1;
+
+ *state &= 0x7fffffff;
+
+ /* Don't scan others when released; might trigger
+ * false keystrokes otherwise
+ */
+
+ return 1;
+ }
+ }
+
+ return 0; // continue with other columns
+}
+
+/****************************************************************************
+ * Keypad: Fileops Prototypes and Structures
+ ****************************************************************************/
+
+typedef FAR struct file file_t;
+
+static int keypad_open(file_t * filep);
+static int keypad_close(file_t * filep);
+static ssize_t keypad_read(file_t * filep, FAR char *buffer, size_t buflen);
+#ifndef CONFIG_DISABLE_POLL
+static int keypad_poll(file_t * filep, FAR struct pollfd *fds, bool setup);
+#endif
+
+static const struct file_operations keypad_ops =
+{
+ keypad_open, /* open */
+ keypad_close, /* close */
+ keypad_read, /* read */
+ 0, /* write */
+ 0, /* seek */
+ 0, /* ioctl */
+#ifndef CONFIG_DISABLE_POLL
+ keypad_poll /* poll */
+#endif
+};
+
+static sem_t kbdsem;
+
+/****************************************************************************
+ * Keypad: Fileops
+ ****************************************************************************/
+
+static int keypad_open(file_t * filep)
+{
+ register uint16_t reg;
+
+ /* Unmask keypad interrupt */
+ reg = readw(ARMIO_REG(KBD_GPIO_MASKIT));
+ writew(reg & ~KBD_INT, ARMIO_REG(KBD_GPIO_MASKIT));
+
+ return OK;
+}
+
+static int keypad_close(file_t * filep)
+{
+ register uint16_t reg;
+
+ /* Mask keypad interrupt */
+
+ reg = readw(ARMIO_REG(KBD_GPIO_MASKIT));
+ writew(reg | KBD_INT, ARMIO_REG(KBD_GPIO_MASKIT));
+
+ return OK;
+}
+
+static ssize_t keypad_read(file_t * filep, FAR char *buf, size_t buflen)
+{
+ static uint32_t btn_state = 0;
+ register uint16_t reg;
+ uint16_t col, col_mask;
+ size_t len = 0;
+
+ if (buf == NULL || buflen < 1)
+ {
+ /* Well... nothing to do */
+
+ return -EINVAL;
+ }
+
+retry:
+ col = 1;
+ col_mask = 0x1e;
+
+ if (!btn_state)
+ {
+ /* Drive all cols low such that all buttons cause events */
+
+ writew(0, ARMIO_REG(KBC_REG));
+
+ /* No button currently pressed, use IRQ */
+
+ reg = readw(ARMIO_REG(KBD_GPIO_MASKIT));
+ writew(reg & ~KBD_INT, ARMIO_REG(KBD_GPIO_MASKIT));
+ sem_wait(&kbdsem);
+ }
+ else
+ {
+ writew(0x1f, ARMIO_REG(KBC_REG));
+ usleep(80000);
+ }
+
+ /* Scan columns */
+
+#ifdef INCLUDE_ALL_COLS
+ while (col <= 6)
+ {
+#else
+ while (col <= 5)
+ {
+#endif
+ /* Read keypad latch and immediately set new column since
+ * synchronization takes about 5usec. For the 1st round, the
+ * interrupt has prepared this and the context switch takes
+ * long enough to serve as a delay.
+ */
+
+ reg = readw(ARMIO_REG(KBR_LATCH_REG));
+ writew(col_mask, ARMIO_REG(KBC_REG));
+
+ /* Turn pressed buttons into 1s */
+
+ reg = 0x1f & ~reg;
+
+ if (col == 1)
+ {
+ /* Power/End switch */
+
+ if (pwr_btn_dec(&btn_state, reg, buf, &len))
+ {
+ break;
+ }
+ }
+ else
+ {
+ /* Non-power switches */
+
+ if (btn_dec(&btn_state, col, reg, buf, buflen, &len))
+ {
+ break;
+ }
+ }
+
+ /* Select next column and respective mask */
+
+ col_mask = 0x1f & ~(1 << col++);
+
+ /* We have to wait for synchronization of the inputs. The
+ * processing is too fast if no/few buttons are processed.
+ */
+
+ usleep(5);
+
+ /* XXX: usleep seems to suffer hugh overhead. Better this!?
+ * If nothing else can be done, it's overhead still wastes
+ * time 'usefully'.
+ */
+ /* sched_yield(); up_udelay(2); */
+ }
+
+ /* If we don't have anything to return, retry to avoid EOF */
+
+ if (!len)
+ {
+ goto retry;
+ }
+
+ return len;
+}
+
+/****************************************************************************
+ * Keypad interrupt handler
+ * mask interrupts
+ * prepare column drivers for scan
+ * posts keypad semaphore
+ ****************************************************************************/
+
+inline int calypso_kbd_irq(int irq, uint32_t * regs)
+{
+ register uint16_t reg;
+
+ /* Mask keypad interrupt */
+
+ reg = readw(ARMIO_REG(KBD_GPIO_MASKIT));
+ writew(reg | KBD_INT, ARMIO_REG(KBD_GPIO_MASKIT));
+
+ /* Turn off column drivers */
+
+ writew(0x1f, ARMIO_REG(KBC_REG));
+
+ /* Let the userspace know */
+
+ sem_post(&kbdsem);
+
+ return 0;
+}
+
+/****************************************************************************
+ * Initialize device, add /dev/... nodes
+ ****************************************************************************/
+
+void up_keypad(void)
+{
+ /* Semaphore; helps leaving IRQ ctx as soon as possible */
+
+ sem_init(&kbdsem, 0, 0);
+
+ /* Drive cols low in idle state such that all buttons cause events */
+
+ writew(0, ARMIO_REG(KBC_REG));
+
+ (void)register_driver("/dev/keypad", &keypad_ops, 0444, NULL);
+}
diff --git a/nuttx/configs/c5471evm/httpd/Make.defs b/nuttx/configs/c5471evm/httpd/Make.defs
index 45a567ec4..d06299359 100644
--- a/nuttx/configs/c5471evm/httpd/Make.defs
+++ b/nuttx/configs/c5471evm/httpd/Make.defs
@@ -90,7 +90,7 @@ MKDEP = $(TOPDIR)/tools/mkdeps.sh
HOSTCC = gcc
HOSTINCLUDES = -I.
-HOSTCFLAGS = -Wall -wstrict-prototypes -Wshadow -g -pipe
+HOSTCFLAGS = -Wall -Wstrict-prototypes -Wshadow -g -pipe
HOSTLDFLAGS =
diff --git a/nuttx/configs/c5471evm/nettest/Make.defs b/nuttx/configs/c5471evm/nettest/Make.defs
index 0db0a8dc9..bd7dcf80c 100644
--- a/nuttx/configs/c5471evm/nettest/Make.defs
+++ b/nuttx/configs/c5471evm/nettest/Make.defs
@@ -90,7 +90,7 @@ MKDEP = $(TOPDIR)/tools/mkdeps.sh
HOSTCC = gcc
HOSTINCLUDES = -I.
-HOSTCFLAGS = -Wall -wstrict-prototypes -Wshadow -g -pipe
+HOSTCFLAGS = -Wall -Wstrict-prototypes -Wshadow -g -pipe
HOSTLDFLAGS =
diff --git a/nuttx/configs/c5471evm/nsh/Make.defs b/nuttx/configs/c5471evm/nsh/Make.defs
index 8d3a3adc1..5feb14400 100644
--- a/nuttx/configs/c5471evm/nsh/Make.defs
+++ b/nuttx/configs/c5471evm/nsh/Make.defs
@@ -90,7 +90,7 @@ MKDEP = $(TOPDIR)/tools/mkdeps.sh
HOSTCC = gcc
HOSTINCLUDES = -I.
-HOSTCFLAGS = -Wall -wstrict-prototypes -Wshadow -g -pipe
+HOSTCFLAGS = -Wall -Wstrict-prototypes -Wshadow -g -pipe
HOSTLDFLAGS =
diff --git a/nuttx/configs/c5471evm/ostest/Make.defs b/nuttx/configs/c5471evm/ostest/Make.defs
index c83459173..b683df3ec 100644
--- a/nuttx/configs/c5471evm/ostest/Make.defs
+++ b/nuttx/configs/c5471evm/ostest/Make.defs
@@ -90,7 +90,7 @@ MKDEP = $(TOPDIR)/tools/mkdeps.sh
HOSTCC = gcc
HOSTINCLUDES = -I.
-HOSTCFLAGS = -Wall -wstrict-prototypes -Wshadow -g -pipe
+HOSTCFLAGS = -Wall -Wstrict-prototypes -Wshadow -g -pipe
HOSTLDFLAGS =
diff --git a/nuttx/configs/compal_e88/nsh_highram/Make.defs b/nuttx/configs/compal_e88/nsh_highram/Make.defs
index 2d65c2782..a9454b0ec 100644
--- a/nuttx/configs/compal_e88/nsh_highram/Make.defs
+++ b/nuttx/configs/compal_e88/nsh_highram/Make.defs
@@ -100,7 +100,7 @@ MKDEP = $(TOPDIR)/tools/mkdeps.sh
HOSTCC = gcc
HOSTINCLUDES = -I.
-HOSTCFLAGS = -Wall -wstrict-prototypes -Wshadow -g -pipe
+HOSTCFLAGS = -Wall -Wstrict-prototypes -Wshadow -g -pipe
HOSTLDFLAGS =
diff --git a/nuttx/configs/compal_e99/nsh_compalram/Make.defs b/nuttx/configs/compal_e99/nsh_compalram/Make.defs
index f93a01f04..61f5a5f6e 100644
--- a/nuttx/configs/compal_e99/nsh_compalram/Make.defs
+++ b/nuttx/configs/compal_e99/nsh_compalram/Make.defs
@@ -100,7 +100,7 @@ MKDEP = $(TOPDIR)/tools/mkdeps.sh
HOSTCC = gcc
HOSTINCLUDES = -I.
-HOSTCFLAGS = -Wall -wstrict-prototypes -Wshadow -g -pipe
+HOSTCFLAGS = -Wall -Wstrict-prototypes -Wshadow -g -pipe
HOSTLDFLAGS =
diff --git a/nuttx/configs/compal_e99/nsh_highram/Make.defs b/nuttx/configs/compal_e99/nsh_highram/Make.defs
index 2d65c2782..a9454b0ec 100644
--- a/nuttx/configs/compal_e99/nsh_highram/Make.defs
+++ b/nuttx/configs/compal_e99/nsh_highram/Make.defs
@@ -100,7 +100,7 @@ MKDEP = $(TOPDIR)/tools/mkdeps.sh
HOSTCC = gcc
HOSTINCLUDES = -I.
-HOSTCFLAGS = -Wall -wstrict-prototypes -Wshadow -g -pipe
+HOSTCFLAGS = -Wall -Wstrict-prototypes -Wshadow -g -pipe
HOSTLDFLAGS =
diff --git a/nuttx/configs/ez80f910200kitg/ostest/Make.defs b/nuttx/configs/ez80f910200kitg/ostest/Make.defs
index 607a5adb7..98296a51b 100644
--- a/nuttx/configs/ez80f910200kitg/ostest/Make.defs
+++ b/nuttx/configs/ez80f910200kitg/ostest/Make.defs
@@ -232,7 +232,7 @@ else
HOSTCC = gcc
HOSTINCLUDES = -I.
- HOSTCFLAGS = -Wall -wstrict-prototypes -Wshadow -g -pipe
+ HOSTCFLAGS = -Wall -Wstrict-prototypes -Wshadow -g -pipe
HOSTLDFLAGS =
# This is the tool to use for dependencies (i.e., none)
diff --git a/nuttx/configs/ez80f910200zco/dhcpd/Make.defs b/nuttx/configs/ez80f910200zco/dhcpd/Make.defs
index c914fc263..8671fdd51 100644
--- a/nuttx/configs/ez80f910200zco/dhcpd/Make.defs
+++ b/nuttx/configs/ez80f910200zco/dhcpd/Make.defs
@@ -232,7 +232,7 @@ else
HOSTCC = gcc
HOSTINCLUDES = -I.
- HOSTCFLAGS = -Wall -wstrict-prototypes -Wshadow -g -pipe
+ HOSTCFLAGS = -Wall -Wstrict-prototypes -Wshadow -g -pipe
HOSTLDFLAGS =
# This is the tool to use for dependencies (i.e., none)
diff --git a/nuttx/configs/ez80f910200zco/httpd/Make.defs b/nuttx/configs/ez80f910200zco/httpd/Make.defs
index 5a8af2d34..a07580a32 100644
--- a/nuttx/configs/ez80f910200zco/httpd/Make.defs
+++ b/nuttx/configs/ez80f910200zco/httpd/Make.defs
@@ -232,7 +232,7 @@ else
HOSTCC = gcc
HOSTINCLUDES = -I.
- HOSTCFLAGS = -Wall -wstrict-prototypes -Wshadow -g -pipe
+ HOSTCFLAGS = -Wall -Wstrict-prototypes -Wshadow -g -pipe
HOSTLDFLAGS =
# This is the tool to use for dependencies (i.e., none)
diff --git a/nuttx/configs/ez80f910200zco/nettest/Make.defs b/nuttx/configs/ez80f910200zco/nettest/Make.defs
index f5cbc8f80..d13428a34 100644
--- a/nuttx/configs/ez80f910200zco/nettest/Make.defs
+++ b/nuttx/configs/ez80f910200zco/nettest/Make.defs
@@ -232,7 +232,7 @@ else
HOSTCC = gcc
HOSTINCLUDES = -I.
- HOSTCFLAGS = -Wall -wstrict-prototypes -Wshadow -g -pipe
+ HOSTCFLAGS = -Wall -Wstrict-prototypes -Wshadow -g -pipe
HOSTLDFLAGS =
# This is the tool to use for dependencies (i.e., none)
diff --git a/nuttx/configs/ez80f910200zco/nsh/Make.defs b/nuttx/configs/ez80f910200zco/nsh/Make.defs
index f0b8aa7c1..7a74bc306 100644
--- a/nuttx/configs/ez80f910200zco/nsh/Make.defs
+++ b/nuttx/configs/ez80f910200zco/nsh/Make.defs
@@ -232,7 +232,7 @@ else
HOSTCC = gcc
HOSTINCLUDES = -I.
- HOSTCFLAGS = -Wall -wstrict-prototypes -Wshadow -g -pipe
+ HOSTCFLAGS = -Wall -Wstrict-prototypes -Wshadow -g -pipe
HOSTLDFLAGS =
# This is the tool to use for dependencies (i.e., none)
diff --git a/nuttx/configs/ez80f910200zco/ostest/Make.defs b/nuttx/configs/ez80f910200zco/ostest/Make.defs
index fa60dac05..5d3d4689e 100644
--- a/nuttx/configs/ez80f910200zco/ostest/Make.defs
+++ b/nuttx/configs/ez80f910200zco/ostest/Make.defs
@@ -232,7 +232,7 @@ else
HOSTCC = gcc
HOSTINCLUDES = -I.
- HOSTCFLAGS = -Wall -wstrict-prototypes -Wshadow -g -pipe
+ HOSTCFLAGS = -Wall -Wstrict-prototypes -Wshadow -g -pipe
HOSTLDFLAGS =
# This is the tool to use for dependencies (i.e., none)
diff --git a/nuttx/configs/ez80f910200zco/poll/Make.defs b/nuttx/configs/ez80f910200zco/poll/Make.defs
index e1eefdd03..98ca22533 100644
--- a/nuttx/configs/ez80f910200zco/poll/Make.defs
+++ b/nuttx/configs/ez80f910200zco/poll/Make.defs
@@ -232,7 +232,7 @@ else
HOSTCC = gcc
HOSTINCLUDES = -I.
- HOSTCFLAGS = -Wall -wstrict-prototypes -Wshadow -g -pipe
+ HOSTCFLAGS = -Wall -Wstrict-prototypes -Wshadow -g -pipe
HOSTLDFLAGS =
# This is the tool to use for dependencies (i.e., none)
diff --git a/nuttx/configs/m68332evb/Make.defs b/nuttx/configs/m68332evb/Make.defs
index 6f6ae7ad0..28b7f73a0 100644
--- a/nuttx/configs/m68332evb/Make.defs
+++ b/nuttx/configs/m68332evb/Make.defs
@@ -77,5 +77,5 @@ MKDEP = $(TOPDIR)/tools/mkdeps.sh
HOSTCC = gcc
HOSTINCLUDES = -I.
-HOSTCFLAGS = -Wall -wstrict-prototypes -Wshadow -g -pipe
+HOSTCFLAGS = -Wall -Wstrict-prototypes -Wshadow -g -pipe
HOSTLDFLAGS =
diff --git a/nuttx/configs/pjrc-8051/Make.defs b/nuttx/configs/pjrc-8051/Make.defs
index 5cf9fadf1..154d36556 100644
--- a/nuttx/configs/pjrc-8051/Make.defs
+++ b/nuttx/configs/pjrc-8051/Make.defs
@@ -77,7 +77,7 @@ MKDEP = $(TOPDIR)/tools/mkdeps.sh
HOSTCC = gcc
HOSTINCLUDES = -I.
-HOSTCFLAGS = -Wall -wstrict-prototypes -Wshadow -g -pipe
+HOSTCFLAGS = -Wall -Wstrict-prototypes -Wshadow -g -pipe
HOSTLDFLAGS =
diff --git a/nuttx/configs/us7032evb1/nsh/Make.defs b/nuttx/configs/us7032evb1/nsh/Make.defs
index fcda18477..595bcf4fd 100644
--- a/nuttx/configs/us7032evb1/nsh/Make.defs
+++ b/nuttx/configs/us7032evb1/nsh/Make.defs
@@ -77,6 +77,6 @@ MKDEP = $(TOPDIR)/tools/mkdeps.sh
HOSTCC = gcc
HOSTINCLUDES = -I.
-HOSTCFLAGS = -Wall -wstrict-prototypes -Wshadow -g -pipe
+HOSTCFLAGS = -Wall -Wstrict-prototypes -Wshadow -g -pipe
HOSTLDFLAGS =
diff --git a/nuttx/configs/us7032evb1/ostest/Make.defs b/nuttx/configs/us7032evb1/ostest/Make.defs
index 379342a5d..6fe463388 100644
--- a/nuttx/configs/us7032evb1/ostest/Make.defs
+++ b/nuttx/configs/us7032evb1/ostest/Make.defs
@@ -77,6 +77,6 @@ MKDEP = $(TOPDIR)/tools/mkdeps.sh
HOSTCC = gcc
HOSTINCLUDES = -I.
-HOSTCFLAGS = -Wall -wstrict-prototypes -Wshadow -g -pipe
+HOSTCFLAGS = -Wall -Wstrict-prototypes -Wshadow -g -pipe
HOSTLDFLAGS =
diff --git a/nuttx/configs/xtrs/nsh/Make.defs b/nuttx/configs/xtrs/nsh/Make.defs
index 2c3e3302f..0eac402ab 100644
--- a/nuttx/configs/xtrs/nsh/Make.defs
+++ b/nuttx/configs/xtrs/nsh/Make.defs
@@ -87,5 +87,5 @@ MKDEP = $(TOPDIR)/tools/mkdeps.sh
HOSTCC = gcc
HOSTINCLUDES = -I.
-HOSTCFLAGS = -Wall -wstrict-prototypes -Wshadow -g -pipe
+HOSTCFLAGS = -Wall -Wstrict-prototypes -Wshadow -g -pipe
HOSTLDFLAGS =
diff --git a/nuttx/configs/xtrs/ostest/Make.defs b/nuttx/configs/xtrs/ostest/Make.defs
index 5823a1361..ae26822d5 100644
--- a/nuttx/configs/xtrs/ostest/Make.defs
+++ b/nuttx/configs/xtrs/ostest/Make.defs
@@ -87,5 +87,5 @@ MKDEP = $(TOPDIR)/tools/mkdeps.sh
HOSTCC = gcc
HOSTINCLUDES = -I.
-HOSTCFLAGS = -Wall -wstrict-prototypes -Wshadow -g -pipe
+HOSTCFLAGS = -Wall -Wstrict-prototypes -Wshadow -g -pipe
HOSTLDFLAGS =
diff --git a/nuttx/configs/xtrs/pashello/Make.defs b/nuttx/configs/xtrs/pashello/Make.defs
index 367d2d950..30caae7fd 100644
--- a/nuttx/configs/xtrs/pashello/Make.defs
+++ b/nuttx/configs/xtrs/pashello/Make.defs
@@ -87,5 +87,5 @@ MKDEP = $(TOPDIR)/tools/mkdeps.sh
HOSTCC = gcc
HOSTINCLUDES = -I.
-HOSTCFLAGS = -Wall -wstrict-prototypes -Wshadow -g -pipe
+HOSTCFLAGS = -Wall -Wstrict-prototypes -Wshadow -g -pipe
HOSTLDFLAGS =
diff --git a/nuttx/configs/z16f2800100zcog/ostest/Make.defs b/nuttx/configs/z16f2800100zcog/ostest/Make.defs
index e094f4ce6..b127a6b7f 100644
--- a/nuttx/configs/z16f2800100zcog/ostest/Make.defs
+++ b/nuttx/configs/z16f2800100zcog/ostest/Make.defs
@@ -183,5 +183,5 @@ DIRUNLINK = $(TOPDIR)/tools/unlink.sh
HOSTCC = gcc
HOSTINCLUDES = -I.
-HOSTCFLAGS = -Wall -wstrict-prototypes -Wshadow -g -pipe
+HOSTCFLAGS = -Wall -Wstrict-prototypes -Wshadow -g -pipe
HOSTLDFLAGS =
diff --git a/nuttx/configs/z16f2800100zcog/pashello/Make.defs b/nuttx/configs/z16f2800100zcog/pashello/Make.defs
index c06dc0d49..2ac7aff1e 100644
--- a/nuttx/configs/z16f2800100zcog/pashello/Make.defs
+++ b/nuttx/configs/z16f2800100zcog/pashello/Make.defs
@@ -183,5 +183,5 @@ DIRUNLINK = $(TOPDIR)/tools/unlink.sh
HOSTCC = gcc
HOSTINCLUDES = -I.
-HOSTCFLAGS = -Wall -wstrict-prototypes -Wshadow -g -pipe
+HOSTCFLAGS = -Wall -Wstrict-prototypes -Wshadow -g -pipe
HOSTLDFLAGS =
diff --git a/nuttx/configs/z80sim/nsh/Make.defs b/nuttx/configs/z80sim/nsh/Make.defs
index 40d934f1d..11253020e 100644
--- a/nuttx/configs/z80sim/nsh/Make.defs
+++ b/nuttx/configs/z80sim/nsh/Make.defs
@@ -87,5 +87,5 @@ MKDEP = $(TOPDIR)/tools/mkdeps.sh
HOSTCC = gcc
HOSTINCLUDES = -I.
-HOSTCFLAGS = -Wall -wstrict-prototypes -Wshadow -g -pipe
+HOSTCFLAGS = -Wall -Wstrict-prototypes -Wshadow -g -pipe
HOSTLDFLAGS =
diff --git a/nuttx/configs/z80sim/ostest/Make.defs b/nuttx/configs/z80sim/ostest/Make.defs
index 4905e82a3..d0185b4f9 100644
--- a/nuttx/configs/z80sim/ostest/Make.defs
+++ b/nuttx/configs/z80sim/ostest/Make.defs
@@ -87,5 +87,5 @@ MKDEP = $(TOPDIR)/tools/mkdeps.sh
HOSTCC = gcc
HOSTINCLUDES = -I.
-HOSTCFLAGS = -Wall -wstrict-prototypes -Wshadow -g -pipe
+HOSTCFLAGS = -Wall -Wstrict-prototypes -Wshadow -g -pipe
HOSTLDFLAGS =
diff --git a/nuttx/configs/z80sim/pashello/Make.defs b/nuttx/configs/z80sim/pashello/Make.defs
index 51bfd1d28..16d3ff342 100644
--- a/nuttx/configs/z80sim/pashello/Make.defs
+++ b/nuttx/configs/z80sim/pashello/Make.defs
@@ -87,5 +87,5 @@ MKDEP = $(TOPDIR)/tools/mkdeps.sh
HOSTCC = gcc
HOSTINCLUDES = -I.
-HOSTCFLAGS = -Wall -wstrict-prototypes -Wshadow -g -pipe
+HOSTCFLAGS = -Wall -Wstrict-prototypes -Wshadow -g -pipe
HOSTLDFLAGS =
diff --git a/nuttx/configs/z8encore000zco/ostest/Make.defs b/nuttx/configs/z8encore000zco/ostest/Make.defs
index 55e351a79..9f033c20a 100644
--- a/nuttx/configs/z8encore000zco/ostest/Make.defs
+++ b/nuttx/configs/z8encore000zco/ostest/Make.defs
@@ -217,5 +217,5 @@ DIRUNLINK = $(TOPDIR)/tools/unlink.sh
HOSTCC = gcc
HOSTINCLUDES = -I.
-HOSTCFLAGS = -Wall -wstrict-prototypes -Wshadow -g -pipe
+HOSTCFLAGS = -Wall -Wstrict-prototypes -Wshadow -g -pipe
HOSTLDFLAGS =
diff --git a/nuttx/configs/z8f64200100kit/ostest/Make.defs b/nuttx/configs/z8f64200100kit/ostest/Make.defs
index 05c2b1593..570fd0f1b 100644
--- a/nuttx/configs/z8f64200100kit/ostest/Make.defs
+++ b/nuttx/configs/z8f64200100kit/ostest/Make.defs
@@ -259,7 +259,7 @@ else
HOSTCC = gcc
HOSTINCLUDES = -I.
- HOSTCFLAGS = -Wall -wstrict-prototypes -Wshadow -g -pipe
+ HOSTCFLAGS = -Wall -Wstrict-prototypes -Wshadow -g -pipe
HOSTLDFLAGS =
# This is the tool to use for dependencies (i.e., none)