aboutsummaryrefslogtreecommitdiff
path: root/nuttx/configs/px4fmu
diff options
context:
space:
mode:
Diffstat (limited to 'nuttx/configs/px4fmu')
-rw-r--r--nuttx/configs/px4fmu/include/drv_led.h51
-rw-r--r--nuttx/configs/px4fmu/nsh/appconfig2
-rw-r--r--nuttx/configs/px4fmu/src/Makefile5
-rw-r--r--nuttx/configs/px4fmu/src/drv_led.c113
-rw-r--r--nuttx/configs/px4fmu/src/empty.c4
-rw-r--r--nuttx/configs/px4fmu/src/px4fmu-internal.h166
-rw-r--r--nuttx/configs/px4fmu/src/up_leds.c127
7 files changed, 7 insertions, 461 deletions
diff --git a/nuttx/configs/px4fmu/include/drv_led.h b/nuttx/configs/px4fmu/include/drv_led.h
deleted file mode 100644
index 4b7093346..000000000
--- a/nuttx/configs/px4fmu/include/drv_led.h
+++ /dev/null
@@ -1,51 +0,0 @@
-/****************************************************************************
- *
- * Copyright (C) 2012 PX4 Development Team. All rights reserved.
- *
- * 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 PX4 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 <sys/ioctl.h>
-
-#define _LEDCBASE 0x6800
-#define LEDC(_x) _IOC(_LEDCBASE, _x)
-
-/* set the LED identified by the argument */
-#define LED_ON LEDC(1)
-
-/* clear the LED identified by the argument */
-#define LED_OFF LEDC(2)
-
-///* toggle the LED identified by the argument */
-//#define LED_TOGGLE LEDC(3)
-
-#define LED_BLUE 0 /* Led on first port */
-#define LED_AMBER 1 /* Led on second port */
-
-extern int px4fmu_led_init(void);
diff --git a/nuttx/configs/px4fmu/nsh/appconfig b/nuttx/configs/px4fmu/nsh/appconfig
index 4da9065df..5b2546911 100644
--- a/nuttx/configs/px4fmu/nsh/appconfig
+++ b/nuttx/configs/px4fmu/nsh/appconfig
@@ -52,7 +52,6 @@ CONFIGURED_APPS += systemcmds/top
CONFIGURED_APPS += systemcmds/boardinfo
CONFIGURED_APPS += systemcmds/mixer
CONFIGURED_APPS += systemcmds/eeprom
-CONFIGURED_APPS += systemcmds/led
CONFIGURED_APPS += systemcmds/param
CONFIGURED_APPS += systemcmds/bl_update
#CONFIGURED_APPS += systemcmds/calibration
@@ -94,6 +93,7 @@ CONFIGURED_APPS += drivers/bma180
CONFIGURED_APPS += drivers/l3gd20
CONFIGURED_APPS += drivers/px4io
CONFIGURED_APPS += drivers/stm32
+CONFIGURED_APPS += drivers/led
CONFIGURED_APPS += drivers/stm32/tone_alarm
CONFIGURED_APPS += drivers/px4fmu
diff --git a/nuttx/configs/px4fmu/src/Makefile b/nuttx/configs/px4fmu/src/Makefile
index 42c931112..c3d6bf543 100644
--- a/nuttx/configs/px4fmu/src/Makefile
+++ b/nuttx/configs/px4fmu/src/Makefile
@@ -40,9 +40,7 @@ CFLAGS += -I$(TOPDIR)/sched
ASRCS =
AOBJS = $(ASRCS:.S=$(OBJEXT))
-CSRCS = up_leds.c \
- drv_led.c
-
+CSRCS = empty.c
COBJS = $(CSRCS:.c=$(OBJEXT))
SRCS = $(ASRCS) $(CSRCS)
@@ -69,6 +67,7 @@ libboard$(LIBEXT): $(OBJS)
@( for obj in $(OBJS) ; do \
$(call ARCHIVE, $@, $${obj}); \
done ; )
+ touch $@
.depend: Makefile $(SRCS)
@$(MKDEP) $(CC) -- $(CFLAGS) -- $(SRCS) >Make.dep
diff --git a/nuttx/configs/px4fmu/src/drv_led.c b/nuttx/configs/px4fmu/src/drv_led.c
deleted file mode 100644
index 13d8eb22a..000000000
--- a/nuttx/configs/px4fmu/src/drv_led.c
+++ /dev/null
@@ -1,113 +0,0 @@
-/****************************************************************************
- *
- * Copyright (C) 2012 PX4 Development Team. All rights reserved.
- *
- * 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 PX4 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.
- *
- ****************************************************************************/
-
-/*
- * led driver for PX4FMU
- *
- * This is something of an experiment currently (ha, get it?)
- */
-
-#include <nuttx/config.h>
-
-#include <stdint.h>
-#include <stdbool.h>
-#include <debug.h>
-
-#include <nuttx/spi.h>
-#include <arch/board/board.h>
-
-#include "up_arch.h"
-#include "chip.h"
-#include "stm32_internal.h"
-#include "px4fmu-internal.h"
-
-#include <arch/board/drv_led.h>
-
-static int px4fmu_led_ioctl(struct file *filep, int cmd, unsigned long arg);
-static ssize_t px4fmu_led_pseudoread(struct file *filp, FAR char *buffer, size_t buflen);
-
-static const struct file_operations px4fmu_led_fops = {
- .read = px4fmu_led_pseudoread,
- .ioctl = px4fmu_led_ioctl,
-};
-
-int
-px4fmu_led_init(void)
-{
- /* register the driver */
- return register_driver("/dev/led", &px4fmu_led_fops, 0666, NULL);
-}
-
-static ssize_t
-px4fmu_led_pseudoread(struct file *filp, FAR char *buffer, size_t buflen)
-{
- return 0;
-}
-
-static int
-px4fmu_led_ioctl(struct file *filep, int cmd, unsigned long arg)
-{
- int result = 0;
-
- switch (cmd) {
-
- case LED_ON:
- switch (arg) {
- case 0:
- case 1:
- up_ledon(arg);
- break;
- default:
- result = -1;
- break;
- }
- break;
-
- case LED_OFF:
- switch (arg) {
- case 0:
- case 1:
- up_ledoff(arg);
- break;
- default:
- result = -1;
- break;
- }
- break;
- default:
- result = -1;
- break;
- }
- return result;
-}
-
diff --git a/nuttx/configs/px4fmu/src/empty.c b/nuttx/configs/px4fmu/src/empty.c
new file mode 100644
index 000000000..ace900866
--- /dev/null
+++ b/nuttx/configs/px4fmu/src/empty.c
@@ -0,0 +1,4 @@
+/*
+ * There are no source files here, but libboard.a can't be empty, so
+ * we have this empty source file to keep it company.
+ */
diff --git a/nuttx/configs/px4fmu/src/px4fmu-internal.h b/nuttx/configs/px4fmu/src/px4fmu-internal.h
deleted file mode 100644
index f48b1bf5e..000000000
--- a/nuttx/configs/px4fmu/src/px4fmu-internal.h
+++ /dev/null
@@ -1,166 +0,0 @@
-/****************************************************************************************************
- * configs/px4fmu/src/px4fmu_internal.h
- * arch/arm/src/board/px4fmu_internal.n
- *
- * Copyright (C) 2011 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.
- *
- ****************************************************************************************************/
-
-#ifndef __CONFIGS_PX4FMU_SRC_PX4FMU_INTERNAL_H
-#define __CONFIGS_PX4FMU_SRC_PX4FMU_INTERNAL_H
-
-/****************************************************************************************************
- * Included Files
- ****************************************************************************************************/
-
-#include <nuttx/config.h>
-#include <nuttx/compiler.h>
-#include <stdint.h>
-
-/****************************************************************************************************
- * Definitions
- ****************************************************************************************************/
-/* Configuration ************************************************************************************/
-
-#ifdef CONFIG_STM32_SPI2
-# error "SPI2 is not supported on this board"
-#endif
-
-#if defined(CONFIG_STM32_CAN1)
-# warning "CAN1 is not supported on this board"
-#endif
-
-/* PX4FMU GPIOs ***********************************************************************************/
-/* LEDs */
-
-#define GPIO_LED1 (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_50MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTB|GPIO_PIN15)
-#define GPIO_LED2 (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_50MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTB|GPIO_PIN14)
-
-/* External interrupts */
-#define GPIO_EXTI_COMPASS (GPIO_INPUT|GPIO_FLOAT|GPIO_EXTI|GPIO_PORTB|GPIO_PIN1)
-// XXX MPU6000 DRDY?
-
-/* SPI chip selects */
-#define GPIO_SPI_CS_GYRO (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_50MHz|GPIO_OUTPUT_SET|GPIO_PORTC|GPIO_PIN14)
-#define GPIO_SPI_CS_ACCEL (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_50MHz|GPIO_OUTPUT_SET|GPIO_PORTC|GPIO_PIN15)
-#define GPIO_SPI_CS_MPU (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_50MHz|GPIO_OUTPUT_SET|GPIO_PORTB|GPIO_PIN0)
-#define GPIO_SPI_CS_SDCARD (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_50MHz|GPIO_OUTPUT_SET|GPIO_PORTA|GPIO_PIN4)
-
-/* User GPIOs
- *
- * GPIO0-1 are the buffered high-power GPIOs.
- * GPIO2-5 are the USART2 pins.
- * GPIO6-7 are the CAN2 pins.
- */
-#define GPIO_GPIO0_INPUT (GPIO_INPUT|GPIO_PULLUP|GPIO_PORTC|GPIO_PIN4)
-#define GPIO_GPIO1_INPUT (GPIO_INPUT|GPIO_PULLUP|GPIO_PORTC|GPIO_PIN5)
-#define GPIO_GPIO2_INPUT (GPIO_INPUT|GPIO_PULLUP|GPIO_PORTA|GPIO_PIN0)
-#define GPIO_GPIO3_INPUT (GPIO_INPUT|GPIO_PULLUP|GPIO_PORTA|GPIO_PIN1)
-#define GPIO_GPIO4_INPUT (GPIO_INPUT|GPIO_PULLUP|GPIO_PORTA|GPIO_PIN2)
-#define GPIO_GPIO5_INPUT (GPIO_INPUT|GPIO_PULLUP|GPIO_PORTA|GPIO_PIN3)
-#define GPIO_GPIO6_INPUT (GPIO_INPUT|GPIO_PULLUP|GPIO_PORTB|GPIO_PIN13)
-#define GPIO_GPIO7_INPUT (GPIO_INPUT|GPIO_PULLUP|GPIO_PORTB|GPIO_PIN2)
-#define GPIO_GPIO0_OUTPUT (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTC|GPIO_PIN4)
-#define GPIO_GPIO1_OUTPUT (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTC|GPIO_PIN5)
-#define GPIO_GPIO2_OUTPUT (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTA|GPIO_PIN0)
-#define GPIO_GPIO3_OUTPUT (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTA|GPIO_PIN1)
-#define GPIO_GPIO4_OUTPUT (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTA|GPIO_PIN2)
-#define GPIO_GPIO5_OUTPUT (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTA|GPIO_PIN3)
-#define GPIO_GPIO6_OUTPUT (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTB|GPIO_PIN13)
-#define GPIO_GPIO7_OUTPUT (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTB|GPIO_PIN12)
-#define GPIO_GPIO_DIR (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTC|GPIO_PIN13)
-
-/* USB OTG FS
- *
- * PA9 OTG_FS_VBUS VBUS sensing (also connected to the green LED)
- */
-#define GPIO_OTGFS_VBUS (GPIO_INPUT|GPIO_FLOAT|GPIO_SPEED_100MHz|GPIO_OPENDRAIN|GPIO_PORTA|GPIO_PIN9)
-
-/* PWM
- *
- * The PX4FMU has five PWM outputs, of which only the output on
- * pin PC8 is fixed assigned to this function. The other four possible
- * pwm sources are the TX, RX, RTS and CTS pins of USART2
- *
- * Alternate function mapping:
- * PC8 - BUZZER - TIM8_CH3/SDIO_D0 /TIM3_CH3/ USART6_CK / DCMI_D2
- */
-
-#ifdef CONFIG_PWM
-# if defined(CONFIG_STM32_TIM3_PWM)
-# define BUZZER_PWMCHANNEL 3
-# define BUZZER_PWMTIMER 3
-# elif defined(CONFIG_STM32_TIM8_PWM)
-# define BUZZER_PWMCHANNEL 3
-# define BUZZER_PWMTIMER 8
-# endif
-#endif
-
-/****************************************************************************************************
- * Public Types
- ****************************************************************************************************/
-
-/****************************************************************************************************
- * Public data
- ****************************************************************************************************/
-
-#ifndef __ASSEMBLY__
-
-/****************************************************************************************************
- * Public Functions
- ****************************************************************************************************/
-
-/****************************************************************************************************
- * Name: stm32_spiinitialize
- *
- * Description:
- * Called to configure SPI chip select GPIO pins for the PX4FMU board.
- *
- ****************************************************************************************************/
-
-extern void stm32_spiinitialize(void);
-
-/****************************************************************************************************
- * Name: px4fmu_gpio_init
- *
- * Description:
- * Called to configure the PX4FMU user GPIOs
- *
- ****************************************************************************************************/
-
-extern void px4fmu_gpio_init(void);
-
-
-// XXX additional SPI chipselect functions required?
-
-#endif /* __ASSEMBLY__ */
-#endif /* __CONFIGS_PX4FMU_SRC_PX4FMU_INTERNAL_H */
-
diff --git a/nuttx/configs/px4fmu/src/up_leds.c b/nuttx/configs/px4fmu/src/up_leds.c
deleted file mode 100644
index f7b76aa58..000000000
--- a/nuttx/configs/px4fmu/src/up_leds.c
+++ /dev/null
@@ -1,127 +0,0 @@
-/****************************************************************************
- * configs/px4fmu/src/up_leds.c
- * arch/arm/src/board/up_leds.c
- *
- * Copyright (C) 2011 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 "chip.h"
-#include "up_arch.h"
-#include "up_internal.h"
-#include "stm32_internal.h"
-#include "px4fmu-internal.h"
-
-/****************************************************************************
- * Definitions
- ****************************************************************************/
-
-/* 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
-#else
-# define leddbg(x...)
-# define ledvdbg(x...)
-#endif
-
-
-/****************************************************************************
- * Public Functions
- ****************************************************************************/
-
-/****************************************************************************
- * Name: up_ledinit
- ****************************************************************************/
-
-#ifdef CONFIG_ARCH_LEDS
-void up_ledinit(void)
-{
- /* Configure LED1-2 GPIOs for output */
-
- stm32_configgpio(GPIO_LED1);
- stm32_configgpio(GPIO_LED2);
-}
-
-/****************************************************************************
- * Name: up_ledon
- ****************************************************************************/
-
-void up_ledon(int led)
-{
- if (led == 0)
- {
- /* Pull down to switch on */
- stm32_gpiowrite(GPIO_LED1, false);
- }
- if (led == 1)
- {
- /* Pull down to switch on */
- stm32_gpiowrite(GPIO_LED2, false);
- }
-}
-
-/****************************************************************************
- * Name: up_ledoff
- ****************************************************************************/
-
-void up_ledoff(int led)
-{
- if (led == 0)
- {
- /* Pull up to switch off */
- stm32_gpiowrite(GPIO_LED1, true);
- }
- if (led == 1)
- {
- /* Pull up to switch off */
- stm32_gpiowrite(GPIO_LED2, true);
- }
-}
-
-#endif /* CONFIG_ARCH_LEDS */