summaryrefslogtreecommitdiff
path: root/nuttx/configs/mikroe-stm32f4/src
diff options
context:
space:
mode:
authorGregory Nutt <gnutt@nuttx.org>2013-05-21 13:13:05 -0600
committerGregory Nutt <gnutt@nuttx.org>2013-05-21 13:13:05 -0600
commit801977de7c84d03616329795e1c59929ab948906 (patch)
treeb9d9220000c01cf9aca8e010f43fc488ccc26f26 /nuttx/configs/mikroe-stm32f4/src
parent3895e0ec4c2c3057935bbeb7558fa4b815385334 (diff)
downloadpx4-nuttx-801977de7c84d03616329795e1c59929ab948906.tar.gz
px4-nuttx-801977de7c84d03616329795e1c59929ab948906.tar.bz2
px4-nuttx-801977de7c84d03616329795e1c59929ab948906.zip
Audio subystem update from Ken Pettit. Plus moved some header files
Diffstat (limited to 'nuttx/configs/mikroe-stm32f4/src')
-rw-r--r--nuttx/configs/mikroe-stm32f4/src/Makefile4
-rw-r--r--nuttx/configs/mikroe-stm32f4/src/mikroe-stm32f4-internal.h23
-rw-r--r--nuttx/configs/mikroe-stm32f4/src/up_nsh.c21
-rw-r--r--nuttx/configs/mikroe-stm32f4/src/up_spi.c15
-rw-r--r--nuttx/configs/mikroe-stm32f4/src/up_vs1053.c200
5 files changed, 242 insertions, 21 deletions
diff --git a/nuttx/configs/mikroe-stm32f4/src/Makefile b/nuttx/configs/mikroe-stm32f4/src/Makefile
index c166e1926..5ca1fe3ee 100644
--- a/nuttx/configs/mikroe-stm32f4/src/Makefile
+++ b/nuttx/configs/mikroe-stm32f4/src/Makefile
@@ -94,6 +94,10 @@ ifeq ($(CONFIG_LCD_MIO283QT2),y)
CSRCS += up_mio283qt2.c
endif
+ifeq ($(CONFIG_VS1053),y)
+CSRCS += up_vs1053.c
+endif
+
COBJS = $(CSRCS:.c=$(OBJEXT))
SRCS = $(ASRCS) $(CSRCS)
diff --git a/nuttx/configs/mikroe-stm32f4/src/mikroe-stm32f4-internal.h b/nuttx/configs/mikroe-stm32f4/src/mikroe-stm32f4-internal.h
index d1a69547e..0f6894316 100644
--- a/nuttx/configs/mikroe-stm32f4/src/mikroe-stm32f4-internal.h
+++ b/nuttx/configs/mikroe-stm32f4/src/mikroe-stm32f4-internal.h
@@ -92,7 +92,9 @@
GPIO_OUTPUT_SET|GPIO_PORTD|GPIO_PIN3)
#define GPIO_CS_FLASH (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_50MHz|\
GPIO_OUTPUT_SET|GPIO_PORTD|GPIO_PIN7)
-#define GPIO_CS_MP3 (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_50MHz|\
+#define GPIO_CS_MP3_DATA (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_50MHz|\
+ GPIO_OUTPUT_SET|GPIO_PORTC|GPIO_PIN9)
+#define GPIO_CS_MP3_CMD (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_50MHz|\
GPIO_OUTPUT_SET|GPIO_PORTC|GPIO_PIN8)
#define GPIO_CS_EXP_SPI3 (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_50MHz|\
GPIO_OUTPUT_SET|GPIO_PORTD|GPIO_PIN0)
@@ -182,6 +184,13 @@
#define GPIO_TP_XL (GPIO_ANALOG|GPIO_PORTB|GPIO_PIN1)
+/* MP3 Codec control pins */
+
+#define GPIO_VS1053_RST (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_SPEED_50MHz|\
+ GPIO_OUTPUT_SET|GPIO_PORTC|GPIO_PIN7)
+#define GPIO_VS1053_DREQ (GPIO_INPUT|GPIO_SPEED_50MHz|GPIO_PORTC|GPIO_PIN6)
+
+
/****************************************************************************************************
* Public Types
****************************************************************************************************/
@@ -258,5 +267,17 @@ void stm32_lcdinitialize(void);
int up_lcdinitialize(void);
#endif
+/****************************************************************************************************
+ * Name: up_vs1053initialize
+ *
+ * Description:
+ * Initialize the VS1053 Audio CODEC hardware.
+ *
+ ****************************************************************************************************/
+
+#ifdef CONFIG_VS1053
+void up_vs1053initialize(FAR struct spi_dev_s *spi);
+#endif
+
#endif /* __ASSEMBLY__ */
#endif /* __CONFIGS_MIKROE_STM32F4_SRC_MIKROE_STM32F4_INTERNAL_H */
diff --git a/nuttx/configs/mikroe-stm32f4/src/up_nsh.c b/nuttx/configs/mikroe-stm32f4/src/up_nsh.c
index 648f69c64..366e4e8f6 100644
--- a/nuttx/configs/mikroe-stm32f4/src/up_nsh.c
+++ b/nuttx/configs/mikroe-stm32f4/src/up_nsh.c
@@ -64,7 +64,7 @@
#endif
#ifdef CONFIG_AUDIO
-# include "nuttx/audio.h"
+# include "nuttx/audio/audio.h"
#endif
#include "stm32.h"
@@ -182,9 +182,6 @@ int nsh_archinitialize(void)
FAR struct spi_dev_s *spi;
FAR struct mtd_dev_s *mtd;
#endif
-#ifdef CONFIG_AUDIO
- FAR struct audio_lowerhalf_s *pVs1053;
-#endif
int ret;
/* Configure SPI-based devices */
@@ -351,21 +348,13 @@ int nsh_archinitialize(void)
#endif
- /* Configure the Audio sub-system if enabled */
+ /* Configure the Audio sub-system if enabled and bind it to SPI 3 */
#ifdef CONFIG_AUDIO
- pVs1053 = vs1053_initialize(0);
- if (pVs1053 == NULL)
- {
- message("nsh_archinitialize: Failed to initialize VS1053 Audio module\n");
- }
- else
- {
- /* Bind the vs1053 to the audio upper-half driver */
- audio_register("mp30", pVs1053);
- }
+ up_vs1053initialize(spi);
+
+#endif
-#endif /* CONFIG_AUDIO */
return OK;
}
diff --git a/nuttx/configs/mikroe-stm32f4/src/up_spi.c b/nuttx/configs/mikroe-stm32f4/src/up_spi.c
index 08fa89a9c..448ed966a 100644
--- a/nuttx/configs/mikroe-stm32f4/src/up_spi.c
+++ b/nuttx/configs/mikroe-stm32f4/src/up_spi.c
@@ -114,8 +114,10 @@ void weak_function stm32_spiinitialize(void)
#endif
#ifdef CONFIG_AUDIO_MP3_CODEC
- (void)stm32_configgpio(GPIO_CS_MP3); /* MP3 codec chip select */
- stm32_gpiowrite(GPIO_CS_MP3, 1); /* Ensure the CS is inactive */
+ (void)stm32_configgpio(GPIO_CS_MP3_DATA); /* MP3 codec chip select for DATA */
+ (void)stm32_configgpio(GPIO_CS_MP3_CMD); /* MP3 codec chip select for CMD */
+ stm32_gpiowrite(GPIO_CS_MP3_DATA, 1); /* Ensure the CS is inactive */
+ stm32_gpiowrite(GPIO_CS_MP3_CMD, 1); /* Ensure the CS is inactive */
#endif
/* Configure the EXP I/O cs for SPI3 */
@@ -172,11 +174,16 @@ void stm32_spi3select(FAR struct spi_dev_s *dev, enum spi_dev_e devid, bool sele
#endif
#if defined(CONFIG_AUDIO_MP3_CODEC)
- if (devid == SPIDEV_AUDIO)
+ if (devid == SPIDEV_AUDIO_DATA)
{
- stm32_gpiowrite(GPIO_CS_MP3, !selected);
+ stm32_gpiowrite(GPIO_CS_MP3_DATA, !selected);
+ }
+ else if (devid == SPIDEV_AUDIO_CTRL)
+ {
+ stm32_gpiowrite(GPIO_CS_MP3_CMD, !selected);
}
else
+
#endif
/* Must be the expansion header device */
diff --git a/nuttx/configs/mikroe-stm32f4/src/up_vs1053.c b/nuttx/configs/mikroe-stm32f4/src/up_vs1053.c
new file mode 100644
index 000000000..cc7e0f96d
--- /dev/null
+++ b/nuttx/configs/mikroe-stm32f4/src/up_vs1053.c
@@ -0,0 +1,200 @@
+/****************************************************************************
+ * configs/mikroe-stm32f4/src/up_vs1053.c
+ *
+ * Copyright (C) 2013 Ken Pettit. All rights reserved.
+ * Author: Ken Pettit <pettitkd@gmail.com>
+ *
+ * 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 <stdio.h>
+#include <debug.h>
+
+#include <nuttx/spi.h>
+#include <nuttx/audio/audio.h>
+#include <nuttx/audio/vs1053.h>
+
+#include <arch/board/board.h>
+
+#include "chip.h"
+#include "up_arch.h"
+#include "mikroe-stm32f4-internal.h"
+
+#ifdef CONFIG_VS1053
+
+/****************************************************************************
+ * Definitions
+ ****************************************************************************/
+
+/* VS1053 is on SPI3 */
+
+#ifndef CONFIG_STM32_SPI3
+# error "Need CONFIG_STM32_SPI3 in the configuration"
+#endif
+
+/* SPI Assumptions **********************************************************/
+
+#define VS1053_SPI_PORTNO 3 /* On SPI3 */
+#define VS1053_DEVNO 0 /* Only one VS1053 */
+
+/****************************************************************************
+ * Private Types
+ ****************************************************************************/
+
+struct stm32_lower_s
+{
+ const struct vs1053_lower_s lower; /* Low-level MCU interface */
+ xcpt_t handler; /* VS1053 interrupt handler */
+};
+
+/****************************************************************************
+ * Private Function Prototypes
+ ****************************************************************************/
+
+static int up_attach(FAR const struct vs1053_lower_s *lower, xcpt_t handler);
+static void up_enable(FAR const struct vs1053_lower_s *lower);
+static void up_disable(FAR const struct vs1053_lower_s *lower);
+static void up_reset(FAR const struct vs1053_lower_s *lower, bool state);
+
+/****************************************************************************
+ * Private Data
+ ****************************************************************************/
+
+/* The VS1053 provides interrupts to the MCU via a GPIO pin. The
+ * following structure provides an MCU-independent mechanixm for controlling
+ * the VS1053 GPIO interrupt.
+ */
+
+static struct stm32_lower_s g_vs1053lower =
+{
+ .lower =
+ {
+ .attach = up_attach,
+ .enable = up_enable,
+ .disable = up_disable,
+ .reset = up_reset
+ },
+ .handler = NULL,
+};
+
+/****************************************************************************
+ * Private Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Name: struct vs1053_lower_s methods
+ ****************************************************************************/
+
+static int up_attach(FAR const struct vs1053_lower_s *lower, xcpt_t handler)
+{
+ FAR struct stm32_lower_s *priv = (FAR struct stm32_lower_s *)lower;
+
+ /* Just save the handler for use when the interrupt is enabled */
+
+ priv->handler = handler;
+ return OK;
+}
+
+static void up_enable(FAR const struct vs1053_lower_s *lower)
+{
+ FAR struct stm32_lower_s *priv = (FAR struct stm32_lower_s *)lower;
+
+ DEBUGASSERT(priv->handler);
+ (void)stm32_gpiosetevent(GPIO_VS1053_DREQ, false, true, true, priv->handler);
+}
+
+static void up_disable(FAR const struct vs1053_lower_s *lower)
+{
+ (void)stm32_gpiosetevent(GPIO_VS1053_DREQ, false, true, true, NULL);
+}
+
+static void up_reset(FAR const struct vs1053_lower_s *lower, bool state)
+{
+ stm32_gpiowrite(GPIO_VS1053_RST, state);
+}
+
+/****************************************************************************
+ * Public Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Name: up_netinitialize
+ ****************************************************************************/
+
+void up_vs1053initialize(FAR struct spi_dev_s* spi)
+{
+ int ret;
+ int x;
+ char name[8];
+ FAR struct audio_lowerhalf_s *pVs1053;
+
+ /* Assumptions:
+ * 1) SPI pins were configured in up_spi.c early in the boot-up phase.
+ * 2) Clocking for the SPI1 peripheral was also provided earlier in boot-up.
+ */
+
+ /* Take VS1053 out of reset (active low)*/
+
+ (void)stm32_configgpio(GPIO_VS1053_RST);
+ (void)stm32_configgpio(GPIO_VS1053_DREQ);
+
+ stm32_gpiowrite(GPIO_VS1053_RST, 0);
+ for (x = 0; x < 10000; x++);
+ stm32_gpiowrite(GPIO_VS1053_RST, 1);
+
+ /* Bind the SPI port to the VS1053 driver */
+
+ pVs1053 = vs1053_initialize(spi, &g_vs1053lower.lower, VS1053_DEVNO);
+ if (ret < 0)
+ {
+ audlldbg("Failed to bind SPI port %d VS1053 device: %d\n",
+ VS1053_DEVNO, ret);
+ return;
+ }
+
+ /* Now register the audio device */
+
+ sprintf(name, "mp3%d", VS1053_DEVNO);
+ ret = audio_register(name, pVs1053);
+ if (ret < 0)
+ {
+ auddbg("up_vs1053initialize: Failed to register VS1053 Audio device\n");
+ }
+
+ audllvdbg("Bound SPI port to VS1053 device %s\n", name);
+}
+
+#endif /* CONFIG_VS1053 */