summaryrefslogtreecommitdiff
path: root/nuttx/configs/detron
diff options
context:
space:
mode:
authorpatacongo <patacongo@42af7a65-404d-4744-a932-0658087f49c3>2011-02-14 16:05:43 +0000
committerpatacongo <patacongo@42af7a65-404d-4744-a932-0658087f49c3>2011-02-14 16:05:43 +0000
commitc45ce4acb9eeca86c6da100828095da514690019 (patch)
treef38474fc93fc90e166dd4a22114bb6e757972635 /nuttx/configs/detron
parentaad231f6e26b8f32232428da5d65d62a8adb6bfb (diff)
downloadpx4-nuttx-c45ce4acb9eeca86c6da100828095da514690019.tar.gz
px4-nuttx-c45ce4acb9eeca86c6da100828095da514690019.tar.bz2
px4-nuttx-c45ce4acb9eeca86c6da100828095da514690019.zip
Update detron board pin definitions
git-svn-id: svn://svn.code.sf.net/p/nuttx/code/trunk@3296 42af7a65-404d-4744-a932-0658087f49c3
Diffstat (limited to 'nuttx/configs/detron')
-rwxr-xr-xnuttx/configs/detron/README.txt93
-rwxr-xr-xnuttx/configs/detron/hidkbd/defconfig7
-rwxr-xr-xnuttx/configs/detron/hidkbd/setenv.sh3
-rwxr-xr-xnuttx/configs/detron/include/board.h76
-rwxr-xr-xnuttx/configs/detron/nsh/defconfig19
-rwxr-xr-xnuttx/configs/detron/nsh/setenv.sh3
-rwxr-xr-xnuttx/configs/detron/ostest/defconfig7
-rwxr-xr-xnuttx/configs/detron/ostest/setenv.sh3
-rwxr-xr-xnuttx/configs/detron/src/Makefile2
-rwxr-xr-xnuttx/configs/detron/src/detron_internal.h96
-rwxr-xr-xnuttx/configs/detron/src/up_boot.c32
-rwxr-xr-xnuttx/configs/detron/src/up_leds.c234
-rwxr-xr-xnuttx/configs/detron/src/up_nsh.c35
-rwxr-xr-xnuttx/configs/detron/src/up_ssp.c172
-rwxr-xr-xnuttx/configs/detron/wlan/defconfig7
-rwxr-xr-xnuttx/configs/detron/wlan/setenv.sh3
16 files changed, 165 insertions, 627 deletions
diff --git a/nuttx/configs/detron/README.txt b/nuttx/configs/detron/README.txt
index 133ed65fc..7f542bdea 100755
--- a/nuttx/configs/detron/README.txt
+++ b/nuttx/configs/detron/README.txt
@@ -1,25 +1,55 @@
README
^^^^^^
-README for NuttX port to Detron LPC1768 board
+README for NuttX port to the Detron LPC1768 board from Decio Renno
+(http://www.detroneletronica.com.br/)
Contents
^^^^^^^^
- Detron LPC1768 Board
+ Internet Radio Detron Board
Development Environment
GNU Toolchain Options
IDEs
NuttX buildroot Toolchain
- LEDs
Detron Configuration Options
USB Host Configuration
Configurations
-etron LPC1768 Board
-^^^^^^^^^^^^^^^^^^^
-
-GPIO Usage -- To be provided
+Internet Radio Detron Board
+^^^^^^^^^^^^^^^^^^^^^^^^^^^
+
+ Graphic display
+
+ Pin Port Function
+ 58 P0(20) DI
+ 59 P0(19) RW
+ 49 P0(11) ENABLE
+ 78 P0(7) D0
+ 79 P0(6) D1
+ 78 P0(5) D2
+ 81 P0(4) D3
+ 94 P1(1) D4
+ 95 P1(0) D5
+ 47 P0(1) D6
+ 46 P0(0) D7
+
+ VS1003
+
+ Pin Port Function
+ 65 P2(8) xreset
+ 85 P4(29) dreq
+ 82 P4(28) xdcs
+ 63 P0(16) xcs
+ 62 P0(15) sclk
+ 60 P0(18) si
+ 61 P0(17) so
+
+ USB
+
+ Pin Port Function
+ 29 D+
+ 30 D-
Development Environment
^^^^^^^^^^^^^^^^^^^^^^^
@@ -165,11 +195,6 @@ NuttX buildroot Toolchain
NOTE: This is an OABI toolchain.
-LEDs
-^^^^
-
- To be provided.
-
Detron Configuration Options
^^^^^^^^^^^^^^^^^^^^^^^^^^^^
@@ -349,39 +374,6 @@ Detron Configuration Options
application can guarantee that all end-user I/O buffers
reside in AHB SRAM.
-USB Host Configuration
-^^^^^^^^^^^^^^^^^^^^^^
-
-The NuttShell (NSH) Detron configuration can be modified in order
-to support USB host operations. To make these modifications, do the
-following:
-
-1. First configure to build the NSH configuration from the top-level
- NuttX directory:
-
- cd tools
- ./configure detron/nsh
- cd ..
-
-2. Then edit the top-level .config file to enable USB host. Make the
- following changes:
-
- CONFIG_LPC17_USBHOST=n
- CONFIG_USBHOST=n
- CONFIG_SCHED_WORKQUEUE=y
-
-When this change is made, NSH should be extended to support USB flash
-devices. When a FLASH device is inserted, you should see a device
-appear in the /dev (psuedo) directory. The device name should be
-like /dev/sda, /dev/sdb, etc. The USB mass storage device, is present
-it can be mounted from the NSH command line like:
-
- ls /dev
- mount -t vfat /dev/sda /mnt/flash
-
-Files on the connect USB flash device should then be accessible under
-the mountpoint /mnt/flash.
-
Configurations
^^^^^^^^^^^^^^
@@ -406,14 +398,3 @@ Where <subdir> is one of the following:
ostest:
This configuration directory, performs a simple OS test using
examples/ostest.
-
- usbserial:
- This configuration directory exercises the USB serial class
- driver at examples/usbserial. See examples/README.txt for
- more information.
-
- usbstorage:
- This configuration directory exercises the USB mass storage
- class driver at examples/usbstorage. See examples/README.txt for
- more information.
-
diff --git a/nuttx/configs/detron/hidkbd/defconfig b/nuttx/configs/detron/hidkbd/defconfig
index b1e035403..1e7fe5e5e 100755
--- a/nuttx/configs/detron/hidkbd/defconfig
+++ b/nuttx/configs/detron/hidkbd/defconfig
@@ -85,7 +85,7 @@ CONFIG_ARCH_IRQPRIO=y
CONFIG_ARCH_INTERRUPTSTACK=n
CONFIG_ARCH_STACKDUMP=y
CONFIG_ARCH_BOOTLOADER=n
-CONFIG_ARCH_LEDS=y
+CONFIG_ARCH_LEDS=n
CONFIG_ARCH_BUTTONS=n
CONFIG_ARCH_CALIBRATION=n
CONFIG_ARCH_DMA=n
@@ -860,6 +860,11 @@ CONFIG_EXAMPLES_USBSERIAL_TRACECONTROLLER=n
CONFIG_EXAMPLES_USBSERIAL_TRACEINTERRUPTS=n
#
+# Settings for internet_radio by Decio
+#
+CONFIG_INTERNETRADIO_ARCHINIT=n
+
+#
# Stack and heap information
#
# CONFIG_BOOT_RUNFROMFLASH - Some configurations support XIP
diff --git a/nuttx/configs/detron/hidkbd/setenv.sh b/nuttx/configs/detron/hidkbd/setenv.sh
index 62a4f279f..1464c414d 100755
--- a/nuttx/configs/detron/hidkbd/setenv.sh
+++ b/nuttx/configs/detron/hidkbd/setenv.sh
@@ -41,8 +41,7 @@ fi
if [ -z "${PATH_ORIG}" ]; then export PATH_ORIG="${PATH}"; fi
WD=`pwd`
-export LPCTOOL_DIR="${WD}/configs/detron/tools"
export BUILDROOT_BIN="${WD}/../buildroot/build_arm_nofpu/staging_dir/bin"
-export PATH="${BUILDROOT_BIN}:${LPCTOOL_DIR}:/sbin:/usr/sbin:${PATH_ORIG}"
+export PATH="${BUILDROOT_BIN}:/sbin:/usr/sbin:${PATH_ORIG}"
echo "PATH : ${PATH}"
diff --git a/nuttx/configs/detron/include/board.h b/nuttx/configs/detron/include/board.h
index 5a30b42c6..544fada1c 100755
--- a/nuttx/configs/detron/include/board.h
+++ b/nuttx/configs/detron/include/board.h
@@ -3,7 +3,9 @@
* include/arch/board/board.h
*
* Copyright (C) 2011 Gregory Nutt. All rights reserved.
- * Author: Gregory Nutt <spudmonkey@racsa.co.cr>
+ * Authors:
+ * Decio Renno <http://www.detroneletronica.com.br>
+ * Gregory Nutt <spudmonkey@racsa.co.cr>
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
@@ -123,70 +125,11 @@
#define CONFIG_LP17_FLASH 1
#define BOARD_FLASHCFG_VALUE 0x0000303a
-/* LED definitions ******************************************************************/
-/* This describes a board with 3 LEDs, LED1, LED2, and hearbeat... This needes to be
- * updated for the Detron board. If CONFIG_ARCH_LEDS is defined, these LEDs will be
- * controlled as follows for NuttX debug functionality (where NC means "No Change").
- */
- /* LED1 LED2 HEARTBEAT */
-#define LED_STARTED 0 /* OFF OFF OFF */
-#define LED_HEAPALLOCATE 1 /* GREEN OFF OFF */
-#define LED_IRQSENABLED 2 /* OFF GREEN OFF */
-#define LED_STACKCREATED 3 /* OFF OFF OFF */
-#define LED_INIRQ 4 /* NC NC ON (momentary) */
-#define LED_SIGNAL 5 /* NC NC ON (momentary) */
-#define LED_ASSERTION 6 /* NC NC ON (momentary) */
-#define LED_PANIC 7 /* NC NC ON (1Hz flashing) */
-
-/* Alternate pin selections *********************************************************/
-/* UART1 -- Not connected */
-
-#define GPIO_UART1_TXD GPIO_UART1_TXD_1
-#define GPIO_UART1_RXD GPIO_UART1_RXD_1
-#define GPIO_UART1_CTS GPIO_UART1_CTS_1
-#define GPIO_UART1_DCD GPIO_UART1_DCD_1
-#define GPIO_UART1_DSR GPIO_UART1_DSR_1
-#define GPIO_UART1_DTR GPIO_UART1_DTR_1
-#define GPIO_UART1_RI GPIO_UART1_RI_1
-#define GPIO_UART1_RTS GPIO_UART1_RTS_1
-
-/* UART2 -- Not connected */
-
-#define GPIO_UART2_TXD GPIO_UART2_TXD_1
-#define GPIO_UART2_RXD GPIO_UART2_RXD_1
-
-/* UART3 -- Not connected */
-
-#define GPIO_UART3_TXD GPIO_UART3_TXD_1
-#define GPIO_UART3_RXD GPIO_UART3_RXD_1
-
-/* Either SPI or SSP0 can drive the MMC/SD slot (SSP0 alternate pin settings are
- * not connected)
- */
-
-#define GPIO_SSP0_SCK GPIO_SSP0_SCK_1
-#define GPIO_SSP0_SSEL GPIO_SSP0_SSEL_1
-#define GPIO_SSP0_MISO GPIO_SSP0_MISO_1
-#define GPIO_SSP0_MOSI GPIO_SSP0_MOSI_1
-
-/* SSP1 */
-
-#define GPIO_SSP1_SCK GPIO_SSP1_SCK_1
-
/************************************************************************************
* Public Types
************************************************************************************/
#ifndef __ASSEMBLY__
-#ifdef CONFIG_ARCH_LEDS
-enum lpc17_ledstate_e
-{
- LPC17_LEDSTATE_OFF = 0,
- LPC17_LEDSTATE_GREEN = 1,
- LPC17_LEDSTATE_RED = 2,
- LPC17_LEDSTATE_AMBER = (LPC17_LEDSTATE_GREEN|LPC17_LEDSTATE_RED),
-};
-#endif
/************************************************************************************
* Public Data
@@ -215,19 +158,6 @@ extern "C" {
EXTERN void lpc17_boardinitialize(void);
-/************************************************************************************
- * Name: lpc17_led1 and 2
- *
- * Description:
- * Once the system has booted, these functions can be used to control LEDs 1 and 2
- *
- ************************************************************************************/
-
-#ifdef CONFIG_ARCH_LEDS
-EXTERN void lpc17_led1(enum lpc17_ledstate_e state);
-EXTERN void lpc17_led2(enum lpc17_ledstate_e state);
-#endif
-
#undef EXTERN
#if defined(__cplusplus)
}
diff --git a/nuttx/configs/detron/nsh/defconfig b/nuttx/configs/detron/nsh/defconfig
index 7d15723ea..95d6e0c40 100755
--- a/nuttx/configs/detron/nsh/defconfig
+++ b/nuttx/configs/detron/nsh/defconfig
@@ -1,8 +1,10 @@
############################################################################
# configs/detron/nsh/defconfig
#
-# Copyright (C) 2010 Gregory Nutt. All rights reserved.
-# Author: Gregory Nutt <spudmonkey@racsa.co.cr>
+# Copyright (C) 2011 Gregory Nutt. All rights reserved.
+# Authors:
+# Decio Renno <http://www.detroneletronica.com.br>
+# Gregory Nutt <spudmonkey@racsa.co.cr>
#
# Redistribution and use in source and binary forms, with or without
# modification, are permitted provided that the following conditions
@@ -84,7 +86,7 @@ CONFIG_ARCH_IRQPRIO=y
CONFIG_ARCH_INTERRUPTSTACK=n
CONFIG_ARCH_STACKDUMP=y
CONFIG_ARCH_BOOTLOADER=n
-CONFIG_ARCH_LEDS=y
+CONFIG_ARCH_LEDS=n
CONFIG_ARCH_BUTTONS=n
CONFIG_ARCH_CALIBRATION=n
CONFIG_ARCH_DMA=n
@@ -104,7 +106,7 @@ CONFIG_LPC17_BUILDROOT=y
# (MAINOSC, PLL0, PLL1 and FLASH are controlled in board.h)
#
CONFIG_LPC17_ETHERNET=n
-CONFIG_LPC17_USBHOST=n
+CONFIG_LPC17_USBHOST=y
CONFIG_LPC17_USBOTG=n
CONFIG_LPC17_USBDEV=n
CONFIG_LPC17_UART0=y
@@ -347,7 +349,7 @@ CONFIG_FDCLONE_DISABLE=n
CONFIG_FDCLONE_STDIO=n
CONFIG_SDCLONE_DISABLE=y
CONFIG_NXFLAT=n
-CONFIG_SCHED_WORKQUEUE=n
+CONFIG_SCHED_WORKQUEUE=y
CONFIG_SCHED_WORKPRIORITY=50
CONFIG_SCHED_WORKPERIOD=(50*1000)
CONFIG_SCHED_WORKSTACKSIZE=1024
@@ -604,7 +606,7 @@ CONFIG_USBDEV_TRACE_NRECORDS=128
# On some architectures, selecting this setting will reduce driver size
# by disabling isochronous endpoint support
#
-CONFIG_USBHOST=n
+CONFIG_USBHOST=y
CONFIG_USBHOST_NPREALLOC=0
CONFIG_USBHOST_BULK_DISABLE=n
CONFIG_USBHOST_INT_DISABLE=y
@@ -859,6 +861,11 @@ CONFIG_EXAMPLES_USBSERIAL_TRACECONTROLLER=n
CONFIG_EXAMPLES_USBSERIAL_TRACEINTERRUPTS=n
#
+# Settings for internet_radio by Decio
+#
+CONFIG_INTERNETRADIO_ARCHINIT=n
+
+#
# Stack and heap information
#
# CONFIG_BOOT_RUNFROMFLASH - Some configurations support XIP
diff --git a/nuttx/configs/detron/nsh/setenv.sh b/nuttx/configs/detron/nsh/setenv.sh
index 7c57d0cf3..5971509ba 100755
--- a/nuttx/configs/detron/nsh/setenv.sh
+++ b/nuttx/configs/detron/nsh/setenv.sh
@@ -40,8 +40,7 @@ fi
if [ -z "${PATH_ORIG}" ]; then export PATH_ORIG="${PATH}"; fi
WD=`pwd`
-export LPCTOOL_DIR="${WD}/configs/detron/tools"
export BUILDROOT_BIN="${WD}/../buildroot/build_arm_nofpu/staging_dir/bin"
-export PATH="${BUILDROOT_BIN}:${LPCTOOL_DIR}:/sbin:/usr/sbin:${PATH_ORIG}"
+export PATH="${BUILDROOT_BIN}:/sbin:/usr/sbin:${PATH_ORIG}"
echo "PATH : ${PATH}"
diff --git a/nuttx/configs/detron/ostest/defconfig b/nuttx/configs/detron/ostest/defconfig
index 66eac4fb6..1816157de 100755
--- a/nuttx/configs/detron/ostest/defconfig
+++ b/nuttx/configs/detron/ostest/defconfig
@@ -84,7 +84,7 @@ CONFIG_ARCH_IRQPRIO=y
CONFIG_ARCH_INTERRUPTSTACK=n
CONFIG_ARCH_STACKDUMP=y
CONFIG_ARCH_BOOTLOADER=n
-CONFIG_ARCH_LEDS=y
+CONFIG_ARCH_LEDS=n
CONFIG_ARCH_BUTTONS=n
CONFIG_ARCH_CALIBRATION=n
CONFIG_ARCH_DMA=n
@@ -794,6 +794,11 @@ CONFIG_EXAMPLES_USBSERIAL_TRACECONTROLLER=n
CONFIG_EXAMPLES_USBSERIAL_TRACEINTERRUPTS=n
#
+# Settings for internet_radio by Decio
+#
+CONFIG_INTERNETRADIO_ARCHINIT=n
+
+#
# Stack and heap information
#
# CONFIG_BOOT_RUNFROMFLASH - Some configurations support XIP
diff --git a/nuttx/configs/detron/ostest/setenv.sh b/nuttx/configs/detron/ostest/setenv.sh
index 587efbe96..ed5ee3796 100755
--- a/nuttx/configs/detron/ostest/setenv.sh
+++ b/nuttx/configs/detron/ostest/setenv.sh
@@ -40,8 +40,7 @@ fi
if [ -z "${PATH_ORIG}" ]; then export PATH_ORIG="${PATH}"; fi
WD=`pwd`
-export LPCTOOL_DIR="${WD}/configs/detron/tools"
export BUILDROOT_BIN="${WD}/../buildroot/build_arm_nofpu/staging_dir/bin"
-export PATH="${BUILDROOT_BIN}:${LPCTOOL_DIR}:/sbin:/usr/sbin:${PATH_ORIG}"
+export PATH="${BUILDROOT_BIN}:/sbin:/usr/sbin:${PATH_ORIG}"
echo "PATH : ${PATH}"
diff --git a/nuttx/configs/detron/src/Makefile b/nuttx/configs/detron/src/Makefile
index 9a9134698..1d6d01355 100755
--- a/nuttx/configs/detron/src/Makefile
+++ b/nuttx/configs/detron/src/Makefile
@@ -38,7 +38,7 @@
CFLAGS += -I$(TOPDIR)/sched
ASRCS =
-CSRCS = up_boot.c up_leds.c up_ssp.c
+CSRCS = up_boot.c
ifeq ($(CONFIG_EXAMPLES_NSH_ARCHINIT),y)
CSRCS += up_nsh.c
endif
diff --git a/nuttx/configs/detron/src/detron_internal.h b/nuttx/configs/detron/src/detron_internal.h
index aedb48dd1..4b00c8032 100755
--- a/nuttx/configs/detron/src/detron_internal.h
+++ b/nuttx/configs/detron/src/detron_internal.h
@@ -34,6 +34,43 @@
*
************************************************************************************/
+/************************************************************************************
+ *
+ * Pin used in the Internet Radio Detron Board
+ *
+ * Graphic Display
+ *
+ * Pin Port Function
+ * 58 P0(20) DI
+ * 59 P0(19) RW
+ * 49 P0(11) ENABLE
+ * 78 P0(7) D0
+ * 79 P0(6) D1
+ * 78 P0(5) D2
+ * 81 P0(4) D3
+ * 94 P1(1) D4
+ * 95 P1(0) D5
+ * 47 P0(1) D6
+ * 46 P0(0) D7
+ *
+ * VS1003
+ *
+ * Pin Port Function
+ * 65 P2(8) xreset
+ * 85 P4(29) dreq
+ * 82 P4(28) xdcs
+ * 63 P0(16) xcs
+ * 62 P0(15) sclk
+ * 60 P0(18) si
+ * 61 P0(17) so
+ *
+ * USB
+ *
+ * Pin Port Function
+ * 29 D+
+ * 30 D-
+ */
+
#ifndef _CONFIGS_DETRON_SRC_DETRON_INTERNAL_H
#define _CONFIGS_DETRON_SRC_DETRON_INTERNAL_H
@@ -49,21 +86,42 @@
************************************************************************************/
/* Detron GPIO Pin Definitions ******************************************************/
-/* Board GPIO Usage: To be provided */
+/* Pinos do Display grafico */
-#define DETRON_LED1_A (GPIO_OUTPUT | GPIO_VALUE_ZERO | GPIO_PORT2 | GPIO_PIN0)
-#define DETRON_LED1_B (GPIO_OUTPUT | GPIO_VALUE_ZERO | GPIO_PORT2 | GPIO_PIN1)
-#define DETRON_LED2_A (GPIO_OUTPUT | GPIO_VALUE_ZERO | GPIO_PORT2 | GPIO_PIN2)
-#define DETRON_LED2_B (GPIO_OUTPUT | GPIO_VALUE_ZERO | GPIO_PORT2 | GPIO_PIN3)
-#define DETRON_232_ENABLE (GPIO_OUTPUT | GPIO_VALUE_ONE | GPIO_PORT2 | GPIO_PIN5)
-#define DETRON_232_POWERSAVE (GPIO_OUTPUT | GPIO_VALUE_ZERO | GPIO_PORT2 | GPIO_PIN5)
-#define DETRON_232_VALID (GPIO_INPUT | GPIO_PULLUP | GPIO_PORT2 | GPIO_PIN5)
-#define DETRON_HEARTBEAT (GPIO_OUTPUT | GPIO_VALUE_ONE | GPIO_PORT2 | GPIO_PIN11)
-#define DETRON_EXTRA_LED (GPIO_OUTPUT | GPIO_VALUE_ZERO | GPIO_PORT2 | GPIO_PIN12)
-#define DETRON_5V_ENABLE (GPIO_OUTPUT | GPIO_VALUE_ONE | GPIO_PORT2 | GPIO_PIN13)
-#define DETRON_5V_DISABLE (GPIO_OUTPUT | GPIO_VALUE_ZERO | GPIO_PORT2 | GPIO_PIN13)
+#define pin_di (GPIO_OUTPUT | GPIO_VALUE_ZERO | GPIO_PORT0 | GPIO_PIN20)
+#define pin_rw (GPIO_OUTPUT | GPIO_VALUE_ZERO | GPIO_PORT0 | GPIO_PIN19)
+#define pin_enable (GPIO_OUTPUT | GPIO_VALUE_ZERO | GPIO_PORT0 | GPIO_PIN11)
+#define pin_d0 (GPIO_OUTPUT | GPIO_VALUE_ZERO | GPIO_PORT0 | GPIO_PIN7)
+#define pin_d1 (GPIO_OUTPUT | GPIO_VALUE_ZERO | GPIO_PORT0 | GPIO_PIN6)
+#define pin_d2 (GPIO_OUTPUT | GPIO_VALUE_ZERO | GPIO_PORT0 | GPIO_PIN5)
+#define pin_d3 (GPIO_OUTPUT | GPIO_VALUE_ZERO | GPIO_PORT0 | GPIO_PIN4)
+#define pin_d4 (GPIO_OUTPUT | GPIO_VALUE_ZERO | GPIO_PORT1 | GPIO_PIN1)
+#define pin_d5 (GPIO_OUTPUT | GPIO_VALUE_ZERO | GPIO_PORT1 | GPIO_PIN0)
+#define pin_d6 (GPIO_OUTPUT | GPIO_VALUE_ZERO | GPIO_PORT0 | GPIO_PIN1)
+#define pin_d7 (GPIO_OUTPUT | GPIO_VALUE_ZERO | GPIO_PORT0 | GPIO_PIN0)
+#define pin_cs1 (GPIO_OUTPUT | GPIO_VALUE_ZERO | GPIO_PORT0 | GPIO_PIN10)
+#define pin_cs2 (GPIO_OUTPUT | GPIO_VALUE_ZERO | GPIO_PORT0 | GPIO_PIN9)
+#define pin_rst (GPIO_OUTPUT | GPIO_VALUE_ZERO | GPIO_PORT0 | GPIO_PIN8)
-#define DETRON_MMCSD_CS (GPIO_OUTPUT | GPIO_VALUE_ONE | GPIO_PORT0 | GPIO_PIN16)
+/* VS1003 pins
+ * xdcs = SPI in mode SDI (data)
+ * xcs = SPI in mode SCI (comand)
+ *
+ * sclk = SPI clock
+ * si = SPI in
+ * so = SPI out
+ *
+ * dreq = SPI status 1 - free 0 - busy
+ * xreset = hardware reset
+ */
+
+#define pin_vs1003_xreset (GPIO_OUTPUT | GPIO_VALUE_ZERO | GPIO_PORT2 | GPIO_PIN8)
+#define pin_vs1003_dreq (GPIO_INPUT | GPIO_VALUE_ZERO | GPIO_PORT4 | GPIO_PIN29)
+#define pin_vs1003_xdcs (GPIO_OUTPUT | GPIO_VALUE_ZERO | GPIO_PORT4 | GPIO_PIN28)
+#define pin_vs1003_xcs (GPIO_OUTPUT | GPIO_VALUE_ZERO | GPIO_PORT0 | GPIO_PIN16)
+#define pin_vs1003_sclk (GPIO_OUTPUT | GPIO_VALUE_ZERO | GPIO_PORT0 | GPIO_PIN15)
+#define pin_vs1003_si (GPIO_OUTPUT | GPIO_VALUE_ZERO | GPIO_PORT0 | GPIO_PIN18)
+#define pin_vs1003_so (GPIO_INPUT | GPIO_VALUE_ZERO | GPIO_PORT0 | GPIO_PIN17)
/************************************************************************************
* Public Types
@@ -78,17 +136,7 @@
/************************************************************************************
* Public Functions
************************************************************************************/
-
-/************************************************************************************
- * Name: lpc17_sspinitialize
- *
- * Description:
- * Called to configure SPI chip select GPIO pins for the Detron board.
- *
- ************************************************************************************/
-
-extern void weak_function lpc17_sspinitialize(void);
-
+
#endif /* __ASSEMBLY__ */
#endif /* _CONFIGS_DETRON_SRC_DETRON_INTERNAL_H */
diff --git a/nuttx/configs/detron/src/up_boot.c b/nuttx/configs/detron/src/up_boot.c
index cb66865b9..3719c8635 100755
--- a/nuttx/configs/detron/src/up_boot.c
+++ b/nuttx/configs/detron/src/up_boot.c
@@ -74,36 +74,4 @@
void lpc17_boardinitialize(void)
{
- /* Enable +5V needed for CAN */
-
-#if defined(CONFIG_LPC17_CAN1) || defined(CONFIG_LPC17_CAN2)
- lpc17_configgpio(DETRON_5V_ENABLE);
-#else
- lpc17_configgpio(DETRON_5V_DISABLE);
-#endif
-
- /* If UART0 is used, enabled the MAX232 driver */
-
-#ifdef CONFIG_LPC17_UART0
- lpc17_configgpio(DETRON_232_ENABLE);
-#else
- lpc17_configgpio(DETRON_232_POWERSAVE);
-#endif
-
- /* Configure SSP chip selects if 1) at least one SSP is enabled, and 2) the weak
- * function lpc17_sspinitialize() has been brought into the link.
- */
-
-#if defined(CONFIG_LPC17_SSP0) || defined(CONFIG_LPC17_SSP1)
- if (lpc17_sspinitialize)
- {
- lpc17_sspinitialize();
- }
-#endif
-
- /* Configure on-board LEDs if LED support has been selected. */
-
-#ifdef CONFIG_ARCH_LEDS
- up_ledinit();
-#endif
}
diff --git a/nuttx/configs/detron/src/up_leds.c b/nuttx/configs/detron/src/up_leds.c
deleted file mode 100755
index 8ea1b98e0..000000000
--- a/nuttx/configs/detron/src/up_leds.c
+++ /dev/null
@@ -1,234 +0,0 @@
-/****************************************************************************
- * configs/detron/src/up_leds.c
- * arch/arm/src/board/up_leds.c
- *
- * Copyright (C) 2010 Gregory Nutt. All rights reserved.
- * Author: Gregory Nutt <spudmonkey@racsa.co.cr>
- *
- * Redistribution and use in source and binary forms, with or without
- * modification, are permitted provided that the following conditions
- * are met:
- *
- * 1. Redistributions of source code must retain the above copyright
- * notice, this list of conditions and the following disclaimer.
- * 2. Redistributions in binary form must reproduce the above copyright
- * notice, this list of conditions and the following disclaimer in
- * the documentation and/or other materials provided with the
- * distribution.
- * 3. Neither the name NuttX nor the names of its contributors may be
- * used to endorse or promote products derived from this software
- * without specific prior written permission.
- *
- * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
- * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
- * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
- * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
- * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
- * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
- * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
- * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
- * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
- * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
- * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
- * POSSIBILITY OF SUCH DAMAGE.
- *
- ****************************************************************************/
-
-/****************************************************************************
- * 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 "lpc17_internal.h"
-
-#include "detron_internal.h"
-
-#ifdef CONFIG_ARCH_LEDS
-
-/****************************************************************************
- * Definitions
- ****************************************************************************/
-
-/* 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
-# 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(DETRON_LED1_A, m)
-#else
-# define led_dumpgpio(m)
-#endif
-
-/****************************************************************************
- * Private Data
- ****************************************************************************/
-
-/* The assumes 3 LEDs: LED1, LED2, and HEARTBEAT. LED1 and LED2 are capabile
- * of OFF/GREEN/RED/AMBER status. If CONFIG_ARCH_LEDS is defined, these LEDs
- * will be controlled as follows for NuttX debug functionality (where NC means
- * "No Change").
- *
- * LED1 LED2 HEARTBEAT
- * +------- ------ -----------------------
- * LED_STARTED | OFF OFF OFF
- * LED_HEAPALLOCATE | GREEN OFF OFF
- * LED_IRQSENABLED | OFF GREEN OFF
- * LED_STACKCREATED | OFF OFF OFF
- * LED_INIRQ | NC NC ON (momentary)
- * LED_SIGNAL | NC NC ON (momentary)
- * LED_ASSERTION | NC NC ON (momentary)
- * LED_PANIC | NC NC ON (1Hz flashing)
- */
-
-static bool g_initialized;
-static int g_nestcount;
-
-/****************************************************************************
- * Private Functions
- ****************************************************************************/
-
-/****************************************************************************
- * Public Functions
- ****************************************************************************/
-
-/****************************************************************************
- * Name: up_ledinit
- ****************************************************************************/
-
-void up_ledinit(void)
-{
- /* Configure all LED GPIO lines */
-
- led_dumpgpio("up_ledinit() Entry)");
-
- lpc17_configgpio(DETRON_LED1_A);
- lpc17_configgpio(DETRON_LED1_B);
- lpc17_configgpio(DETRON_LED2_A);
- lpc17_configgpio(DETRON_LED2_B);
- lpc17_configgpio(DETRON_HEARTBEAT);
- lpc17_configgpio(DETRON_EXTRA_LED);
-
- led_dumpgpio("up_ledinit() Exit");
-}
-
-/****************************************************************************
- * Name: up_ledon
- ****************************************************************************/
-
-void up_ledon(int led)
-{
- /* We will control LED1 and LED2 not yet completed the boot sequence. */
-
- if (!g_initialized)
- {
- enum lpc17_ledstate_e led1 = LPC17_LEDSTATE_OFF;
- enum lpc17_ledstate_e led2 = LPC17_LEDSTATE_OFF;
- switch (led)
- {
- case LED_STACKCREATED:
- g_initialized = true;
- case LED_STARTED:
- default:
- break;
-
- case LED_HEAPALLOCATE:
- led1 = LPC17_LEDSTATE_GREEN;
- break;
-
- case LED_IRQSENABLED:
- led2 = LPC17_LEDSTATE_GREEN;
- }
- lpc17_led1(led1);
- lpc17_led2(led2);
- }
-
- /* We will always control the HB LED */
-
- switch (led)
- {
- default:
- break;
-
- case LED_INIRQ:
- case LED_SIGNAL:
- case LED_ASSERTION:
- case LED_PANIC:
- lpc17_gpiowrite(DETRON_HEARTBEAT, false);
- g_nestcount++;
- }
-}
-
-/****************************************************************************
- * Name: up_ledoff
- ****************************************************************************/
-
-void up_ledoff(int led)
-{
- /* In all states, OFF can only mean turning off the HB LED */
-
- if (g_nestcount <= 1)
- {
- lpc17_gpiowrite(DETRON_HEARTBEAT, true);
- g_nestcount = 0;
- }
- else
- {
- g_nestcount--;
- }
-}
-
-/************************************************************************************
- * Name: lpc17_led1 and 2
- *
- * Description:
- * Once the system has booted, these functions can be used to control LEDs 1 and 2
- *
- ************************************************************************************/
-
-void lpc17_led1(enum lpc17_ledstate_e state)
-{
- bool red = (((unsigned int)state & LPC17_LEDSTATE_RED) != 0);
- bool green = (((unsigned int)state & LPC17_LEDSTATE_GREEN) != 0);
-
- lpc17_gpiowrite(DETRON_LED1_A, red);
- lpc17_gpiowrite(DETRON_LED1_B, green);
-}
-
-void lpc17_led2(enum lpc17_ledstate_e state)
-{
- bool red = (((unsigned int)state & LPC17_LEDSTATE_RED) != 0);
- bool green = (((unsigned int)state & LPC17_LEDSTATE_GREEN) != 0);
-
- lpc17_gpiowrite(DETRON_LED2_A, red);
- lpc17_gpiowrite(DETRON_LED2_B, green);
-}
-#endif /* CONFIG_ARCH_LEDS */
diff --git a/nuttx/configs/detron/src/up_nsh.c b/nuttx/configs/detron/src/up_nsh.c
index 47dcbaf1f..650bf9276 100755
--- a/nuttx/configs/detron/src/up_nsh.c
+++ b/nuttx/configs/detron/src/up_nsh.c
@@ -58,25 +58,9 @@
/* Configuration ************************************************************/
-/* PORT and SLOT number probably depend on the board configuration */
-
#ifdef CONFIG_ARCH_BOARD_DETRON
-# define CONFIG_EXAMPLES_NSH_HAVEMMCSD 1
-# define CONFIG_EXAMPLES_NSH_HAVEUSBHOST 1
-# if !defined(CONFIG_EXAMPLES_NSH_MMCSDSPIPORTNO) || CONFIG_EXAMPLES_NSH_MMCSDSPIPORTNO != 0
-# error "The Detron MMC/SD is on SSP0"
-# undef CONFIG_EXAMPLES_NSH_MMCSDSPIPORTNO
-# define CONFIG_EXAMPLES_NSH_MMCSDSPIPORTNO 0
-# endif
-# if !defined(CONFIG_EXAMPLES_NSH_MMCSDSLOTNO) || CONFIG_EXAMPLES_NSH_MMCSDSLOTNO != 0
-# error "The Detron MMC/SD is only one slot (0)"
-# undef CONFIG_EXAMPLES_NSH_MMCSDSLOTNO
-# define CONFIG_EXAMPLES_NSH_MMCSDSLOTNO 0
-# endif
-# ifndef CONFIG_LPC17_SSP0
-# undef CONFIG_EXAMPLES_NSH_HAVEMMCSD
-# warning "CONFIG_LPC17_SSP0 is not enabled"
-# endif
+# undef CONFIG_EXAMPLES_NSH_HAVEMMCSD
+# define CONFIG_EXAMPLES_NSH_HAVEUSBHOST 1
#else
# error "Unrecognized board"
# undef CONFIG_EXAMPLES_NSH_HAVEMMCSD
@@ -89,6 +73,21 @@
# undef CONFIG_EXAMPLES_NSH_HAVEMMCSD
#endif
+/* MMC/SD PORT and SLOT number probably depend on the board configuration */
+
+#ifdef CONFIG_EXAMPLES_NSH_HAVEMMCSD
+# if !defined(CONFIG_EXAMPLES_NSH_MMCSDSPIPORTNO) || CONFIG_EXAMPLES_NSH_MMCSDSPIPORTNO != 0
+# error "The Detron MMC/SD is on SSP0"
+# undef CONFIG_EXAMPLES_NSH_MMCSDSPIPORTNO
+# define CONFIG_EXAMPLES_NSH_MMCSDSPIPORTNO 0
+# endif
+# if !defined(CONFIG_EXAMPLES_NSH_MMCSDSLOTNO) || CONFIG_EXAMPLES_NSH_MMCSDSLOTNO != 0
+# error "The Detron MMC/SD is only one slot (0)"
+# undef CONFIG_EXAMPLES_NSH_MMCSDSLOTNO
+# define CONFIG_EXAMPLES_NSH_MMCSDSLOTNO 0
+# endif
+#endif
+
#ifndef CONFIG_EXAMPLES_NSH_MMCSDMINOR
# define CONFIG_EXAMPLES_NSH_MMCSDMINOR 0
#endif
diff --git a/nuttx/configs/detron/src/up_ssp.c b/nuttx/configs/detron/src/up_ssp.c
deleted file mode 100755
index 92206df76..000000000
--- a/nuttx/configs/detron/src/up_ssp.c
+++ /dev/null
@@ -1,172 +0,0 @@
-/************************************************************************************
- * configs/detron/src/up_ssp.c
- * arch/arm/src/board/up_ssp.c
- *
- * Copyright (C) 2010 Gregory Nutt. All rights reserved.
- * Author: Gregory Nutt <spudmonkey@racsa.co.cr>
- *
- * Redistribution and use in source and binary forms, with or without
- * modification, are permitted provided that the following conditions
- * are met:
- *
- * 1. Redistributions of source code must retain the above copyright
- * notice, this list of conditions and the following disclaimer.
- * 2. Redistributions in binary form must reproduce the above copyright
- * notice, this list of conditions and the following disclaimer in
- * the documentation and/or other materials provided with the
- * distribution.
- * 3. Neither the name NuttX nor the names of its contributors may be
- * used to endorse or promote products derived from this software
- * without specific prior written permission.
- *
- * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
- * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
- * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
- * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
- * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
- * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
- * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
- * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
- * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
- * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
- * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
- * POSSIBILITY OF SUCH DAMAGE.
- *
- ************************************************************************************/
-
-/************************************************************************************
- * Included Files
- ************************************************************************************/
-
-#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 "lpc17_internal.h"
-#include "detron_internal.h"
-
-/* The LM3S6965 Eval Kit microSD CS is on SSI0 */
-
-#if defined(CONFIG_LPC17_SSP0) || defined(CONFIG_LPC17_SSP1)
-
-/************************************************************************************
- * Definitions
- ************************************************************************************/
-
-/* Enables debug output from this file (needs CONFIG_DEBUG too) */
-
-#undef SSP_DEBUG /* Define to enable debug */
-#undef SSP_VERBOSE /* Define to enable verbose debug */
-
-#ifdef SSP_DEBUG
-# define sspdbg lldbg
-# ifdef SSP_VERBOSE
-# define sspvdbg lldbg
-# else
-# define sspvdbg(x...)
-# endif
-#else
-# undef SSP_VERBOSE
-# define sspdbg(x...)
-# define sspvdbg(x...)
-#endif
-
-/* Dump GPIO registers */
-
-#ifdef SSP_VERBOSE
-# define ssp_dumpgpio(m) lpc17_dumpgpio(SDCCS_GPIO, m)
-#else
-# define ssp_dumpgpio(m)
-#endif
-
-/************************************************************************************
- * Private Functions
- ************************************************************************************/
-
-/************************************************************************************
- * Public Functions
- ************************************************************************************/
-
-/************************************************************************************
- * Name: lpc17_sspinitialize
- *
- * Description:
- * Called to configure SPI chip select GPIO pins for the LM3S6965 Eval Kit.
- *
- ************************************************************************************/
-
-void weak_function lpc17_sspinitialize(void)
-{
- /* Configure the SPI-based microSD CS GPIO */
-
- ssp_dumpgpio("lpc17_sspinitialize() Entry)");
-
-#ifdef CONFIG_LPC17_SSP0
- lpc17_configgpio(DETRON_MMCSD_CS);
-#endif
-
-#ifdef CONFIG_LPC17_SSP1
-# warning "SSP1 chip selects not known"
-#endif
- ssp_dumpgpio("lpc17_sspinitialize() Exit");
-}
-
-/************************************************************************************
- * Name: lpc17_ssp0/ssp1select and lpc17_ssp0/ssp1status
- *
- * Description:
- * The external functions, lpc17_ssp0/ssp1select and lpc17_ssp0/ssp1status
- * must be provided by board-specific logic. They are implementations of the select
- * and status methods of the SPI interface defined by struct spi_ops_s (see
- * include/nuttx/spi.h). All other methods (including up_spiinitialize())
- * are provided by common LPC17xx logic. To use this common SPI logic on your
- * board:
- *
- * 1. Provide logic in lpc17_boardinitialize() to configure SPI/SSP chip select
- * pins.
- * 2. Provide lpc17_ssp0/ssp1select() and lpc17_ssp0/ssp1status() functions
- * in your board-specific logic. These functions will perform chip selection
- * and status operations using GPIOs in the way your board is configured.
- * 3. Add a calls to up_spiinitialize() in your low level application
- * initialization logic
- * 4. The handle returned by up_spiinitialize() may then be used to bind the
- * SPI driver to higher level logic (e.g., calling
- * mmcsd_spislotinitialize(), for example, will bind the SPI driver to
- * the SPI MMC/SD driver).
- *
- ************************************************************************************/
-
-#ifdef CONFIG_LPC17_SSP0
-void lpc17_ssp0select(FAR struct spi_dev_s *dev, enum spi_dev_e devid, bool selected)
-{
- sspdbg("devid: %d CS: %s\n", (int)devid, selected ? "assert" : "de-assert");
- ssp_dumpgpio("lpc17_spiselect() Entry");
-
- if (devid == SPIDEV_MMCSD)
- {
- /* Assert the CS pin to the card */
-
- lpc17_gpiowrite(DETRON_MMCSD_CS, !selected);
- }
- ssp_dumpgpio("lpc17_spiselect() Exit");
-}
-
-uint8_t lpc17_ssp0status(FAR struct spi_dev_s *dev, enum spi_dev_e devid)
-{
- sspdbg("Returning SPI_STATUS_PRESENT\n");
- return SPI_STATUS_PRESENT;
-}
-#endif
-
-#ifdef CONFIG_LPC17_SSP1
-# warning "SSP1 chip selects not known"
-#endif
-
-#endif /* CONFIG_LPC17_SSP0 || CONFIG_LPC17_SSP1 */
diff --git a/nuttx/configs/detron/wlan/defconfig b/nuttx/configs/detron/wlan/defconfig
index f9e3cf4c4..d173298ca 100755
--- a/nuttx/configs/detron/wlan/defconfig
+++ b/nuttx/configs/detron/wlan/defconfig
@@ -85,7 +85,7 @@ CONFIG_ARCH_IRQPRIO=y
CONFIG_ARCH_INTERRUPTSTACK=n
CONFIG_ARCH_STACKDUMP=y
CONFIG_ARCH_BOOTLOADER=n
-CONFIG_ARCH_LEDS=y
+CONFIG_ARCH_LEDS=n
CONFIG_ARCH_BUTTONS=n
CONFIG_ARCH_CALIBRATION=n
CONFIG_ARCH_DMA=n
@@ -860,6 +860,11 @@ CONFIG_EXAMPLES_USBSERIAL_TRACECONTROLLER=n
CONFIG_EXAMPLES_USBSERIAL_TRACEINTERRUPTS=n
#
+# Settings for internet_radio by Decio
+#
+CONFIG_INTERNETRADIO_ARCHINIT=n
+
+#
# Stack and heap information
#
# CONFIG_BOOT_RUNFROMFLASH - Some configurations support XIP
diff --git a/nuttx/configs/detron/wlan/setenv.sh b/nuttx/configs/detron/wlan/setenv.sh
index 29370d7be..7dfa40542 100755
--- a/nuttx/configs/detron/wlan/setenv.sh
+++ b/nuttx/configs/detron/wlan/setenv.sh
@@ -41,8 +41,7 @@ fi
if [ -z "${PATH_ORIG}" ]; then export PATH_ORIG="${PATH}"; fi
WD=`pwd`
-export LPCTOOL_DIR="${WD}/configs/detron/tools"
export BUILDROOT_BIN="${WD}/../buildroot/build_arm_nofpu/staging_dir/bin"
-export PATH="${BUILDROOT_BIN}:${LPCTOOL_DIR}:/sbin:/usr/sbin:${PATH_ORIG}"
+export PATH="${BUILDROOT_BIN}:/sbin:/usr/sbin:${PATH_ORIG}"
echo "PATH : ${PATH}"