summaryrefslogtreecommitdiff
path: root/nuttx/configs/nucleo-f401re
diff options
context:
space:
mode:
authorGregory Nutt <gnutt@nuttx.org>2014-04-22 12:55:31 -0600
committerGregory Nutt <gnutt@nuttx.org>2014-04-22 12:55:31 -0600
commit36e36e07c2450ca18424cae78c2bf7b69e8f464b (patch)
treea140d53de3bd051dd24fd53409bc403ff7943050 /nuttx/configs/nucleo-f401re
parentd7726f846b5530cf4dd31c5829d4e493b21b0813 (diff)
downloadpx4-nuttx-36e36e07c2450ca18424cae78c2bf7b69e8f464b.tar.gz
px4-nuttx-36e36e07c2450ca18424cae78c2bf7b69e8f464b.tar.bz2
px4-nuttx-36e36e07c2450ca18424cae78c2bf7b69e8f464b.zip
Nucleo-F401RE: Use standard NuttX LED interfaces
Diffstat (limited to 'nuttx/configs/nucleo-f401re')
-rw-r--r--nuttx/configs/nucleo-f401re/README.txt31
-rw-r--r--nuttx/configs/nucleo-f401re/include/board.h65
-rw-r--r--nuttx/configs/nucleo-f401re/nsh/defconfig22
-rw-r--r--nuttx/configs/nucleo-f401re/src/Makefile12
-rw-r--r--nuttx/configs/nucleo-f401re/src/nucleo-f401re.h12
-rw-r--r--nuttx/configs/nucleo-f401re/src/stm32_autoleds.c (renamed from nuttx/configs/nucleo-f401re/src/stm32_led.c)72
-rw-r--r--nuttx/configs/nucleo-f401re/src/stm32_boot.c4
-rw-r--r--nuttx/configs/nucleo-f401re/src/stm32_nsh.c (renamed from nuttx/configs/nucleo-f401re/src/stm32_init.c)13
-rw-r--r--nuttx/configs/nucleo-f401re/src/stm32_userleds.c233
9 files changed, 423 insertions, 41 deletions
diff --git a/nuttx/configs/nucleo-f401re/README.txt b/nuttx/configs/nucleo-f401re/README.txt
index b3a94a43b..868c12358 100644
--- a/nuttx/configs/nucleo-f401re/README.txt
+++ b/nuttx/configs/nucleo-f401re/README.txt
@@ -31,6 +31,7 @@ Contents
- LED
- Button
- USARTS and Serial Consoles
+ - Buttons and LEDs
- LQFP64
- DFU and JTAG
- Configurations
@@ -342,14 +343,38 @@ DFU and JTAG
Hardware
========
-Buttons and LEDs
-================
-
Buttons
-------
LEDs
----
+ The Nucleo F401RE and a single user LED, LD2. LD2 is the green LED
+ connected to Arduino signal D13 corresponding to MCU I/O PA5 (pin 21) or
+ PB13 (pin 34) depending on the STM32target.
+
+ - When the I/O is HIGH value, the LED is on.
+ - When the I/O is LOW, the LED is off.
+
+ These LEDs are not used by the board port unless CONFIG_ARCH_LEDS is
+ defined. In that case, the usage by the board port is defined in
+ include/board.h and src/sam_leds.c. The LEDs are used to encode OS-related
+ events as follows when the red LED (PE24) is available:
+
+ SYMBOL Meaning LD2
+ ------------------- ----------------------- -----------
+ LED_STARTED NuttX has been started OFF
+ LED_HEAPALLOCATE Heap has been allocated OFF
+ LED_IRQSENABLED Interrupts enabled OFF
+ LED_STACKCREATED Idle stack created ON
+ LED_INIRQ In an interrupt No change
+ LED_SIGNAL In a signal handler No change
+ LED_ASSERTION An assertion failed No change
+ LED_PANIC The system has crashed Blinking
+ LED_IDLE MCU is is sleep mode Not used
+
+ Thus if LD2, NuttX has successfully booted and is, apparently, running
+ normally. If LD2 is flashing at approximately 2Hz, then a fatal error
+ has been detected and the system has halted.
Serial Consoles
===============
diff --git a/nuttx/configs/nucleo-f401re/include/board.h b/nuttx/configs/nucleo-f401re/include/board.h
index 4ba300d3d..ecebadf87 100644
--- a/nuttx/configs/nucleo-f401re/include/board.h
+++ b/nuttx/configs/nucleo-f401re/include/board.h
@@ -278,15 +278,54 @@
#define GPIO_SPI2_MOSI GPIO_SPI2_MOSI_1
#define GPIO_SPI2_SCK GPIO_SPI2_SCK_2
-/* LED Definitions. Needed if CONFIG_ARCH_LEDs is defined */
+/* LEDs
+ *
+ * The Nucleo F401RE and a single user LED, LD2. LD2 is the green LED
+ * connected to Arduino signal D13 corresponding to MCU I/O PA5 (pin 21) or
+ * PB13 (pin 34) depending on the STM32target.
+ *
+ * - When the I/O is HIGH value, the LED is on.
+ * - When the I/O is LOW, the LED is off.
+ */
+
+/* LED index values for use with stm32_setled() */
+
+#define BOARD_LD2 0
+#define BOARD_NLEDS 1
+
+/* LED bits for use with stm32_setleds() */
+
+#define BOARD_LD2_BIT (1 << BOARD_LD2)
+
+/* These LEDs are not used by the board port unless CONFIG_ARCH_LEDS is
+ * defined. In that case, the usage by the board port is defined in
+ * include/board.h and src/sam_leds.c. The LEDs are used to encode OS-related
+ * events as follows when the red LED (PE24) is available:
+ *
+ * SYMBOL Meaning LD2
+ * ------------------- ----------------------- -----------
+ * LED_STARTED NuttX has been started OFF
+ * LED_HEAPALLOCATE Heap has been allocated OFF
+ * LED_IRQSENABLED Interrupts enabled OFF
+ * LED_STACKCREATED Idle stack created ON
+ * LED_INIRQ In an interrupt No change
+ * LED_SIGNAL In a signal handler No change
+ * LED_ASSERTION An assertion failed No change
+ * LED_PANIC The system has crashed Blinking
+ * LED_IDLE MCU is is sleep mode Not used
+ *
+ * Thus if LD2, NuttX has successfully booted and is, apparently, running
+ * normally. If LD2 is flashing at approximately 2Hz, then a fatal error
+ * has been detected and the system has halted.
+ */
#define LED_STARTED 0
#define LED_HEAPALLOCATE 0
#define LED_IRQSENABLED 0
#define LED_STACKCREATED 1
-#define LED_INIRQ 1
-#define LED_SIGNAL 1
-#define LED_ASSERTION 1
+#define LED_INIRQ 2
+#define LED_SIGNAL 2
+#define LED_ASSERTION 2
#define LED_PANIC 1
/************************************************************************************
@@ -312,13 +351,29 @@ extern "C"
*
* Description:
* All STM32 architectures must provide the following entry point. This entry point
- * is called early in the intitialization -- after all memory has been configured
+ * is called early in the initialization -- after all memory has been configured
* and mapped but before any devices have been initialized.
*
************************************************************************************/
void stm32_boardinitialize(void);
+/************************************************************************************
+ * Name: stm32_ledinit, stm32_setled, and stm32_setleds
+ *
+ * Description:
+ * If CONFIG_ARCH_LEDS is defined, then NuttX will control the on-board LEDs. If
+ * CONFIG_ARCH_LEDS is not defined, then the following interfaces are available to
+ * control the LEDs from user applications.
+ *
+ ************************************************************************************/
+
+#ifndef CONFIG_ARCH_LEDS
+void stm32_ledinit(void);
+void stm32_setled(int led, bool ledon);
+void stm32_setleds(uint8_t ledset);
+#endif
+
#undef EXTERN
#if defined(__cplusplus)
}
diff --git a/nuttx/configs/nucleo-f401re/nsh/defconfig b/nuttx/configs/nucleo-f401re/nsh/defconfig
index 5192364b9..a77a2e7fb 100644
--- a/nuttx/configs/nucleo-f401re/nsh/defconfig
+++ b/nuttx/configs/nucleo-f401re/nsh/defconfig
@@ -12,6 +12,10 @@ CONFIG_HOST_LINUX=y
# CONFIG_HOST_OSX is not set
# CONFIG_HOST_WINDOWS is not set
# CONFIG_HOST_OTHER is not set
+# CONFIG_WINDOWS_NATIVE is not set
+# CONFIG_WINDOWS_CYGWIN is not set
+# CONFIG_WINDOWS_MSYS is not set
+# CONFIG_WINDOWS_OTHER is not set
#
# Build Configuration
@@ -109,10 +113,16 @@ CONFIG_ARCH_HAVE_MPU=y
#
# ARMV7M Configuration Options
#
+# CONFIG_ARMV7M_TOOLCHAIN_ATOLLIC is not set
# CONFIG_ARMV7M_TOOLCHAIN_BUILDROOT is not set
# CONFIG_ARMV7M_TOOLCHAIN_CODEREDL is not set
+# CONFIG_ARMV7M_TOOLCHAIN_CODEREDW is not set
CONFIG_ARMV7M_TOOLCHAIN_CODESOURCERYL=y
+# CONFIG_ARMV7M_TOOLCHAIN_CODESOURCERYW is not set
+# CONFIG_ARMV7M_TOOLCHAIN_DEVKITARM is not set
# CONFIG_ARMV7M_TOOLCHAIN_GNU_EABIL is not set
+# CONFIG_ARMV7M_TOOLCHAIN_GNU_EABIW is not set
+# CONFIG_ARMV7M_TOOLCHAIN_RAISONANCE is not set
# CONFIG_SERIAL_TERMIOS is not set
CONFIG_SDIO_DMA=y
CONFIG_SDIO_DMAPRIO=0x00010000
@@ -373,6 +383,11 @@ CONFIG_ARCH_BOARD="nucleo-f401re"
#
# Common Board Options
#
+CONFIG_ARCH_HAVE_LEDS=y
+CONFIG_ARCH_LEDS=y
+CONFIG_ARCH_HAVE_BUTTONS=y
+# CONFIG_ARCH_BUTTONS is not set
+CONFIG_ARCH_HAVE_IRQBUTTONS=y
CONFIG_NSH_MMCSDMINOR=0
CONFIG_NSH_MMCSDSLOTNO=0
@@ -489,6 +504,8 @@ CONFIG_SPI_EXCHANGE=y
# CONFIG_I2S is not set
# CONFIG_RTC is not set
CONFIG_WATCHDOG=y
+CONFIG_WATCHDOG_DEVPATH="/dev/watchdog0"
+# CONFIG_TIMER is not set
# CONFIG_ANALOG is not set
# CONFIG_AUDIO_DEVICES is not set
# CONFIG_VIDEO_DEVICES is not set
@@ -799,6 +816,7 @@ CONFIG_EXAMPLES_CC3000BASIC=y
# CONFIG_EXAMPLES_CC3000_MEM_CHECK is not set
# CONFIG_EXAMPLES_CC3000_STACK_CHECK is not set
# CONFIG_EXAMPLES_CONFIGDATA is not set
+# CONFIG_EXAMPLES_CPUHOG is not set
# CONFIG_EXAMPLES_DHCPD is not set
# CONFIG_EXAMPLES_ELF is not set
# CONFIG_EXAMPLES_FTPC is not set
@@ -836,6 +854,8 @@ CONFIG_EXAMPLES_NSH=y
# CONFIG_EXAMPLES_RGMP is not set
# CONFIG_EXAMPLES_ROMFS is not set
# CONFIG_EXAMPLES_SENDMAIL is not set
+# CONFIG_EXAMPLES_SERIALBLASTER is not set
+# CONFIG_EXAMPLES_SERIALRX is not set
# CONFIG_EXAMPLES_SERLOOP is not set
# CONFIG_EXAMPLES_SLCD is not set
# CONFIG_EXAMPLES_SMART_TEST is not set
@@ -967,7 +987,7 @@ CONFIG_NSH_CONSOLE=y
#
# USB Trace Support
#
-# CONFIG_NSH_CONDEV is not set
+CONFIG_NSH_CONDEV="/dev/console"
CONFIG_NSH_ARCHINIT=y
CONFIG_NSH_IPADDR=0x0a000002
CONFIG_NSH_DRIPADDR=0x0a000001
diff --git a/nuttx/configs/nucleo-f401re/src/Makefile b/nuttx/configs/nucleo-f401re/src/Makefile
index ca34843bc..e952073f6 100644
--- a/nuttx/configs/nucleo-f401re/src/Makefile
+++ b/nuttx/configs/nucleo-f401re/src/Makefile
@@ -40,12 +40,22 @@ CFLAGS += -I$(TOPDIR)/sched
ASRCS =
AOBJS = $(ASRCS:.S=$(OBJEXT))
-CSRCS = stm32_boot.c stm32_init.c stm32_led.c stm32_spi.c
+CSRCS = stm32_boot.c stm32_spi.c
+
+ifeq ($(CONFIG_ARCH_LEDS),y)
+CSRCS += stm32_autoleds.c
+else
+CSRCS += stm32_userleds.c
+endif
ifeq ($(CONFIG_WL_CC3000),y)
CSRCS += stm32_wireless.c
endif
+ifeq ($(CONFIG_NSH_LIBRARY),y)
+CSRCS += stm32_nsh.c
+endif
+
ifeq ($(CONFIG_CC3000_PROBES),)
CSRCS += stm32_io.c
endif
diff --git a/nuttx/configs/nucleo-f401re/src/nucleo-f401re.h b/nuttx/configs/nucleo-f401re/src/nucleo-f401re.h
index fc6935fe2..eb904a9f2 100644
--- a/nuttx/configs/nucleo-f401re/src/nucleo-f401re.h
+++ b/nuttx/configs/nucleo-f401re/src/nucleo-f401re.h
@@ -84,5 +84,17 @@ void stm32_spiinitialize(void);
void stm32_usbinitialize(void);
+/****************************************************************************
+ * Name: board_led_initialize
+ *
+ * Description:
+ * Initialize LED GPIO outputs
+ *
+ ****************************************************************************/
+
+#ifdef CONFIG_ARCH_LEDS
+void board_led_initialize(void);
+#endif
+
#endif /* __ASSEMBLY__ */
#endif /* __CONFIGS_NUCLEO_F401RE_SRC_NUCLEO_F401RE_H */
diff --git a/nuttx/configs/nucleo-f401re/src/stm32_led.c b/nuttx/configs/nucleo-f401re/src/stm32_autoleds.c
index 2ac49740d..6d80551e4 100644
--- a/nuttx/configs/nucleo-f401re/src/stm32_led.c
+++ b/nuttx/configs/nucleo-f401re/src/stm32_autoleds.c
@@ -1,5 +1,5 @@
/****************************************************************************
- * configs/nucleo-f401re/src/stm32_led.c
+ * configs/nucleo-f401re/src/stm32_autoleds.c
*
* Copyright (C) 2014 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <gnutt@nuttx.org>
@@ -39,55 +39,81 @@
#include <nuttx/config.h>
+#include <stdint.h>
#include <stdbool.h>
+#include <debug.h>
#include <arch/board/board.h>
+#include "chip.h"
+#include "up_arch.h"
+#include "up_internal.h"
#include "stm32.h"
#include "nucleo-f401re.h"
+#ifdef CONFIG_ARCH_LEDS
+
+/****************************************************************************
+ * Pre-processor Definitions
+ ****************************************************************************/
+
+/* CONFIG_DEBUG_LEDS enables debug output from this file (needs CONFIG_DEBUG
+ * with CONFIG_DEBUG_VERBOSE too)
+ */
+
+#ifdef CONFIG_DEBUG_LEDS
+# define leddbg lldbg
+# define ledvdbg llvdbg
+#else
+# define leddbg(x...)
+# define ledvdbg(x...)
+#endif
+
+/****************************************************************************
+ * Private Data
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Functions
+ ****************************************************************************/
+
/****************************************************************************
* Public Functions
****************************************************************************/
-void led_init(void)
+/****************************************************************************
+ * Name: board_led_initialize
+ ****************************************************************************/
+
+void board_led_initialize(void)
{
- /* Configure LED1 GPIO for output */
+ /* Configure LD2 GPIO for output */
stm32_configgpio(GPIO_LD2);
}
-void led_on(int led)
+/****************************************************************************
+ * Name: board_led_on
+ ****************************************************************************/
+
+void board_led_on(int led)
{
if (led == 1)
{
- /* Pull down to switch on */
-
stm32_gpiowrite(GPIO_LD2, true);
}
}
-void led_off(int led)
+/****************************************************************************
+ * Name: board_led_off
+ ****************************************************************************/
+
+void board_led_off(int led)
{
if (led == 1)
{
- /* Pull up to switch off */
-
stm32_gpiowrite(GPIO_LD2, false);
}
}
-void led_toggle(int led)
-{
- if (led == 1)
- {
- if (stm32_gpioread(GPIO_LD2))
- {
- stm32_gpiowrite(GPIO_LD2, false);
- }
- else
- {
- stm32_gpiowrite(GPIO_LD2, true);
- }
- }
-}
+#endif /* CONFIG_ARCH_LEDS */
diff --git a/nuttx/configs/nucleo-f401re/src/stm32_boot.c b/nuttx/configs/nucleo-f401re/src/stm32_boot.c
index ca22088fe..28766791e 100644
--- a/nuttx/configs/nucleo-f401re/src/stm32_boot.c
+++ b/nuttx/configs/nucleo-f401re/src/stm32_boot.c
@@ -80,10 +80,6 @@ void stm32_boardinitialize(void)
board_led_initialize();
#endif
-#ifdef CONFIG_ARCH_HAVE_BUTTONS
- board_button_initialize();
-#endif
-
/* Configure SPI chip selects if 1) SP2 is not disabled, and 2) the weak function
* stm32_spiinitialize() has been brought into the link.
*/
diff --git a/nuttx/configs/nucleo-f401re/src/stm32_init.c b/nuttx/configs/nucleo-f401re/src/stm32_nsh.c
index 196cb133a..bd4714974 100644
--- a/nuttx/configs/nucleo-f401re/src/stm32_init.c
+++ b/nuttx/configs/nucleo-f401re/src/stm32_nsh.c
@@ -1,5 +1,5 @@
/****************************************************************************
- * configs/nucleo-f401re/src/stm32_init.c
+ * configs/nucleo-f401re/src/stm32_nsh.c
*
* Copyright (C) 2014 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <gnutt@nuttx.org>
@@ -47,10 +47,8 @@
#include <nuttx/arch.h>
#include <nuttx/spi/spi.h>
-#include <nuttx/i2c.h>
#include <nuttx/sdio.h>
#include <nuttx/mmcsd.h>
-#include <nuttx/analog/adc.h>
#include <nuttx/gran.h>
#include <stm32.h>
@@ -135,6 +133,14 @@ static void dma_alloc_init(void)
* Public Functions
****************************************************************************/
+/****************************************************************************
+ * Name: up_netinitialize
+ *
+ * Description:
+ * Dummy function expected to start-up logic.
+ *
+ ****************************************************************************/
+
void up_netinitialize(void)
{
}
@@ -165,7 +171,6 @@ int nsh_archinitialize(void)
if (!spi1)
{
message("[boot] FAILED to initialize SPI port 1\n");
- board_led_on(LED_AMBER);
return -ENODEV;
}
diff --git a/nuttx/configs/nucleo-f401re/src/stm32_userleds.c b/nuttx/configs/nucleo-f401re/src/stm32_userleds.c
new file mode 100644
index 000000000..c79790583
--- /dev/null
+++ b/nuttx/configs/nucleo-f401re/src/stm32_userleds.c
@@ -0,0 +1,233 @@
+/****************************************************************************
+ * configs/nucleo-f401re/src/stm32_userleds.c
+ *
+ * Copyright (C) 2014 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 <stdint.h>
+#include <stdbool.h>
+#include <debug.h>
+
+#include <arch/board/board.h>
+#include <nuttx/power/pm.h>
+
+#include "chip.h"
+#include "up_arch.h"
+#include "up_internal.h"
+#include "stm32.h"
+#include "nucleo-f401re.h"
+
+#ifndef CONFIG_ARCH_LEDS
+
+/****************************************************************************
+ * Pre-processor Definitions
+ ****************************************************************************/
+
+/* CONFIG_DEBUG_LEDS enables debug output from this file (needs CONFIG_DEBUG
+ * with CONFIG_DEBUG_VERBOSE too)
+ */
+
+#ifdef CONFIG_DEBUG_LEDS
+# define leddbg lldbg
+# define ledvdbg llvdbg
+#else
+# define leddbg(x...)
+# define ledvdbg(x...)
+#endif
+
+/****************************************************************************
+ * Private Data
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Function Prototypes
+ ****************************************************************************/
+
+/* LED Power Management */
+
+#ifdef CONFIG_PM
+static void led_pm_notify(struct pm_callback_s *cb, enum pm_state_e pmstate);
+static int led_pm_prepare(struct pm_callback_s *cb, enum pm_state_e pmstate);
+#endif
+
+/****************************************************************************
+ * Private Data
+ ****************************************************************************/
+
+#ifdef CONFIG_PM
+static struct pm_callback_s g_ledscb =
+{
+ .notify = led_pm_notify,
+ .prepare = led_pm_prepare,
+};
+#endif
+
+/****************************************************************************
+ * Private Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Name: led_pm_notify
+ *
+ * Description:
+ * Notify the driver of new power state. This callback is called after
+ * all drivers have had the opportunity to prepare for the new power state.
+ *
+ ****************************************************************************/
+
+#ifdef CONFIG_PM
+static void led_pm_notify(struct pm_callback_s *cb , enum pm_state_e pmstate)
+{
+ switch (pmstate)
+ {
+ case(PM_NORMAL):
+ {
+ /* Restore normal LEDs operation */
+
+ }
+ break;
+
+ case(PM_IDLE):
+ {
+ /* Entering IDLE mode - Turn leds off */
+
+ }
+ break;
+
+ case(PM_STANDBY):
+ {
+ /* Entering STANDBY mode - Logic for PM_STANDBY goes here */
+
+ }
+ break;
+
+ case(PM_SLEEP):
+ {
+ /* Entering SLEEP mode - Logic for PM_SLEEP goes here */
+
+ }
+ break;
+
+ default:
+ {
+ /* Should not get here */
+
+ }
+ break;
+ }
+}
+#endif
+
+/****************************************************************************
+ * Name: led_pm_prepare
+ *
+ * Description:
+ * Request the driver to prepare for a new power state. This is a warning
+ * that the system is about to enter into a new power state. The driver
+ * should begin whatever operations that may be required to enter power
+ * state. The driver may abort the state change mode by returning a
+ * non-zero value from the callback function.
+ *
+ ****************************************************************************/
+
+#ifdef CONFIG_PM
+static int led_pm_prepare(struct pm_callback_s *cb , enum pm_state_e pmstate)
+{
+ /* No preparation to change power modes is required by the LEDs driver.
+ * We always accept the state change by returning OK.
+ */
+
+ return OK;
+}
+#endif
+
+/****************************************************************************
+ * Public Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Name: stm32_ledinit
+ ****************************************************************************/
+
+void stm32_ledinit(void)
+{
+ /* Configure LD2 GPIO for output */
+
+ stm32_configgpio(GPIO_LD2);
+}
+
+/****************************************************************************
+ * Name: stm32_setled
+ ****************************************************************************/
+
+void stm32_setled(int led, bool ledon)
+{
+ if (led == 1)
+ {
+ stm32_gpiowrite(GPIO_LD2, ldeon);
+ }
+}
+
+/****************************************************************************
+ * Name: stm32_setleds
+ ****************************************************************************/
+
+void stm32_setleds(uint8_t ledset)
+{
+ if (led == 1)
+ {
+ stm32_gpiowrite(GPIO_LD2, (ledset & BOARD_LD2_BIT) != 0);
+ }
+}
+
+/****************************************************************************
+ * Name: stm32_led_pminitialize
+ ****************************************************************************/
+
+#ifdef CONFIG_PM
+void stm32_led_pminitialize(void)
+{
+ /* Register to receive power management callbacks */
+
+ int ret = pm_register(&g_ledscb);
+ DEBUGASSERT(ret == OK);
+ UNUSED(ret);
+}
+#endif /* CONFIG_PM */
+
+#endif /* !CONFIG_ARCH_LEDS */