summaryrefslogtreecommitdiff
diff options
context:
space:
mode:
-rw-r--r--nuttx/Kconfig7
-rw-r--r--nuttx/arch/arm/src/nuc1xx/Make.defs4
-rw-r--r--nuttx/arch/arm/src/nuc1xx/chip/nuc_gpio.h2
-rw-r--r--nuttx/arch/arm/src/nuc1xx/nuc_dumpgpio.c144
-rw-r--r--nuttx/arch/arm/src/nuc1xx/nuc_gpio.c48
-rw-r--r--nuttx/arch/arm/src/nuc1xx/nuc_gpio.h18
-rw-r--r--nuttx/configs/cloudctrl/src/up_autoleds.c8
-rw-r--r--nuttx/configs/cloudctrl/src/up_userleds.c8
-rw-r--r--nuttx/configs/demo9s12ne64/src/up_leds.c10
-rw-r--r--nuttx/configs/ea3131/src/up_leds.c12
-rw-r--r--nuttx/configs/ea3152/src/up_leds.c12
-rw-r--r--nuttx/configs/eagle100/src/up_leds.c12
-rw-r--r--nuttx/configs/ekk-lm3s9b96/src/up_leds.c12
-rw-r--r--nuttx/configs/fire-stm32v2/src/up_autoleds.c10
-rw-r--r--nuttx/configs/fire-stm32v2/src/up_userleds.c10
-rw-r--r--nuttx/configs/hymini-stm32v/src/up_leds.c10
-rw-r--r--nuttx/configs/kwikstik-k40/src/up_leds.c10
-rw-r--r--nuttx/configs/lincoln60/src/up_leds.c14
-rw-r--r--nuttx/configs/lm3s6432-s2e/src/up_leds.c12
-rw-r--r--nuttx/configs/lm3s6965-ek/src/up_leds.c12
-rw-r--r--nuttx/configs/lm3s8962-ek/src/up_leds.c12
-rw-r--r--nuttx/configs/lpc4330-xplorer/src/up_autoleds.c8
-rw-r--r--nuttx/configs/lpc4330-xplorer/src/up_userleds.c8
-rw-r--r--nuttx/configs/lpcxpresso-lpc1768/src/up_leds.c12
-rw-r--r--nuttx/configs/mbed/src/up_leds.c14
-rw-r--r--nuttx/configs/ne64badge/src/up_leds.c16
-rw-r--r--nuttx/configs/nucleus2g/src/up_leds.c14
-rw-r--r--nuttx/configs/nutiny-nuc120/src/nuc_led.c24
-rw-r--r--nuttx/configs/olimex-lpc1766stk/src/up_leds.c20
-rw-r--r--nuttx/configs/open1788/src/lpc17_autoleds.c16
-rw-r--r--nuttx/configs/open1788/src/lpc17_userleds.c24
-rw-r--r--nuttx/configs/pjrc-8051/src/up_leds.c4
-rw-r--r--nuttx/configs/sam3u-ek/src/up_leds.c8
-rw-r--r--nuttx/configs/shenzhou/src/up_autoleds.c10
-rw-r--r--nuttx/configs/shenzhou/src/up_userleds.c10
-rw-r--r--nuttx/configs/stm3210e-eval/src/up_leds.c10
-rw-r--r--nuttx/configs/stm3220g-eval/src/up_autoleds.c8
-rw-r--r--nuttx/configs/stm3220g-eval/src/up_userleds.c10
-rw-r--r--nuttx/configs/stm3240g-eval/src/up_autoleds.c10
-rw-r--r--nuttx/configs/stm3240g-eval/src/up_userleds.c10
-rw-r--r--nuttx/configs/stm32f100rc_generic/src/up_leds.c10
-rw-r--r--nuttx/configs/stm32f3discovery/src/up_autoleds.c8
-rw-r--r--nuttx/configs/stm32f3discovery/src/up_userleds.c8
-rw-r--r--nuttx/configs/stm32f4discovery/src/up_autoleds.c10
-rw-r--r--nuttx/configs/stm32f4discovery/src/up_userleds.c8
-rw-r--r--nuttx/configs/teensy/src/up_leds.c14
-rw-r--r--nuttx/configs/twr-k60n512/src/up_leds.c10
-rw-r--r--nuttx/configs/vsn/src/leds.c11
-rw-r--r--nuttx/configs/zkit-arm-1769/README.txt8
-rw-r--r--nuttx/configs/zkit-arm-1769/src/up_leds.c4
-rw-r--r--nuttx/configs/zkit-arm-1769/thttpd/defconfig2
51 files changed, 434 insertions, 282 deletions
diff --git a/nuttx/Kconfig b/nuttx/Kconfig
index af743b9db..dc77e9612 100644
--- a/nuttx/Kconfig
+++ b/nuttx/Kconfig
@@ -381,6 +381,13 @@ config DEBUG_LCD
---help---
Enable low level debug SYSLOG output from the LCD driver (disabled by default)
+config DEBUG_LEDS
+ bool "Enable Low-level LED Debug Output"
+ default n
+ depends on ARCH_HAVE_LEDS
+ ---help---
+ Enable low level debug from board-specific LED logic
+
config DEBUG_INPUT
bool "Enable Input Device Debug Output"
default n
diff --git a/nuttx/arch/arm/src/nuc1xx/Make.defs b/nuttx/arch/arm/src/nuc1xx/Make.defs
index 7ccae77fa..0d20f8135 100644
--- a/nuttx/arch/arm/src/nuc1xx/Make.defs
+++ b/nuttx/arch/arm/src/nuc1xx/Make.defs
@@ -58,3 +58,7 @@ endif
CHIP_ASRCS =
CHIP_CSRCS = nuc_clockconfig.c nuc_gpio.c nuc_idle.c nuc_irq.c nuc_lowputc.c
CHIP_CSRCS += nuc_serial.c nuc_start.c nuc_timerisr.c
+
+ifeq ($(CONFIG_DEBUG),y)
+CHIP_CSRCS += nuc_dumpgpio.c
+endif
diff --git a/nuttx/arch/arm/src/nuc1xx/chip/nuc_gpio.h b/nuttx/arch/arm/src/nuc1xx/chip/nuc_gpio.h
index 4e2f2d7f7..aea16ab0c 100644
--- a/nuttx/arch/arm/src/nuc1xx/chip/nuc_gpio.h
+++ b/nuttx/arch/arm/src/nuc1xx/chip/nuc_gpio.h
@@ -55,6 +55,8 @@
#define NUC_GPIO_PORTD 3
#define NUC_GPIO_PORTE 4
+#define NUC_GPIO_NPORTS 5
+
/* GPIO control registers */
#define NUC_GPIO_CTRL_OFFSET(n) (0x0000 + ((n) << 6))
diff --git a/nuttx/arch/arm/src/nuc1xx/nuc_dumpgpio.c b/nuttx/arch/arm/src/nuc1xx/nuc_dumpgpio.c
new file mode 100644
index 000000000..aee9fa219
--- /dev/null
+++ b/nuttx/arch/arm/src/nuc1xx/nuc_dumpgpio.c
@@ -0,0 +1,144 @@
+/****************************************************************************
+ * arch/arm/src/nuc/nuc_gpio.c
+ *
+ * Copyright (C) 2013 Gregory Nutt. All rights reserved.
+ * Author: Gregory Nutt <gnutt@nuttx.org>
+ *
+ * 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 <sys/types.h>
+#include <debug.h>
+
+#include "up_arch.h"
+
+#include "chip.h"
+#include "nuc_gpio.h"
+
+#ifdef CONFIG_DEBUG
+
+/****************************************************************************
+ * Private Data
+ ****************************************************************************/
+/* Port letters for prettier debug output */
+
+#ifdef CONFIG_DEBUG
+static const char g_portchar[NUC_GPIO_NPORTS] =
+{
+#if NUC_GPIO_NPORTS > 9
+# error "Additional support required for this number of GPIOs"
+#elif NUC_GPIO_NPORTS > 8
+ 'A', 'B', 'C', 'D', 'E', 'F', 'G', 'H', 'I'
+#elif NUC_GPIO_NPORTS > 7
+ 'A', 'B', 'C', 'D', 'E', 'F', 'G', 'H'
+#elif NUC_GPIO_NPORTS > 6
+ 'A', 'B', 'C', 'D', 'E', 'F', 'G'
+#elif NUC_GPIO_NPORTS > 5
+ 'A', 'B', 'C', 'D', 'E', 'F'
+#elif NUC_GPIO_NPORTS > 4
+ 'A', 'B', 'C', 'D', 'E'
+#elif NUC_GPIO_NPORTS > 3
+ 'A', 'B', 'C', 'D'
+#elif NUC_GPIO_NPORTS > 2
+ 'A', 'B', 'C'
+#elif NUC_GPIO_NPORTS > 1
+ 'A', 'B'
+#elif NUC_GPIO_NPORTS > 0
+ 'A'
+#else
+# error "Bad number of GPIOs"
+#endif
+};
+#endif
+
+/****************************************************************************
+ * Public Data
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Public Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Function: nuc_dumpgpio
+ *
+ * Description:
+ * Dump all GPIO registers associated with the provided pin description
+ * along with a descriptive messasge.
+ *
+ ****************************************************************************/
+
+int nuc_dumpgpio(gpio_cfgset_t pinset, const char *msg)
+{
+ irqstate_t flags;
+ uintptr_t base;
+ int port;
+
+ /* Decode the port and pin. Use the port number to get the GPIO base
+ * address.
+ */
+
+ port = (pinset & GPIO_PORT_MASK) >> GPIO_PORT_SHIFT;
+ DEBUGASSERT((unsigned)port <= NUC_GPIO_PORTE);
+ base = NUC_GPIO_CTRL_BASE(port);
+
+ /* The following requires exclusive access to the GPIO registers */
+
+ flags = irqsave();
+
+ lldbg("GPIO%c pinset: %08x base: %08x -- %s\n",
+ g_portchar[port], pinset, base, msg);
+ lldbg(" PMD: %08x OFFD: %08x DOUT: %08x DMASK: %08x\n",
+ getreg32(base + NUC_GPIO_PMD_OFFSET),
+ getreg32(base + NUC_GPIO_OFFD_OFFSET),
+ getreg32(base + NUC_GPIO_DOUT_OFFSET),
+ getreg32(base + NUC_GPIO_DMASK_OFFSET));
+ lldbg(" PIN: %08x DBEN: %08x IMD: %08x IEN: %08x\n",
+ getreg32(base + NUC_GPIO_PIN_OFFSET),
+ getreg32(base + NUC_GPIO_DBEN_OFFSET),
+ getreg32(base + NUC_GPIO_IMD_OFFSET),
+ getreg32(base + NUC_GPIO_IEN_OFFSET));
+ lldbg(" ISRC: %08x\n",
+ getreg32(base + NUC_GPIO_ISRC_OFFSET));
+
+ irqrestore(flags);
+ return OK;
+}
+
+#endif /* CONFIG_DEBUG */
diff --git a/nuttx/arch/arm/src/nuc1xx/nuc_gpio.c b/nuttx/arch/arm/src/nuc1xx/nuc_gpio.c
index 1ba92a801..366226a8c 100644
--- a/nuttx/arch/arm/src/nuc1xx/nuc_gpio.c
+++ b/nuttx/arch/arm/src/nuc1xx/nuc_gpio.c
@@ -43,6 +43,8 @@
#include <assert.h>
#include <debug.h>
+#include <arch/nuc1xx/chip.h>
+
#include "up_arch.h"
#include "chip.h"
@@ -222,6 +224,10 @@ int nuc_configgpio(gpio_cfgset_t cfgset)
void nuc_gpiowrite(gpio_cfgset_t pinset, bool value)
{
+#ifndef NUC_LOW
+ irqstate_t flags;
+ uintptr_t base;
+#endif
int port;
int pin;
@@ -233,7 +239,31 @@ void nuc_gpiowrite(gpio_cfgset_t pinset, bool value)
pin = (pinset & GPIO_PIN_MASK) >> GPIO_PIN_SHIFT;
DEBUGASSERT((unsigned)port <= NUC_GPIO_PORTE);
+
+ /* Only the low density NUC100/120 chips support bit-band access to GPIO
+ * pins.
+ */
+
+#ifdef NUC_LOW
putreg32((uint32_t)value, NUC_PORT_PDIO(port, pin));
+#else
+ /* Get the base address of the GPIO port registers */
+
+ base = NUC_GPIO_CTRL_BASE(port);
+
+ /* Disable interrupts -- the following operations must be atomic */
+
+ flags = irqsave();
+
+ /* Allow writing only to the selected pin in the DOUT register */
+
+ putreg32(~(1 << pin), base + NUC_GPIO_DMASK_OFFSET);
+
+ /* Set the pin to the selected value and re-enable interrupts */
+
+ putreg32(((uint32_t)value << pin), base + NUC_GPIO_DOUT_OFFSET);
+ irqrestore(flags);
+#endif
}
/****************************************************************************
@@ -246,6 +276,9 @@ void nuc_gpiowrite(gpio_cfgset_t pinset, bool value)
bool nuc_gpioread(gpio_cfgset_t pinset)
{
+#ifndef NUC_LOW
+ uintptr_t base;
+#endif
int port;
int pin;
@@ -257,5 +290,20 @@ bool nuc_gpioread(gpio_cfgset_t pinset)
pin = (pinset & GPIO_PIN_MASK) >> GPIO_PIN_SHIFT;
DEBUGASSERT((unsigned)port <= NUC_GPIO_PORTE);
+
+ /* Only the low density NUC100/120 chips support bit-band access to GPIO
+ * pins.
+ */
+
+#ifdef NUC_LOW
return (getreg32(NUC_PORT_PDIO(port, pin)) & PORT_MASK) != 0;
+#else
+ /* Get the base address of the GPIO port registers */
+
+ base = NUC_GPIO_CTRL_BASE(port);
+
+ /* Return the state of the selected pin */
+
+ return (getreg32(base + NUC_GPIO_PIN_OFFSET) & (1 << pin)) != 0;
+#endif
}
diff --git a/nuttx/arch/arm/src/nuc1xx/nuc_gpio.h b/nuttx/arch/arm/src/nuc1xx/nuc_gpio.h
index 7da42af8f..807080475 100644
--- a/nuttx/arch/arm/src/nuc1xx/nuc_gpio.h
+++ b/nuttx/arch/arm/src/nuc1xx/nuc_gpio.h
@@ -74,7 +74,7 @@
* MM.. .... .... ....
*/
-#define GPIO_MODE_SHIFT (14) /* Bits 145_15: GPIO mode */
+#define GPIO_MODE_SHIFT (14) /* Bits 14-15: GPIO mode */
#define GPIO_MODE_MASK (3 << GPIO_MODE_SHIFT)
# define GPIO_INPUT (0 << GPIO_MODE_SHIFT) /* Input */
# define GPIO_OUTPUT (1 << GPIO_MODE_SHIFT) /* Push-pull output */
@@ -146,6 +146,7 @@
# define GPIO_PORTD (3 << GPIO_PORT_SHIFT) /* GPIOD */
# define GPIO_PORTE (4 << GPIO_PORT_SHIFT) /* GPIOE */
#
+
/* This identifies the bit in the port:
*
* 1111 1100 0000 0000
@@ -234,6 +235,21 @@ void nuc_gpiowrite(gpio_cfgset_t pinset, bool value);
bool nuc_gpioread(gpio_cfgset_t pinset);
+/****************************************************************************
+ * Function: nuc_dumpgpio
+ *
+ * Description:
+ * Dump all GPIO registers associated with the provided pin description
+ * along with a descriptive messasge.
+ *
+ ****************************************************************************/
+
+#ifdef CONFIG_DEBUG
+int nuc_dumpgpio(gpio_cfgset_t pinset, const char *msg);
+#else
+# define nuc_dumpgpio(p,m)
+#endif
+
#undef EXTERN
#if defined(__cplusplus)
}
diff --git a/nuttx/configs/cloudctrl/src/up_autoleds.c b/nuttx/configs/cloudctrl/src/up_autoleds.c
index 83e0b9e68..bc45a2154 100644
--- a/nuttx/configs/cloudctrl/src/up_autoleds.c
+++ b/nuttx/configs/cloudctrl/src/up_autoleds.c
@@ -58,13 +58,11 @@
* Definitions
****************************************************************************/
-/* Enables debug output from this file (needs CONFIG_DEBUG with
- * CONFIG_DEBUG_VERBOSE too)
+/* CONFIG_DEBUG_LEDS enables debug output from this file (needs CONFIG_DEBUG
+ * with CONFIG_DEBUG_VERBOSE too)
*/
-#undef LED_DEBUG /* Define to enable debug */
-
-#ifdef LED_DEBUG
+#ifdef CONFIG_DEBUG_LEDS
# define leddbg lldbg
# define ledvdbg llvdbg
#else
diff --git a/nuttx/configs/cloudctrl/src/up_userleds.c b/nuttx/configs/cloudctrl/src/up_userleds.c
index 6c39b1442..633aa7d98 100644
--- a/nuttx/configs/cloudctrl/src/up_userleds.c
+++ b/nuttx/configs/cloudctrl/src/up_userleds.c
@@ -59,13 +59,11 @@
* Definitions
****************************************************************************/
-/* Enables debug output from this file (needs CONFIG_DEBUG with
- * CONFIG_DEBUG_VERBOSE too)
+/* CONFIG_DEBUG_LEDS enables debug output from this file (needs CONFIG_DEBUG
+ * with CONFIG_DEBUG_VERBOSE too)
*/
-#undef LED_DEBUG /* Define to enable debug */
-
-#ifdef LED_DEBUG
+#ifdef CONFIG_DEBUG_LEDS
# define leddbg lldbg
# define ledvdbg llvdbg
#else
diff --git a/nuttx/configs/demo9s12ne64/src/up_leds.c b/nuttx/configs/demo9s12ne64/src/up_leds.c
index 1984d8165..49266aced 100644
--- a/nuttx/configs/demo9s12ne64/src/up_leds.c
+++ b/nuttx/configs/demo9s12ne64/src/up_leds.c
@@ -2,7 +2,7 @@
* configs/demo9s12ne64/src/up_leds.c
* arch/arm/src/board/up_leds.c
*
- * Copyright (C) 2009 Gregory Nutt. All rights reserved.
+ * Copyright (C) 2009, 2013 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <gnutt@nuttx.org>
*
* Redistribution and use in source and binary forms, with or without
@@ -50,13 +50,11 @@
* Pre-processor Definitions
****************************************************************************/
-/* Enables debug output from this file (needs CONFIG_DEBUG with
- * CONFIG_DEBUG_VERBOSE too)
+/* CONFIG_DEBUG_LEDS enables debug output from this file (needs CONFIG_DEBUG
+ * with CONFIG_DEBUG_VERBOSE too)
*/
-#undef LED_DEBUG /* Define to enable debug */
-
-#ifdef LED_DEBUG
+#ifdef CONFIG_DEBUG_LEDS
# define leddbg lldbg
# define ledvdbg llvdbg
#else
diff --git a/nuttx/configs/ea3131/src/up_leds.c b/nuttx/configs/ea3131/src/up_leds.c
index ab22c7657..021600cb9 100644
--- a/nuttx/configs/ea3131/src/up_leds.c
+++ b/nuttx/configs/ea3131/src/up_leds.c
@@ -2,7 +2,7 @@
* configs/ea3131/src/up_leds.c
* arch/arm/src/board/up_leds.c
*
- * Copyright (C) 2009-2010 Gregory Nutt. All rights reserved.
+ * Copyright (C) 2009-2010, 2013 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <gnutt@nuttx.org>
*
* Redistribution and use in source and binary forms, with or without
@@ -55,13 +55,11 @@
* Definitions
****************************************************************************/
-/* Enables debug output from this file (needs CONFIG_DEBUG with
- * CONFIG_DEBUG_VERBOSE too)
+/* CONFIG_DEBUG_LEDS enables debug output from this file (needs CONFIG_DEBUG
+ * with CONFIG_DEBUG_VERBOSE too)
*/
-#undef LED_DEBUG /* Define to enable debug */
-
-#ifdef LED_DEBUG
+#ifdef CONFIG_DEBUG_LEDS
# define leddbg lldbg
# define ledvdbg llvdbg
#else
@@ -69,8 +67,6 @@
# define ledvdbg(x...)
#endif
-/* The following definitions map the encoded LED setting to GPIO settings */
-
/****************************************************************************
* Private Data
****************************************************************************/
diff --git a/nuttx/configs/ea3152/src/up_leds.c b/nuttx/configs/ea3152/src/up_leds.c
index 4c6aeea0f..bbd393beb 100644
--- a/nuttx/configs/ea3152/src/up_leds.c
+++ b/nuttx/configs/ea3152/src/up_leds.c
@@ -2,7 +2,7 @@
* configs/ea3152/src/up_leds.c
* arch/arm/src/board/up_leds.c
*
- * Copyright (C) 2011 Gregory Nutt. All rights reserved.
+ * Copyright (C) 2011, 2013 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <gnutt@nuttx.org>
*
* Redistribution and use in source and binary forms, with or without
@@ -55,13 +55,11 @@
* Definitions
****************************************************************************/
-/* Enables debug output from this file (needs CONFIG_DEBUG with
- * CONFIG_DEBUG_VERBOSE too)
+/* CONFIG_DEBUG_LEDS enables debug output from this file (needs CONFIG_DEBUG
+ * with CONFIG_DEBUG_VERBOSE too)
*/
-#undef LED_DEBUG /* Define to enable debug */
-
-#ifdef LED_DEBUG
+#ifdef CONFIG_DEBUG_LEDS
# define leddbg lldbg
# define ledvdbg llvdbg
#else
@@ -69,8 +67,6 @@
# define ledvdbg(x...)
#endif
-/* The following definitions map the encoded LED setting to GPIO settings */
-
/****************************************************************************
* Private Data
****************************************************************************/
diff --git a/nuttx/configs/eagle100/src/up_leds.c b/nuttx/configs/eagle100/src/up_leds.c
index 5566b58b2..4976c4bcb 100644
--- a/nuttx/configs/eagle100/src/up_leds.c
+++ b/nuttx/configs/eagle100/src/up_leds.c
@@ -2,7 +2,7 @@
* configs/eagle100/src/up_leds.c
* arch/arm/src/board/up_leds.c
*
- * Copyright (C) 2009-2010 Gregory Nutt. All rights reserved.
+ * Copyright (C) 2009-2010, 2013 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <gnutt@nuttx.org>
*
* Redistribution and use in source and binary forms, with or without
@@ -55,13 +55,11 @@
* Definitions
****************************************************************************/
-/* Enables debug output from this file (needs CONFIG_DEBUG with
- * CONFIG_DEBUG_VERBOSE too)
+/* CONFIG_DEBUG_LEDS enables debug output from this file (needs CONFIG_DEBUG
+ * with CONFIG_DEBUG_VERBOSE too)
*/
-#undef LED_DEBUG /* Define to enable debug */
-
-#ifdef LED_DEBUG
+#ifdef CONFIG_DEBUG_LEDS
# define leddbg lldbg
# define ledvdbg llvdbg
#else
@@ -71,7 +69,7 @@
/* Dump GPIO registers */
-#ifdef LED_DEBUG
+#ifdef CONFIG_DEBUG_LEDS
# define led_dumpgpio(m) lm_dumpgpio(LED_GPIO, m)
#else
# define led_dumpgpio(m)
diff --git a/nuttx/configs/ekk-lm3s9b96/src/up_leds.c b/nuttx/configs/ekk-lm3s9b96/src/up_leds.c
index e6abe1a8a..d3c940f5a 100644
--- a/nuttx/configs/ekk-lm3s9b96/src/up_leds.c
+++ b/nuttx/configs/ekk-lm3s9b96/src/up_leds.c
@@ -2,7 +2,7 @@
* configs/lm3s6965-ek/src/up_leds.c
* arch/arm/src/board/up_leds.c
*
- * Copyright (C) 2012 Gregory Nutt. All rights reserved.
+ * Copyright (C) 2012-2013 Gregory Nutt. All rights reserved.
* Authors: Gregory Nutt <gnutt@nuttx.org>
* Jose Pablo Rojas V. <jrojas@nx-engineering.com>
*
@@ -56,13 +56,11 @@
* Definitions
****************************************************************************/
-/* Enables debug output from this file (needs CONFIG_DEBUG with
- * CONFIG_DEBUG_VERBOSE too)
+/* CONFIG_DEBUG_LEDS enables debug output from this file (needs CONFIG_DEBUG
+ * with CONFIG_DEBUG_VERBOSE too)
*/
-#undef LED_DEBUG /* Define to enable debug */
-
-#ifdef LED_DEBUG
+#ifdef CONFIG_DEBUG_LEDS
# define leddbg lldbg
# define ledvdbg llvdbg
#else
@@ -72,7 +70,7 @@
/* Dump GPIO registers */
-#ifdef LED_DEBUG
+#ifdef CONFIG_DEBUG_LEDS
# define led_dumpgpio(m) lm_dumpgpio(LED_GPIO, m)
#else
# define led_dumpgpio(m)
diff --git a/nuttx/configs/fire-stm32v2/src/up_autoleds.c b/nuttx/configs/fire-stm32v2/src/up_autoleds.c
index dcc3d8708..7127b8608 100644
--- a/nuttx/configs/fire-stm32v2/src/up_autoleds.c
+++ b/nuttx/configs/fire-stm32v2/src/up_autoleds.c
@@ -2,7 +2,7 @@
* configs/fire-stm32v2/src/up_autoleds.c
* arch/arm/src/board/up_autoleds.c
*
- * Copyright (C) 2012 Gregory Nutt. All rights reserved.
+ * Copyright (C) 2012-2013 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <gnutt@nuttx.org>
*
* Redistribution and use in source and binary forms, with or without
@@ -57,13 +57,11 @@
* Definitions
****************************************************************************/
-/* Enables debug output from this file (needs CONFIG_DEBUG with
- * CONFIG_DEBUG_VERBOSE too)
+/* CONFIG_DEBUG_LEDS enables debug output from this file (needs CONFIG_DEBUG
+ * with CONFIG_DEBUG_VERBOSE too)
*/
-#undef LED_DEBUG /* Define to enable debug */
-
-#ifdef LED_DEBUG
+#ifdef CONFIG_DEBUG_LEDS
# define leddbg lldbg
# define ledvdbg llvdbg
#else
diff --git a/nuttx/configs/fire-stm32v2/src/up_userleds.c b/nuttx/configs/fire-stm32v2/src/up_userleds.c
index 574c2c5b3..4a996af9c 100644
--- a/nuttx/configs/fire-stm32v2/src/up_userleds.c
+++ b/nuttx/configs/fire-stm32v2/src/up_userleds.c
@@ -2,7 +2,7 @@
* configs/fire-stm32v2/src/up_userleds.c
* arch/arm/src/board/up_userleds.c
*
- * Copyright (C) 2012 Gregory Nutt. All rights reserved.
+ * Copyright (C) 2012-2013 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <gnutt@nuttx.org>
*
* Redistribution and use in source and binary forms, with or without
@@ -58,13 +58,11 @@
* Definitions
****************************************************************************/
-/* Enables debug output from this file (needs CONFIG_DEBUG with
- * CONFIG_DEBUG_VERBOSE too)
+/* CONFIG_DEBUG_LEDS enables debug output from this file (needs CONFIG_DEBUG
+ * with CONFIG_DEBUG_VERBOSE too)
*/
-#undef LED_DEBUG /* Define to enable debug */
-
-#ifdef LED_DEBUG
+#ifdef CONFIG_DEBUG_LEDS
# define leddbg lldbg
# define ledvdbg llvdbg
#else
diff --git a/nuttx/configs/hymini-stm32v/src/up_leds.c b/nuttx/configs/hymini-stm32v/src/up_leds.c
index 5eac5a045..8c678cb99 100644
--- a/nuttx/configs/hymini-stm32v/src/up_leds.c
+++ b/nuttx/configs/hymini-stm32v/src/up_leds.c
@@ -2,7 +2,7 @@
* configs/hymini-stm32v/src/up_leds.c
* arch/arm/src/board/up_leds.c
*
- * Copyright (C) 2009, 2011 Gregory Nutt. All rights reserved.
+ * Copyright (C) 2009, 2011, 2013 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <gnutt@nuttx.org>
* Laurent Latil <laurent@latil.nom.fr>
*
@@ -57,13 +57,11 @@
* Definitions
****************************************************************************/
-/* Enables debug output from this file (needs CONFIG_DEBUG with
- * CONFIG_DEBUG_VERBOSE too)
+/* CONFIG_DEBUG_LEDS enables debug output from this file (needs CONFIG_DEBUG
+ * with CONFIG_DEBUG_VERBOSE too)
*/
-#undef LED_DEBUG /* Define to enable debug */
-
-#ifdef LED_DEBUG
+#ifdef CONFIG_DEBUG_LEDS
# define leddbg lldbg
# define ledvdbg llvdbg
#else
diff --git a/nuttx/configs/kwikstik-k40/src/up_leds.c b/nuttx/configs/kwikstik-k40/src/up_leds.c
index a455fcc34..71a02df63 100644
--- a/nuttx/configs/kwikstik-k40/src/up_leds.c
+++ b/nuttx/configs/kwikstik-k40/src/up_leds.c
@@ -2,7 +2,7 @@
* configs/kwikstik-k40/src/up_leds.c
* arch/arm/src/board/up_leds.c
*
- * Copyright (C) 2011 Gregory Nutt. All rights reserved.
+ * Copyright (C) 2011, 2013 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <gnutt@nuttx.org>
*
* Redistribution and use in source and binary forms, with or without
@@ -46,13 +46,11 @@
* Definitions
****************************************************************************/
-/* Enables debug output from this file (needs CONFIG_DEBUG with
- * CONFIG_DEBUG_VERBOSE too)
+/* CONFIG_DEBUG_LEDS enables debug output from this file (needs CONFIG_DEBUG
+ * with CONFIG_DEBUG_VERBOSE too)
*/
-#undef LED_DEBUG /* Define to enable debug */
-
-#ifdef LED_DEBUG
+#ifdef CONFIG_DEBUG_LEDS
# define leddbg lldbg
# define ledvdbg llvdbg
#else
diff --git a/nuttx/configs/lincoln60/src/up_leds.c b/nuttx/configs/lincoln60/src/up_leds.c
index 3b8692d93..d0b2016ca 100644
--- a/nuttx/configs/lincoln60/src/up_leds.c
+++ b/nuttx/configs/lincoln60/src/up_leds.c
@@ -60,29 +60,25 @@
* Definitions
****************************************************************************/
-/* Enables debug output from this file (needs CONFIG_DEBUG with
- * CONFIG_DEBUG_VERBOSE too)
+/* CONFIG_DEBUG_LEDS enables debug output from this file (needs CONFIG_DEBUG
+ * with CONFIG_DEBUG_VERBOSE too)
*/
-#undef LED_DEBUG /* Define to enable debug */
-#undef LED_VERBOSE /* Define to enable verbose debug */
-
-#ifdef LED_DEBUG
+#ifdef CONFIG_DEBUG_LEDS
# define leddbg lldbg
-# ifdef LED_VERBOSE
+# ifdef CONFIG_DEBUG_VERBOSE
# define ledvdbg lldbg
# else
# define ledvdbg(x...)
# endif
#else
-# undef LED_VERBOSE
# define leddbg(x...)
# define ledvdbg(x...)
#endif
/* Dump GPIO registers */
-#ifdef LED_VERBOSE
+#if defined(CONFIG_DEBUG_VERBOSE) && defined(CONFIG_DEBUG_LEDS)
# define led_dumpgpio(m) lpc17_dumpgpio(LINCOLN60_LED2, m)
#else
# define led_dumpgpio(m)
diff --git a/nuttx/configs/lm3s6432-s2e/src/up_leds.c b/nuttx/configs/lm3s6432-s2e/src/up_leds.c
index e0dd53f28..a159cbb50 100644
--- a/nuttx/configs/lm3s6432-s2e/src/up_leds.c
+++ b/nuttx/configs/lm3s6432-s2e/src/up_leds.c
@@ -2,7 +2,7 @@
* configs/lm3s6432-s2e/src/up_leds.c
* arch/arm/src/board/up_leds.c
*
- * Copyright (C) 2010 Gregory Nutt. All rights reserved.
+ * Copyright (C) 2010, 2013 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <gnutt@nuttx.org>
*
* Redistribution and use in source and binary forms, with or without
@@ -55,13 +55,11 @@
* Definitions
****************************************************************************/
-/* Enables debug output from this file (needs CONFIG_DEBUG with
- * CONFIG_DEBUG_VERBOSE too)
+/* CONFIG_DEBUG_LEDS enables debug output from this file (needs CONFIG_DEBUG
+ * with CONFIG_DEBUG_VERBOSE too)
*/
-#undef LED_DEBUG /* Define to enable debug */
-
-#ifdef LED_DEBUG
+#ifdef CONFIG_DEBUG_LEDS
# define leddbg lldbg
# define ledvdbg llvdbg
#else
@@ -71,7 +69,7 @@
/* Dump GPIO registers */
-#ifdef LED_DEBUG
+#ifdef CONFIG_DEBUG_LEDS
# define led_dumpgpio(m) lm_dumpgpio(LED_GPIO, m)
#else
# define led_dumpgpio(m)
diff --git a/nuttx/configs/lm3s6965-ek/src/up_leds.c b/nuttx/configs/lm3s6965-ek/src/up_leds.c
index 0e6c5e50f..6139a7922 100644
--- a/nuttx/configs/lm3s6965-ek/src/up_leds.c
+++ b/nuttx/configs/lm3s6965-ek/src/up_leds.c
@@ -2,7 +2,7 @@
* configs/lm3s6965-ek/src/up_leds.c
* arch/arm/src/board/up_leds.c
*
- * Copyright (C) 2010 Gregory Nutt. All rights reserved.
+ * Copyright (C) 2010, 2013 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <gnutt@nuttx.org>
*
* Redistribution and use in source and binary forms, with or without
@@ -55,13 +55,11 @@
* Definitions
****************************************************************************/
-/* Enables debug output from this file (needs CONFIG_DEBUG with
- * CONFIG_DEBUG_VERBOSE too)
+/* CONFIG_DEBUG_LEDS enables debug output from this file (needs CONFIG_DEBUG
+ * with CONFIG_DEBUG_VERBOSE too)
*/
-#undef LED_DEBUG /* Define to enable debug */
-
-#ifdef LED_DEBUG
+#ifdef CONFIG_DEBUG_LEDS
# define leddbg lldbg
# define ledvdbg llvdbg
#else
@@ -71,7 +69,7 @@
/* Dump GPIO registers */
-#ifdef LED_DEBUG
+#ifdef CONFIG_DEBUG_LEDS
# define led_dumpgpio(m) lm_dumpgpio(LED_GPIO, m)
#else
# define led_dumpgpio(m)
diff --git a/nuttx/configs/lm3s8962-ek/src/up_leds.c b/nuttx/configs/lm3s8962-ek/src/up_leds.c
index a20617f1e..5adf27d42 100644
--- a/nuttx/configs/lm3s8962-ek/src/up_leds.c
+++ b/nuttx/configs/lm3s8962-ek/src/up_leds.c
@@ -2,7 +2,7 @@
* configs/lm3s8962-ek/src/up_leds.c
* arch/arm/src/board/up_leds.c
*
- * Copyright (C) 2010 Gregory Nutt. All rights reserved.
+ * Copyright (C) 2010, 2013 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <gnutt@nuttx.org>
*
* Redistribution and use in source and binary forms, with or without
@@ -55,13 +55,11 @@
* Definitions
****************************************************************************/
-/* Enables debug output from this file (needs CONFIG_DEBUG with
- * CONFIG_DEBUG_VERBOSE too)
+/* CONFIG_DEBUG_LEDS enables debug output from this file (needs CONFIG_DEBUG
+ * with CONFIG_DEBUG_VERBOSE too)
*/
-#undef LED_DEBUG /* Define to enable debug */
-
-#ifdef LED_DEBUG
+#ifdef CONFIG_DEBUG_LEDS
# define leddbg lldbg
# define ledvdbg llvdbg
#else
@@ -71,7 +69,7 @@
/* Dump GPIO registers */
-#ifdef LED_DEBUG
+#ifdef CONFIG_DEBUG_LEDS
# define led_dumpgpio(m) lm_dumpgpio(LED_GPIO, m)
#else
# define led_dumpgpio(m)
diff --git a/nuttx/configs/lpc4330-xplorer/src/up_autoleds.c b/nuttx/configs/lpc4330-xplorer/src/up_autoleds.c
index b19e33459..badeb9a16 100644
--- a/nuttx/configs/lpc4330-xplorer/src/up_autoleds.c
+++ b/nuttx/configs/lpc4330-xplorer/src/up_autoleds.c
@@ -2,7 +2,7 @@
* configs/lpc4330-xplorer/src/up_autoleds.c
* arch/arm/src/board/up_autoleds.c
*
- * Copyright (C) 2012 Gregory Nutt. All rights reserved.
+ * Copyright (C) 2012-2013 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <gnutt@nuttx.org>
*
* Redistribution and use in source and binary forms, with or without
@@ -90,11 +90,11 @@
*/
/* Debug definitions ********************************************************/
-/* Enables debug output from this file (needs CONFIG_DEBUG with
- * CONFIG_DEBUG_VERBOSE too)
+/* CONFIG_DEBUG_LEDS enables debug output from this file (needs CONFIG_DEBUG
+ * with CONFIG_DEBUG_VERBOSE too)
*/
-#ifdef CONFIG_DEBUG_LED
+#ifdef CONFIG_DEBUG_LEDS
# define leddbg lldbg
# ifdef CONFIG_DEBUG_VERBOSE
# define LED_VERBOSE 1
diff --git a/nuttx/configs/lpc4330-xplorer/src/up_userleds.c b/nuttx/configs/lpc4330-xplorer/src/up_userleds.c
index 2d8b5b511..c91f4df3b 100644
--- a/nuttx/configs/lpc4330-xplorer/src/up_userleds.c
+++ b/nuttx/configs/lpc4330-xplorer/src/up_userleds.c
@@ -2,7 +2,7 @@
* configs/lpc4330-xplorer/src/up_userleds.c
* arch/arm/src/board/up_userleds.c
*
- * Copyright (C) 2012 Gregory Nutt. All rights reserved.
+ * Copyright (C) 2012-2013 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <gnutt@nuttx.org>
*
* Redistribution and use in source and binary forms, with or without
@@ -68,11 +68,11 @@
*/
/* Debug definitions ********************************************************/
-/* Enables debug output from this file (needs CONFIG_DEBUG with
- * CONFIG_DEBUG_VERBOSE too)
+/* CONFIG_DEBUG_LEDS enables debug output from this file (needs CONFIG_DEBUG
+ * with CONFIG_DEBUG_VERBOSE too)
*/
-#ifdef CONFIG_DEBUG_LED
+#ifdef CONFIG_DEBUG_LEDS
# define leddbg lldbg
# ifdef CONFIG_DEBUG_VERBOSE
# define LED_VERBOSE 1
diff --git a/nuttx/configs/lpcxpresso-lpc1768/src/up_leds.c b/nuttx/configs/lpcxpresso-lpc1768/src/up_leds.c
index 85539b378..d0dc19727 100644
--- a/nuttx/configs/lpcxpresso-lpc1768/src/up_leds.c
+++ b/nuttx/configs/lpcxpresso-lpc1768/src/up_leds.c
@@ -55,22 +55,18 @@
* Definitions
****************************************************************************/
-/* Enables debug output from this file (needs CONFIG_DEBUG with
- * CONFIG_DEBUG_VERBOSE too)
+/* CONFIG_DEBUG_LEDS enables debug output from this file (needs CONFIG_DEBUG
+ * with CONFIG_DEBUG_VERBOSE too)
*/
-#undef LED_DEBUG /* Define to enable debug */
-#undef LED_VERBOSE /* Define to enable verbose debug */
-
-#ifdef LED_DEBUG
+#ifdef CONFIG_DEBUG_LEDS
# define leddbg lldbg
-# ifdef LED_VERBOSE
+# ifdef CONFIG_DEBUG_VERBOSE
# define ledvdbg lldbg
# else
# define ledvdbg(x...)
# endif
#else
-# undef LED_VERBOSE
# define leddbg(x...)
# define ledvdbg(x...)
#endif
diff --git a/nuttx/configs/mbed/src/up_leds.c b/nuttx/configs/mbed/src/up_leds.c
index c8c78e3ad..3a2f160ed 100644
--- a/nuttx/configs/mbed/src/up_leds.c
+++ b/nuttx/configs/mbed/src/up_leds.c
@@ -60,29 +60,25 @@
* Definitions
****************************************************************************/
-/* Enables debug output from this file (needs CONFIG_DEBUG with
- * CONFIG_DEBUG_VERBOSE too)
+/* CONFIG_DEBUG_LEDS enables debug output from this file (needs CONFIG_DEBUG
+ * with CONFIG_DEBUG_VERBOSE too)
*/
-#undef LED_DEBUG /* Define to enable debug */
-#undef LED_VERBOSE /* Define to enable verbose debug */
-
-#ifdef LED_DEBUG
+#ifdef CONFIG_DEBUG_LEDS
# define leddbg lldbg
-# ifdef LED_VERBOSE
+# ifdef CONFIG_DEBUG_VERBOSE
# define ledvdbg lldbg
# else
# define ledvdbg(x...)
# endif
#else
-# undef LED_VERBOSE
# define leddbg(x...)
# define ledvdbg(x...)
#endif
/* Dump GPIO registers */
-#ifdef LED_VERBOSE
+#if defined(CONFIG_DEBUG_VERBOSE) && defined(CONFIG_DEBUG_LEDS)
# define led_dumpgpio(m) lpc17_dumpgpio(MBED_LED3, m)
#else
# define led_dumpgpio(m)
diff --git a/nuttx/configs/ne64badge/src/up_leds.c b/nuttx/configs/ne64badge/src/up_leds.c
index 73991f570..d4aab0d3b 100644
--- a/nuttx/configs/ne64badge/src/up_leds.c
+++ b/nuttx/configs/ne64badge/src/up_leds.c
@@ -2,7 +2,7 @@
* configs/ne64badge/src/up_leds.c
* arch/arm/src/board/up_leds.c
*
- * Copyright (C) 2011 Gregory Nutt. All rights reserved.
+ * Copyright (C) 2011, 2013 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <gnutt@nuttx.org>
*
* Redistribution and use in source and binary forms, with or without
@@ -52,29 +52,25 @@
* Pre-processor Definitions
****************************************************************************/
-/* Enables debug output from this file (needs CONFIG_DEBUG with
- * CONFIG_DEBUG_VERBOSE too)
+/* CONFIG_DEBUG_LEDS enables debug output from this file (needs CONFIG_DEBUG
+ * with CONFIG_DEBUG_VERBOSE too)
*/
-#undef LED_DEBUG /* Define to enable debug */
-#undef LED_VERBOSE /* Define to enable verbose debug */
-
-#ifdef LED_DEBUG
+#ifdef CONFIG_DEBUG_LEDS
# define leddbg lldbg
-# ifdef LED_VERBOSE
+# ifdef CONFIG_DEBUG_VERBOSE
# define ledvdbg lldbg
# else
# define ledvdbg(x...)
# endif
#else
-# undef LED_VERBOSE
# define leddbg(x...)
# define ledvdbg(x...)
#endif
/* Dump GPIO registers */
-#ifdef LED_VERBOSE
+#if defined(CONFIG_DEBUG_VERBOSE) && defined(CONFIG_DEBUG_LEDS)
# define led_dumpgpio(m) m9s12_dumpgpio(m)
#else
# define led_dumpgpio(m)
diff --git a/nuttx/configs/nucleus2g/src/up_leds.c b/nuttx/configs/nucleus2g/src/up_leds.c
index e1c39f515..a3d4569cc 100644
--- a/nuttx/configs/nucleus2g/src/up_leds.c
+++ b/nuttx/configs/nucleus2g/src/up_leds.c
@@ -60,29 +60,25 @@
* Definitions
****************************************************************************/
-/* Enables debug output from this file (needs CONFIG_DEBUG with
- * CONFIG_DEBUG_VERBOSE too)
+/* CONFIG_DEBUG_LEDS enables debug output from this file (needs CONFIG_DEBUG
+ * with CONFIG_DEBUG_VERBOSE too)
*/
-#undef LED_DEBUG /* Define to enable debug */
-#undef LED_VERBOSE /* Define to enable verbose debug */
-
-#ifdef LED_DEBUG
+#ifdef CONFIG_DEBUG_LEDS
# define leddbg lldbg
-# ifdef LED_VERBOSE
+# ifdef CONFIG_DEBUG_VERBOSE
# define ledvdbg lldbg
# else
# define ledvdbg(x...)
# endif
#else
-# undef LED_VERBOSE
# define leddbg(x...)
# define ledvdbg(x...)
#endif
/* Dump GPIO registers */
-#ifdef LED_VERBOSE
+#if defined(CONFIG_DEBUG_VERBOSE) && defined(CONFIG_DEBUG_LEDS)
# define led_dumpgpio(m) lpc17_dumpgpio(NUCLEUS2G_LED1_A, m)
#else
# define led_dumpgpio(m)
diff --git a/nuttx/configs/nutiny-nuc120/src/nuc_led.c b/nuttx/configs/nutiny-nuc120/src/nuc_led.c
index 2482e7da0..64c34ad2b 100644
--- a/nuttx/configs/nutiny-nuc120/src/nuc_led.c
+++ b/nuttx/configs/nutiny-nuc120/src/nuc_led.c
@@ -76,20 +76,30 @@
* Definitions
****************************************************************************/
-/* Enables debug output from this file (needs CONFIG_DEBUG with
- * CONFIG_DEBUG_VERBOSE too)
+/* CONFIG_DEBUG_LEDS enables debug output from this file (needs CONFIG_DEBUG
+ * with CONFIG_DEBUG_VERBOSE too)
*/
-#undef LED_DEBUG /* Define to enable debug */
-
-#ifdef LED_DEBUG
+#ifdef CONFIG_DEBUG_LEDS
# define leddbg lldbg
-# define ledvdbg llvdbg
+# ifdef CONFIG_DEBUG_VERBOSE
+# define ledvdbg lldbg
+# else
+# define ledvdbg(x...)
+# endif
#else
# define leddbg(x...)
# define ledvdbg(x...)
#endif
+/* Dump GPIO registers */
+
+#if defined(CONFIG_DEBUG_VERBOSE) && defined(CONFIG_DEBUG_LEDS)
+# define led_dumpgpio(m) nuc_dumpgpio(GPIO_LED, m)
+#else
+# define led_dumpgpio(m)
+#endif
+
/****************************************************************************
* Private Data
****************************************************************************/
@@ -112,7 +122,9 @@
void nuc_ledinit(void)
{
+ led_dumpgpio("Before configuration");
nuc_configgpio(GPIO_LED);
+ led_dumpgpio("After configuration");
}
/****************************************************************************
diff --git a/nuttx/configs/olimex-lpc1766stk/src/up_leds.c b/nuttx/configs/olimex-lpc1766stk/src/up_leds.c
index e590be39f..b55d3a76f 100644
--- a/nuttx/configs/olimex-lpc1766stk/src/up_leds.c
+++ b/nuttx/configs/olimex-lpc1766stk/src/up_leds.c
@@ -2,7 +2,7 @@
* configs/olimex-lpc1766stk/src/up_leds.c
* arch/arm/src/board/up_leds.c
*
- * Copyright (C) 2010-2011 Gregory Nutt. All rights reserved.
+ * Copyright (C) 2010-2011, 2013 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <gnutt@nuttx.org>
*
* Redistribution and use in source and binary forms, with or without
@@ -58,30 +58,26 @@
* Definitions
****************************************************************************/
-/* Enables debug output from this file (needs CONFIG_DEBUG with
- * CONFIG_DEBUG_VERBOSE too)
+/* CONFIG_DEBUG_LEDS enables debug output from this file (needs CONFIG_DEBUG
+ * with CONFIG_DEBUG_VERBOSE too)
*/
-#undef LED_DEBUG /* Define to enable debug */
-#undef LED_VERBOSE /* Define to enable verbose debug */
-
-#ifdef LED_DEBUG
-# define leddbg lldbg
-# ifdef LED_VERBOSE
+#ifdef CONFIG_DEBUG_LEDS
+# define leddbg lldbg
+# ifdef CONFIG_DEBUG_VERBOSE
# define ledvdbg lldbg
# else
# define ledvdbg(x...)
# endif
#else
-# undef LED_VERBOSE
# define leddbg(x...)
# define ledvdbg(x...)
#endif
/* Dump GPIO registers */
-#ifdef LED_VERBOSE
-# define led_dumpgpio(m) lpc17_dumpgpio(???, m)
+#if defined(CONFIG_DEBUG_VERBOSE) && defined(CONFIG_DEBUG_LEDS)
+# define led_dumpgpio(m) lpc17_dumpgpio(LPC1766STK_LED1, m)
#else
# define led_dumpgpio(m)
#endif
diff --git a/nuttx/configs/open1788/src/lpc17_autoleds.c b/nuttx/configs/open1788/src/lpc17_autoleds.c
index 66cfc1734..80d682df5 100644
--- a/nuttx/configs/open1788/src/lpc17_autoleds.c
+++ b/nuttx/configs/open1788/src/lpc17_autoleds.c
@@ -134,29 +134,25 @@
#define LED_IDLE_OFF_SETBITS ((0) << OFF_SETBITS_SHIFT)
#define LED_IDLE_OFF_CLRBITS ((OPEN1788_LED4) << OFF_CLRBITS_SHIFT)
-/* Enables debug output from this file (needs CONFIG_DEBUG with
- * CONFIG_DEBUG_VERBOSE too)
+/* CONFIG_DEBUG_LEDS enables debug output from this file (needs CONFIG_DEBUG
+ * with CONFIG_DEBUG_VERBOSE too)
*/
-#undef LED_DEBUG /* Define to enable debug */
-#undef LED_VERBOSE /* Define to enable verbose debug */
-
-#ifdef LED_DEBUG
-# define leddbg lldbg
-# ifdef LED_VERBOSE
+#ifdef CONFIG_DEBUG_LEDS
+# define leddbg lldbg
+# ifdef CONFIG_DEBUG_VERBOSE
# define ledvdbg lldbg
# else
# define ledvdbg(x...)
# endif
#else
-# undef LED_VERBOSE
# define leddbg(x...)
# define ledvdbg(x...)
#endif
/* Dump GPIO registers */
-#ifdef LED_VERBOSE
+#if defined(CONFIG_DEBUG_VERBOSE) && defined(CONFIG_DEBUG_LEDS)
# define led_dumpgpio(m) lpc17_dumpgpio(???, m)
#else
# define led_dumpgpio(m)
diff --git a/nuttx/configs/open1788/src/lpc17_userleds.c b/nuttx/configs/open1788/src/lpc17_userleds.c
index dacea5a1c..bf0300e25 100644
--- a/nuttx/configs/open1788/src/lpc17_userleds.c
+++ b/nuttx/configs/open1788/src/lpc17_userleds.c
@@ -60,20 +60,30 @@
* Definitions
****************************************************************************/
-/* Enables debug output from this file (needs CONFIG_DEBUG with
- * CONFIG_DEBUG_VERBOSE too)
+/* CONFIG_DEBUG_LEDS enables debug output from this file (needs CONFIG_DEBUG
+ * with CONFIG_DEBUG_VERBOSE too)
*/
-#undef LED_DEBUG /* Define to enable debug */
-
-#ifdef LED_DEBUG
-# define leddbg lldbg
-# define ledvdbg llvdbg
+#ifdef CONFIG_DEBUG_LEDS
+# define leddbg lldbg
+# ifdef CONFIG_DEBUG_VERBOSE
+# define ledvdbg lldbg
+# else
+# define ledvdbg(x...)
+# endif
#else
# define leddbg(x...)
# define ledvdbg(x...)
#endif
+/* Dump GPIO registers */
+
+#if defined(CONFIG_DEBUG_VERBOSE) && defined(CONFIG_DEBUG_LEDS)
+# define led_dumpgpio(m) lpc17_dumpgpio(???, m)
+#else
+# define led_dumpgpio(m)
+#endif
+
/****************************************************************************
* Private Data
****************************************************************************/
diff --git a/nuttx/configs/pjrc-8051/src/up_leds.c b/nuttx/configs/pjrc-8051/src/up_leds.c
index 64446b5e3..18e7b461d 100644
--- a/nuttx/configs/pjrc-8051/src/up_leds.c
+++ b/nuttx/configs/pjrc-8051/src/up_leds.c
@@ -1,7 +1,7 @@
/************************************************************************
* up_leds.c
*
- * Copyright (C) 2007, 2009 Gregory Nutt. All rights reserved.
+ * Copyright (C) 2007, 2009, 2013 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <gnutt@nuttx.org>
*
* Redistribution and use in source and binary forms, with or without
@@ -57,7 +57,7 @@ static uint8_t g_ledstate;
* Private Functions
************************************************************************/
-#if defined(CONFIG_LED_DEBUG) && defined(CONFIG_ARCH_LEDS)
+#if defined(CONFIG_DEBUG_LEDS) && defined(CONFIG_ARCH_LEDS)
static void _up_puthex(uint8_t hex) __naked
{
hex; /* To avoid unreferenced argument warning */
diff --git a/nuttx/configs/sam3u-ek/src/up_leds.c b/nuttx/configs/sam3u-ek/src/up_leds.c
index 28a2cead5..72c565bd1 100644
--- a/nuttx/configs/sam3u-ek/src/up_leds.c
+++ b/nuttx/configs/sam3u-ek/src/up_leds.c
@@ -58,13 +58,11 @@
* Definitions
****************************************************************************/
-/* Enables debug output from this file (needs CONFIG_DEBUG with
- * CONFIG_DEBUG_VERBOSE too)
+/* CONFIG_DEBUG_LEDS enables debug output from this file (needs CONFIG_DEBUG
+ * with CONFIG_DEBUG_VERBOSE too)
*/
-#undef LED_DEBUG /* Define to enable debug */
-
-#ifdef LED_DEBUG
+#ifdef CONFIG_DEBUG_LEDS
# define leddbg lldbg
# define ledvdbg llvdbg
#else
diff --git a/nuttx/configs/shenzhou/src/up_autoleds.c b/nuttx/configs/shenzhou/src/up_autoleds.c
index 1ce25e80e..522859f3e 100644
--- a/nuttx/configs/shenzhou/src/up_autoleds.c
+++ b/nuttx/configs/shenzhou/src/up_autoleds.c
@@ -2,7 +2,7 @@
* configs/shenzhou/src/up_autoleds.c
* arch/arm/src/board/up_autoleds.c
*
- * Copyright (C) 2012 Gregory Nutt. All rights reserved.
+ * Copyright (C) 2012-2013 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <gnutt@nuttx.org>
*
* Redistribution and use in source and binary forms, with or without
@@ -57,13 +57,11 @@
* Definitions
****************************************************************************/
-/* Enables debug output from this file (needs CONFIG_DEBUG with
- * CONFIG_DEBUG_VERBOSE too)
+/* CONFIG_DEBUG_LEDS enables debug output from this file (needs CONFIG_DEBUG
+ * with CONFIG_DEBUG_VERBOSE too)
*/
-#undef LED_DEBUG /* Define to enable debug */
-
-#ifdef LED_DEBUG
+#ifdef CONFIG_DEBUG_LEDS
# define leddbg lldbg
# define ledvdbg llvdbg
#else
diff --git a/nuttx/configs/shenzhou/src/up_userleds.c b/nuttx/configs/shenzhou/src/up_userleds.c
index 0e690e825..60fa7d9c3 100644
--- a/nuttx/configs/shenzhou/src/up_userleds.c
+++ b/nuttx/configs/shenzhou/src/up_userleds.c
@@ -2,7 +2,7 @@
* configs/shenzhou/src/up_userleds.c
* arch/arm/src/board/up_userleds.c
*
- * Copyright (C) 2012 Gregory Nutt. All rights reserved.
+ * Copyright (C) 2012-2013 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <gnutt@nuttx.org>
*
* Redistribution and use in source and binary forms, with or without
@@ -58,13 +58,11 @@
* Definitions
****************************************************************************/
-/* Enables debug output from this file (needs CONFIG_DEBUG with
- * CONFIG_DEBUG_VERBOSE too)
+/* CONFIG_DEBUG_LEDS enables debug output from this file (needs CONFIG_DEBUG
+ * with CONFIG_DEBUG_VERBOSE too)
*/
-#undef LED_DEBUG /* Define to enable debug */
-
-#ifdef LED_DEBUG
+#ifdef CONFIG_DEBUG_LEDS
# define leddbg lldbg
# define ledvdbg llvdbg
#else
diff --git a/nuttx/configs/stm3210e-eval/src/up_leds.c b/nuttx/configs/stm3210e-eval/src/up_leds.c
index 45a24684b..1266b7203 100644
--- a/nuttx/configs/stm3210e-eval/src/up_leds.c
+++ b/nuttx/configs/stm3210e-eval/src/up_leds.c
@@ -2,7 +2,7 @@
* configs/stm3210e_eval/src/up_leds.c
* arch/arm/src/board/up_leds.c
*
- * Copyright (C) 2009-2012 Gregory Nutt. All rights reserved.
+ * Copyright (C) 2009-2013 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <gnutt@nuttx.org>
*
* Redistribution and use in source and binary forms, with or without
@@ -57,13 +57,11 @@
* Definitions
****************************************************************************/
-/* Enables debug output from this file (needs CONFIG_DEBUG with
- * CONFIG_DEBUG_VERBOSE too)
+/* CONFIG_DEBUG_LEDS enables debug output from this file (needs CONFIG_DEBUG
+ * with CONFIG_DEBUG_VERBOSE too)
*/
-#undef LED_DEBUG /* Define to enable debug */
-
-#ifdef LED_DEBUG
+#ifdef CONFIG_DEBUG_LEDS
# define leddbg lldbg
# define ledvdbg llvdbg
#else
diff --git a/nuttx/configs/stm3220g-eval/src/up_autoleds.c b/nuttx/configs/stm3220g-eval/src/up_autoleds.c
index 068c07ab4..85010c504 100644
--- a/nuttx/configs/stm3220g-eval/src/up_autoleds.c
+++ b/nuttx/configs/stm3220g-eval/src/up_autoleds.c
@@ -58,13 +58,11 @@
* Definitions
****************************************************************************/
-/* Enables debug output from this file (needs CONFIG_DEBUG with
- * CONFIG_DEBUG_VERBOSE too)
+/* CONFIG_DEBUG_LEDS enables debug output from this file (needs CONFIG_DEBUG
+ * with CONFIG_DEBUG_VERBOSE too)
*/
-#undef LED_DEBUG /* Define to enable debug */
-
-#ifdef LED_DEBUG
+#ifdef CONFIG_DEBUG_LEDS
# define leddbg lldbg
# define ledvdbg llvdbg
#else
diff --git a/nuttx/configs/stm3220g-eval/src/up_userleds.c b/nuttx/configs/stm3220g-eval/src/up_userleds.c
index cc29349e9..682809afd 100644
--- a/nuttx/configs/stm3220g-eval/src/up_userleds.c
+++ b/nuttx/configs/stm3220g-eval/src/up_userleds.c
@@ -2,7 +2,7 @@
* configs/stm3220g_eval/src/up_leds.c
* arch/arm/src/board/up_leds.c
*
- * Copyright (C) 2012 Gregory Nutt. All rights reserved.
+ * Copyright (C) 2012-2013 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <gnutt@nuttx.org>
*
* Redistribution and use in source and binary forms, with or without
@@ -58,13 +58,11 @@
* Definitions
****************************************************************************/
-/* Enables debug output from this file (needs CONFIG_DEBUG with
- * CONFIG_DEBUG_VERBOSE too)
+/* CONFIG_DEBUG_LEDS enables debug output from this file (needs CONFIG_DEBUG
+ * with CONFIG_DEBUG_VERBOSE too)
*/
-#undef LED_DEBUG /* Define to enable debug */
-
-#ifdef LED_DEBUG
+#ifdef CONFIG_DEBUG_LEDS
# define leddbg lldbg
# define ledvdbg llvdbg
#else
diff --git a/nuttx/configs/stm3240g-eval/src/up_autoleds.c b/nuttx/configs/stm3240g-eval/src/up_autoleds.c
index 8e7f40da3..8474a0476 100644
--- a/nuttx/configs/stm3240g-eval/src/up_autoleds.c
+++ b/nuttx/configs/stm3240g-eval/src/up_autoleds.c
@@ -2,7 +2,7 @@
* configs/stm3240g_eval/src/up_autoleds.c
* arch/arm/src/board/up_autoleds.c
*
- * Copyright (C) 2011 Gregory Nutt. All rights reserved.
+ * Copyright (C) 2011, 2013 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <gnutt@nuttx.org>
*
* Redistribution and use in source and binary forms, with or without
@@ -58,13 +58,11 @@
* Definitions
****************************************************************************/
-/* Enables debug output from this file (needs CONFIG_DEBUG with
- * CONFIG_DEBUG_VERBOSE too)
+/* CONFIG_DEBUG_LEDS enables debug output from this file (needs CONFIG_DEBUG
+ * with CONFIG_DEBUG_VERBOSE too)
*/
-#undef LED_DEBUG /* Define to enable debug */
-
-#ifdef LED_DEBUG
+#ifdef CONFIG_DEBUG_LEDS
# define leddbg lldbg
# define ledvdbg llvdbg
#else
diff --git a/nuttx/configs/stm3240g-eval/src/up_userleds.c b/nuttx/configs/stm3240g-eval/src/up_userleds.c
index 4faf0dfd2..6607bb616 100644
--- a/nuttx/configs/stm3240g-eval/src/up_userleds.c
+++ b/nuttx/configs/stm3240g-eval/src/up_userleds.c
@@ -2,7 +2,7 @@
* configs/stm3240g_eval/src/up_userleds.c
* arch/arm/src/board/up_userleds.c
*
- * Copyright (C) 2011 Gregory Nutt. All rights reserved.
+ * Copyright (C) 2011, 2013 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <gnutt@nuttx.org>
*
* Redistribution and use in source and binary forms, with or without
@@ -58,13 +58,11 @@
* Definitions
****************************************************************************/
-/* Enables debug output from this file (needs CONFIG_DEBUG with
- * CONFIG_DEBUG_VERBOSE too)
+/* CONFIG_DEBUG_LEDS enables debug output from this file (needs CONFIG_DEBUG
+ * with CONFIG_DEBUG_VERBOSE too)
*/
-#undef LED_DEBUG /* Define to enable debug */
-
-#ifdef LED_DEBUG
+#ifdef CONFIG_DEBUG_LEDS
# define leddbg lldbg
# define ledvdbg llvdbg
#else
diff --git a/nuttx/configs/stm32f100rc_generic/src/up_leds.c b/nuttx/configs/stm32f100rc_generic/src/up_leds.c
index c7cf27d86..83e1761dc 100644
--- a/nuttx/configs/stm32f100rc_generic/src/up_leds.c
+++ b/nuttx/configs/stm32f100rc_generic/src/up_leds.c
@@ -1,7 +1,7 @@
/****************************************************************************
* configs/stm32f100rc_generic/src/up_leds.c
*
- * Copyright (C) 2012 Gregory Nutt. All rights reserved.
+ * Copyright (C) 2012-2013 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <gnutt@nuttx.org>
* Freddie Chopin <freddie_chopin@op.pl>
*
@@ -57,13 +57,11 @@
* Definitions
****************************************************************************/
-/* Enables debug output from this file (needs CONFIG_DEBUG with
- * CONFIG_DEBUG_VERBOSE too)
+/* CONFIG_DEBUG_LEDS enables debug output from this file (needs CONFIG_DEBUG
+ * with CONFIG_DEBUG_VERBOSE too)
*/
-#undef LED_DEBUG /* Define to enable debug */
-
-#ifdef LED_DEBUG
+#ifdef CONFIG_DEBUG_LEDS
# define leddbg lldbg
# define ledvdbg llvdbg
#else
diff --git a/nuttx/configs/stm32f3discovery/src/up_autoleds.c b/nuttx/configs/stm32f3discovery/src/up_autoleds.c
index d56b7db65..1191fb689 100644
--- a/nuttx/configs/stm32f3discovery/src/up_autoleds.c
+++ b/nuttx/configs/stm32f3discovery/src/up_autoleds.c
@@ -56,13 +56,11 @@
* Definitions
****************************************************************************/
-/* Enables debug output from this file (needs CONFIG_DEBUG with
- * CONFIG_DEBUG_VERBOSE too)
+/* CONFIG_DEBUG_LEDS enables debug output from this file (needs CONFIG_DEBUG
+ * with CONFIG_DEBUG_VERBOSE too)
*/
-#undef LED_DEBUG /* Define to enable debug */
-
-#ifdef LED_DEBUG
+#ifdef CONFIG_DEBUG_LEDS
# define leddbg lldbg
# define ledvdbg llvdbg
#else
diff --git a/nuttx/configs/stm32f3discovery/src/up_userleds.c b/nuttx/configs/stm32f3discovery/src/up_userleds.c
index 1b13de535..85b8b8346 100644
--- a/nuttx/configs/stm32f3discovery/src/up_userleds.c
+++ b/nuttx/configs/stm32f3discovery/src/up_userleds.c
@@ -56,13 +56,11 @@
* Definitions
****************************************************************************/
-/* Enables debug output from this file (needs CONFIG_DEBUG with
- * CONFIG_DEBUG_VERBOSE too)
+/* CONFIG_DEBUG_LEDS enables debug output from this file (needs CONFIG_DEBUG
+ * with CONFIG_DEBUG_VERBOSE too)
*/
-#undef LED_DEBUG /* Define to enable debug */
-
-#ifdef LED_DEBUG
+#ifdef CONFIG_DEBUG_LEDS
# define leddbg lldbg
# define ledvdbg llvdbg
#else
diff --git a/nuttx/configs/stm32f4discovery/src/up_autoleds.c b/nuttx/configs/stm32f4discovery/src/up_autoleds.c
index c72a54a02..985c1000f 100644
--- a/nuttx/configs/stm32f4discovery/src/up_autoleds.c
+++ b/nuttx/configs/stm32f4discovery/src/up_autoleds.c
@@ -2,7 +2,7 @@
* configs/stm32f4discovery/src/up_autoleds.c
* arch/arm/src/board/up_autoleds.c
*
- * Copyright (C) 2011-2012 Gregory Nutt. All rights reserved.
+ * Copyright (C) 2011-2013 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <gnutt@nuttx.org>
*
* Redistribution and use in source and binary forms, with or without
@@ -58,13 +58,11 @@
* Definitions
****************************************************************************/
-/* Enables debug output from this file (needs CONFIG_DEBUG with
- * CONFIG_DEBUG_VERBOSE too)
+/* CONFIG_DEBUG_LEDS enables debug output from this file (needs CONFIG_DEBUG
+ * with CONFIG_DEBUG_VERBOSE too)
*/
-#undef LED_DEBUG /* Define to enable debug */
-
-#ifdef LED_DEBUG
+#ifdef CONFIG_DEBUG_LEDS
# define leddbg lldbg
# define ledvdbg llvdbg
#else
diff --git a/nuttx/configs/stm32f4discovery/src/up_userleds.c b/nuttx/configs/stm32f4discovery/src/up_userleds.c
index 5981a12e6..919919c3e 100644
--- a/nuttx/configs/stm32f4discovery/src/up_userleds.c
+++ b/nuttx/configs/stm32f4discovery/src/up_userleds.c
@@ -59,13 +59,11 @@
* Definitions
****************************************************************************/
-/* Enables debug output from this file (needs CONFIG_DEBUG with
- * CONFIG_DEBUG_VERBOSE too)
+/* CONFIG_DEBUG_LEDS enables debug output from this file (needs CONFIG_DEBUG
+ * with CONFIG_DEBUG_VERBOSE too)
*/
-#undef LED_DEBUG /* Define to enable debug */
-
-#ifdef LED_DEBUG
+#ifdef CONFIG_DEBUG_LEDS
# define leddbg lldbg
# define ledvdbg llvdbg
#else
diff --git a/nuttx/configs/teensy/src/up_leds.c b/nuttx/configs/teensy/src/up_leds.c
index ce83b4999..545148709 100644
--- a/nuttx/configs/teensy/src/up_leds.c
+++ b/nuttx/configs/teensy/src/up_leds.c
@@ -2,7 +2,7 @@
* configs/teensy/src/up_leds.c
* arch/arm/src/board/up_leds.c
*
- * Copyright (C) 2011 Gregory Nutt. All rights reserved.
+ * Copyright (C) 2011, 2013 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <gnutt@nuttx.org>
*
* Redistribution and use in source and binary forms, with or without
@@ -56,22 +56,18 @@
* Definitions
****************************************************************************/
-/* Enables debug output from this file (needs CONFIG_DEBUG with
- * CONFIG_DEBUG_VERBOSE too)
+/* CONFIG_DEBUG_LEDS enables debug output from this file (needs CONFIG_DEBUG
+ * with CONFIG_DEBUG_VERBOSE too)
*/
-#undef LED_DEBUG /* Define to enable debug */
-#undef LED_VERBOSE /* Define to enable verbose debug */
-
-#ifdef LED_DEBUG
+#ifdef CONFIG_DEBUG_LEDS
# define leddbg lldbg
-# ifdef LED_VERBOSE
+# ifdef CONFIG_DEBUG_VERBOSE
# define ledvdbg lldbg
# else
# define ledvdbg(x...)
# endif
#else
-# undef LED_VERBOSE
# define leddbg(x...)
# define ledvdbg(x...)
#endif
diff --git a/nuttx/configs/twr-k60n512/src/up_leds.c b/nuttx/configs/twr-k60n512/src/up_leds.c
index df7aeeaa5..4c3c35006 100644
--- a/nuttx/configs/twr-k60n512/src/up_leds.c
+++ b/nuttx/configs/twr-k60n512/src/up_leds.c
@@ -2,7 +2,7 @@
* configs/twr-k60n512/src/up_leds.c
* arch/arm/src/board/up_leds.c
*
- * Copyright (C) 2011 Gregory Nutt. All rights reserved.
+ * Copyright (C) 2011, 2013 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <gnutt@nuttx.org>
*
* Redistribution and use in source and binary forms, with or without
@@ -118,13 +118,11 @@
#define LED_PANIC_OFF_SETBITS ((0) << OFF_SETBITS_SHIFT)
#define LED_PANIC_OFF_CLRBITS ((K60_LED4) << OFF_CLRBITS_SHIFT)
-/* Enables debug output from this file (needs CONFIG_DEBUG with
- * CONFIG_DEBUG_VERBOSE too)
+/* CONFIG_DEBUG_LEDS enables debug output from this file (needs CONFIG_DEBUG
+ * with CONFIG_DEBUG_VERBOSE too)
*/
-#undef LED_DEBUG /* Define to enable debug */
-
-#ifdef LED_DEBUG
+#ifdef CONFIG_DEBUG_LEDS
# define leddbg lldbg
# define ledvdbg llvdbg
#else
diff --git a/nuttx/configs/vsn/src/leds.c b/nuttx/configs/vsn/src/leds.c
index e440e5fce..5a674465d 100644
--- a/nuttx/configs/vsn/src/leds.c
+++ b/nuttx/configs/vsn/src/leds.c
@@ -53,18 +53,15 @@
#include "vsn.h"
-
/****************************************************************************
* Definitions
****************************************************************************/
-/* Enables debug output from this file (needs CONFIG_DEBUG with
- * CONFIG_DEBUG_VERBOSE too)
+/* CONFIG_DEBUG_LEDS enables debug output from this file (needs CONFIG_DEBUG
+ * with CONFIG_DEBUG_VERBOSE too)
*/
-#undef LED_DEBUG /* Define to enable debug */
-
-#ifdef LED_DEBUG
+#ifdef CONFIG_DEBUG_LEDS
# define leddbg lldbg
# define ledvdbg llvdbg
#else
@@ -72,14 +69,12 @@
# define ledvdbg(x...)
#endif
-
/****************************************************************************
* Private Data
****************************************************************************/
irqstate_t irqidle_mask;
-
/****************************************************************************
* Private Functions
****************************************************************************/
diff --git a/nuttx/configs/zkit-arm-1769/README.txt b/nuttx/configs/zkit-arm-1769/README.txt
index 6dbc8a809..43fbf8428 100644
--- a/nuttx/configs/zkit-arm-1769/README.txt
+++ b/nuttx/configs/zkit-arm-1769/README.txt
@@ -584,5 +584,11 @@ Where <subdir> is one of the following:
CONFIG_HOST_LINUX=y : Builds under Windows (or Cygwin)
CONFIG_ARMV7M_TOOLCHAIN_BUILDROOT=y : NuttX buildroot toolchain
- 3. You will need to build the NXFLAT toolchain as described above in
+ 3. TCP/IP (only) networking is enabled with this configuration:
+
+ CONFIG_EXAMPLES_THTTPD_NOMAC=y : Will use MAC 00:e0:de:ad:be:ef
+ CONFIG_EXAMPLES_THTTPD_DRIPADDR=0xac100002 : Gateway 172.16.00.02
+ CONFIG_EXAMPLES_THTTPD_NETMASK=0xffffff00 : Netmask 255.255.255.0
+
+ 4. You will need to build the NXFLAT toolchain as described above in
order to use this example.
diff --git a/nuttx/configs/zkit-arm-1769/src/up_leds.c b/nuttx/configs/zkit-arm-1769/src/up_leds.c
index 124c14af9..2b2dfb1e4 100644
--- a/nuttx/configs/zkit-arm-1769/src/up_leds.c
+++ b/nuttx/configs/zkit-arm-1769/src/up_leds.c
@@ -60,11 +60,11 @@
* Definitions
****************************************************************************/
-/* CONFIG_DEBUG_LED enables debug output from this file (needs CONFIG_DEBUG
+/* CONFIG_DEBUG_LEDS enables debug output from this file (needs CONFIG_DEBUG
* and pherhaps CONFIG_DEBUG_VERBOSE too)
*/
-#ifdef CONFIG_DEBUG_LED
+#ifdef CONFIG_DEBUG_LEDS
# define leddbg lldbg
# ifdef CONFIG_DEBUG_VERBOSE
# define ledvdbg lldbg
diff --git a/nuttx/configs/zkit-arm-1769/thttpd/defconfig b/nuttx/configs/zkit-arm-1769/thttpd/defconfig
index fab04c704..27f9ca861 100644
--- a/nuttx/configs/zkit-arm-1769/thttpd/defconfig
+++ b/nuttx/configs/zkit-arm-1769/thttpd/defconfig
@@ -548,7 +548,7 @@ CONFIG_LIB_SENDFILE_BUFSIZE=512
# CONFIG_EXAMPLES_TELNETD is not set
CONFIG_EXAMPLES_THTTPD=y
CONFIG_EXAMPLES_THTTPD_NOMAC=y
-CONFIG_EXAMPLES_THTTPD_DRIPADDR=0xa0000001
+CONFIG_EXAMPLES_THTTPD_DRIPADDR=0xac100002
CONFIG_EXAMPLES_THTTPD_NETMASK=0xffffff00
# CONFIG_EXAMPLES_TIFF is not set
# CONFIG_EXAMPLES_TOUCHSCREEN is not set