summaryrefslogtreecommitdiff
path: root/nuttx/configs/vsn/src
diff options
context:
space:
mode:
authorpatacongo <patacongo@42af7a65-404d-4744-a932-0658087f49c3>2011-03-06 15:39:02 +0000
committerpatacongo <patacongo@42af7a65-404d-4744-a932-0658087f49c3>2011-03-06 15:39:02 +0000
commit9fa76b36d2eb8b4c329e763e499675dee143d527 (patch)
tree189cfec40a0599ca60497ac94d137f9f1231dae2 /nuttx/configs/vsn/src
parent517ae43b4f1c1eaf64137a5a6d0d79f3e26608af (diff)
downloadpx4-nuttx-9fa76b36d2eb8b4c329e763e499675dee143d527.tar.gz
px4-nuttx-9fa76b36d2eb8b4c329e763e499675dee143d527.tar.bz2
px4-nuttx-9fa76b36d2eb8b4c329e763e499675dee143d527.zip
Add support for RAMTRON NVRAM devices
git-svn-id: svn://svn.code.sf.net/p/nuttx/code/trunk@3347 42af7a65-404d-4744-a932-0658087f49c3
Diffstat (limited to 'nuttx/configs/vsn/src')
-rw-r--r--nuttx/configs/vsn/src/Makefile7
-rw-r--r--nuttx/configs/vsn/src/README.txt12
-rw-r--r--nuttx/configs/vsn/src/boot.c (renamed from nuttx/configs/vsn/src/up_boot.c)31
-rw-r--r--nuttx/configs/vsn/src/buttons.c (renamed from nuttx/configs/vsn/src/up_buttons.c)4
-rw-r--r--nuttx/configs/vsn/src/leds.c (renamed from nuttx/configs/vsn/src/up_leds.c)6
-rw-r--r--nuttx/configs/vsn/src/nsh.c89
-rw-r--r--nuttx/configs/vsn/src/power.c57
-rw-r--r--nuttx/configs/vsn/src/ramtron.c87
-rw-r--r--nuttx/configs/vsn/src/sdcard.c120
-rw-r--r--nuttx/configs/vsn/src/spi.c (renamed from nuttx/configs/vsn/src/up_spi.c)37
-rw-r--r--nuttx/configs/vsn/src/sysclock.c (renamed from nuttx/configs/vsn/src/up_sysclock.c)2
-rw-r--r--nuttx/configs/vsn/src/up_nsh.c215
-rw-r--r--nuttx/configs/vsn/src/usbdev.c (renamed from nuttx/configs/vsn/src/up_usbdev.c)6
-rw-r--r--nuttx/configs/vsn/src/usbstrg.c (renamed from nuttx/configs/vsn/src/up_usbstrg.c)4
-rw-r--r--nuttx/configs/vsn/src/vsn.h (renamed from nuttx/configs/vsn/src/vsn-internal.h)55
15 files changed, 452 insertions, 280 deletions
diff --git a/nuttx/configs/vsn/src/Makefile b/nuttx/configs/vsn/src/Makefile
index f6d03d41f..1a2005d60 100644
--- a/nuttx/configs/vsn/src/Makefile
+++ b/nuttx/configs/vsn/src/Makefile
@@ -43,13 +43,14 @@ CFLAGS += -I$(TOPDIR)/sched
ASRCS =
AOBJS = $(ASRCS:.S=$(OBJEXT))
-CSRCS = up_sysclock.c up_boot.c up_leds.c up_buttons.c up_spi.c up_usbdev.c
+CSRCS = sysclock.c boot.c leds.c buttons.c spi.c \
+ usbdev.c sdcard.c ramtron.c power.c
ifeq ($(CONFIG_EXAMPLES_NSH_ARCHINIT),y)
-CSRCS += up_nsh.c
+CSRCS += nsh.c
endif
ifeq ($(CONFIG_APP_DIR),examples/usbstorage)
-CSRCS += up_usbstrg.c
+CSRCS += usbstrg.c
endif
COBJS = $(CSRCS:.c=$(OBJEXT))
diff --git a/nuttx/configs/vsn/src/README.txt b/nuttx/configs/vsn/src/README.txt
new file mode 100644
index 000000000..bacf82c17
--- /dev/null
+++ b/nuttx/configs/vsn/src/README.txt
@@ -0,0 +1,12 @@
+
+The directory contains start-up and board level functions.
+Execution starts in the following order:
+
+ - sysclock, immediately after reset stm32_rcc calls external
+ clock configuration when
+ CONFIG_ARCH_BOARD_STM32_CUSTOM_CLOCKCONFIG=y
+ is set. It must be set for the VSN board.
+
+ - boot, performs initial chip and board initialization
+ - ...
+ - nsh, as central application last.
diff --git a/nuttx/configs/vsn/src/up_boot.c b/nuttx/configs/vsn/src/boot.c
index df05a10bf..2f959333d 100644
--- a/nuttx/configs/vsn/src/up_boot.c
+++ b/nuttx/configs/vsn/src/boot.c
@@ -1,6 +1,6 @@
/************************************************************************************
- * configs/vsn/src/up_boot.c
- * arch/arm/src/board/up_boot.c
+ * configs/vsn/src/boot.c
+ * arch/arm/src/board/boot.c
*
* Copyright (C) 2009 Gregory Nutt. All rights reserved.
* Copyright (c) 2011 Uros Platise. All rights reserved.
@@ -47,8 +47,9 @@
#include <arch/board/board.h>
+#include "stm32_gpio.h"
#include "up_arch.h"
-#include "vsn-internal.h"
+#include "vsn.h"
/************************************************************************************
* Definitions
@@ -74,15 +75,24 @@
void stm32_boardinitialize(void)
{
+#ifdef CONFIG_STM32_SPI3
+#warning JTAG Port Disabled as SPI3 NVRAM/FRAM support is enabled
+
+ uint32_t val = getreg32(STM32_AFIO_MAPR);
+ val &= 0x00FFFFFF; // clear undefined readings ...
+ val |= AFIO_MAPR_DISAB; // set JTAG-DP and SW-DP Disabled
+ putreg32(val, STM32_AFIO_MAPR);
+#endif
+
+ // Set Board Voltage to 3.3 V
+ board_power_setbootvoltage();
+
/* Configure SPI chip selects if 1) SPI is not disabled, and 2) the weak function
* stm32_spiinitialize() has been brought into the link.
*/
-#if defined(CONFIG_STM32_SPI1) || defined(CONFIG_STM32_SPI2)
- if (stm32_spiinitialize)
- {
- stm32_spiinitialize();
- }
+#if defined(CONFIG_STM32_SPI1) || defined(CONFIG_STM32_SPI2) || defined(CONFIG_STM32_SPI3)
+ if (stm32_spiinitialize) stm32_spiinitialize();
#endif
/* Initialize USB is 1) USBDEV is selected, 2) the USB controller is not
@@ -91,10 +101,7 @@ void stm32_boardinitialize(void)
*/
#if defined(CONFIG_USBDEV) && defined(CONFIG_STM32_USB)
- if (stm32_usbinitialize)
- {
- stm32_usbinitialize();
- }
+ if (stm32_usbinitialize) stm32_usbinitialize();
#endif
/* Configure on-board LEDs if LED support has been selected. */
diff --git a/nuttx/configs/vsn/src/up_buttons.c b/nuttx/configs/vsn/src/buttons.c
index 27284a8d0..3025b373c 100644
--- a/nuttx/configs/vsn/src/up_buttons.c
+++ b/nuttx/configs/vsn/src/buttons.c
@@ -1,5 +1,5 @@
/****************************************************************************
- * configs/vsn-1.2/src/up_buttons.c
+ * configs/vsn/src/buttons.c
*
* Copyright (C) 2009 Gregory Nutt. All rights reserved.
* Copyright (C) 2011 Uros Platise. All rights reserved.
@@ -43,7 +43,7 @@
#include <nuttx/config.h>
#include <stdint.h>
#include <arch/board/board.h>
-#include "vsn-internal.h"
+#include "vsn.h"
#ifdef CONFIG_ARCH_BUTTONS
diff --git a/nuttx/configs/vsn/src/up_leds.c b/nuttx/configs/vsn/src/leds.c
index a936aac2e..ef3c87144 100644
--- a/nuttx/configs/vsn/src/up_leds.c
+++ b/nuttx/configs/vsn/src/leds.c
@@ -1,6 +1,6 @@
/****************************************************************************
- * configs/vsn-1.2/src/up_leds.c
- * arch/arm/src/board/up_leds.c
+ * configs/vsn/src/leds.c
+ * arch/arm/src/board/leds.c
*
* Copyright (C) 2009 Gregory Nutt. All rights reserved.
* Copyright (C) 2011 Uros Platise. All rights reserved.
@@ -48,7 +48,7 @@
#include <debug.h>
#include <arch/board/board.h>
-#include "vsn-internal.h"
+#include "vsn.h"
/****************************************************************************
* Definitions
diff --git a/nuttx/configs/vsn/src/nsh.c b/nuttx/configs/vsn/src/nsh.c
new file mode 100644
index 000000000..96f9f3d4d
--- /dev/null
+++ b/nuttx/configs/vsn/src/nsh.c
@@ -0,0 +1,89 @@
+/****************************************************************************
+ * config/vsn/src/nsh.c
+ * arch/arm/src/board/nsh.c
+ *
+ * Copyright (C) 2011 Uros Platise. All rights reserved.
+ * Copyright (C) 2009 Gregory Nutt. All rights reserved.
+ *
+ * Authors: Uros Platise <uros.platise@isotel.eu>
+ * 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 <stdbool.h>
+#include <stdio.h>
+#include <debug.h>
+#include <errno.h>
+
+#include "vsn.h"
+
+/****************************************************************************
+ * Pre-Processor Definitions
+ ****************************************************************************/
+
+/* Configuration ************************************************************/
+
+/* PORT and SLOT number probably depend on the board configuration */
+
+#define CONFIG_EXAMPLES_NSH_HAVEUSBDEV 1
+
+/* Can't support USB features if USB is not enabled */
+
+#ifndef CONFIG_USBDEV
+# undef CONFIG_EXAMPLES_NSH_HAVEUSBDEV
+#endif
+
+
+
+/****************************************************************************
+ * Public Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Name: nsh_archinitialize
+ *
+ * Description:
+ * Perform architecture specific initialization
+ *
+ ****************************************************************************/
+
+int nsh_archinitialize(void)
+{
+ up_ramtron();
+ up_sdcard();
+
+ return OK;
+}
diff --git a/nuttx/configs/vsn/src/power.c b/nuttx/configs/vsn/src/power.c
new file mode 100644
index 000000000..2e23ed033
--- /dev/null
+++ b/nuttx/configs/vsn/src/power.c
@@ -0,0 +1,57 @@
+/****************************************************************************
+ * config/vsn/src/ramtron.c
+ * arch/arm/src/board/ramtron.c
+ *
+ * Copyright (C) 2011 Uros Platise. All rights reserved.
+ *
+ * Authors: Uros Platise <uros.platise@isotel.eu>
+ *
+ * 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.
+ *
+ ****************************************************************************/
+
+#include <nuttx/config.h>
+
+#include <stdint.h>
+#include <stdbool.h>
+#include <debug.h>
+
+#include <arch/board/board.h>
+#include "vsn.h"
+
+void board_power_register(void);
+void board_power_adjust(void);
+void board_power_status(void);
+
+void board_power_setbootvoltage(void)
+{
+ stm32_configgpio(GPIO_PVS);
+}
+
+void board_power_reboot(void);
+void board_power_off(void);
diff --git a/nuttx/configs/vsn/src/ramtron.c b/nuttx/configs/vsn/src/ramtron.c
new file mode 100644
index 000000000..545289f7c
--- /dev/null
+++ b/nuttx/configs/vsn/src/ramtron.c
@@ -0,0 +1,87 @@
+/****************************************************************************
+ * config/vsn/src/ramtron.c
+ * arch/arm/src/board/ramtron.c
+ *
+ * Copyright (C) 2011 Uros Platise. All rights reserved.
+ * Copyright (C) 2009 Gregory Nutt. All rights reserved.
+ *
+ * Authors: Uros Platise <uros.platise@isotel.eu>
+ * 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.
+ *
+ ****************************************************************************/
+
+#include <nuttx/config.h>
+
+#include <stdbool.h>
+#include <stdio.h>
+#include <debug.h>
+#include <errno.h>
+
+#ifdef CONFIG_STM32_SPI3
+# include <nuttx/spi.h>
+# include <nuttx/mtd.h>
+#endif
+
+#include "vsn.h"
+
+
+
+int up_ramtron(void)
+{
+#ifdef CONFIG_STM32_SPI3
+ FAR struct spi_dev_s *spi;
+ FAR struct mtd_dev_s *mtd;
+ int retval;
+
+ /* Get the SPI port */
+
+ message("nsh_archinitialize: Initializing SPI port 3\n");
+ spi = up_spiinitialize(3);
+ if (!spi)
+ {
+ message("nsh_archinitialize: Failed to initialize SPI port 3\n");
+ return -ENODEV;
+ }
+ message("nsh_archinitialize: Successfully initialized SPI port 3\n");
+
+ message("nsh_archinitialize: Bind SPI to the SPI flash driver\n");
+ mtd = ramtron_initialize(spi);
+ if (!mtd)
+ {
+ message("nsh_archinitialize: Failed to bind SPI port 0 to the SPI FLASH driver\n");
+ return -ENODEV;
+ }
+ message("nsh_archinitialize: Successfully bound SPI port 0 to the SPI FLASH driver\n");
+
+ retval = ftl_initialize(0,NULL, mtd);
+ message("FTL returned with %d\n", retval);
+#endif
+ return OK;
+}
diff --git a/nuttx/configs/vsn/src/sdcard.c b/nuttx/configs/vsn/src/sdcard.c
new file mode 100644
index 000000000..3b20913df
--- /dev/null
+++ b/nuttx/configs/vsn/src/sdcard.c
@@ -0,0 +1,120 @@
+/****************************************************************************
+ * config/vsn/src/sdcard.c
+ * arch/arm/src/board/sdcard.c
+ *
+ * Copyright (C) 2011 Uros Platise. All rights reserved.
+ * Copyright (C) 2009 Gregory Nutt. All rights reserved.
+ *
+ * Authors: Uros Platise <uros.platise@isotel.eu>
+ * 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.
+ *
+ ****************************************************************************/
+
+#include <nuttx/config.h>
+
+#include <stdbool.h>
+#include <stdio.h>
+#include <debug.h>
+#include <errno.h>
+
+#ifdef CONFIG_STM32_SDIO
+# include <nuttx/sdio.h>
+# include <nuttx/mmcsd.h>
+#endif
+
+#include "vsn.h"
+
+
+#define CONFIG_EXAMPLES_NSH_HAVEMMCSD 1
+#if defined(CONFIG_EXAMPLES_NSH_MMCSDSLOTNO) && CONFIG_EXAMPLES_NSH_MMCSDSLOTNO != 0
+# error "Only one MMC/SD slot"
+# undef CONFIG_EXAMPLES_NSH_MMCSDSLOTNO
+#endif
+#ifndef CONFIG_EXAMPLES_NSH_MMCSDSLOTNO
+# define CONFIG_EXAMPLES_NSH_MMCSDSLOTNO 0
+#endif
+
+/* Can't support MMC/SD features if mountpoints are disabled or if SDIO support
+ * is not enabled.
+ */
+
+#if defined(CONFIG_DISABLE_MOUNTPOINT) || !defined(CONFIG_STM32_SDIO)
+# undef CONFIG_EXAMPLES_NSH_HAVEMMCSD
+#endif
+
+#ifndef CONFIG_EXAMPLES_NSH_MMCSDMINOR
+# define CONFIG_EXAMPLES_NSH_MMCSDMINOR 0
+#endif
+
+
+
+int up_sdcard(void)
+{
+ /* Mount the SDIO-based MMC/SD block driver */
+
+#ifdef CONFIG_EXAMPLES_NSH_HAVEMMCSD
+
+ FAR struct sdio_dev_s *sdio;
+ int ret;
+
+ /* First, get an instance of the SDIO interface */
+
+ message("nsh_archinitialize: Initializing SDIO slot %d\n",
+ CONFIG_EXAMPLES_NSH_MMCSDSLOTNO);
+ sdio = sdio_initialize(CONFIG_EXAMPLES_NSH_MMCSDSLOTNO);
+ if (!sdio)
+ {
+ message("nsh_archinitialize: Failed to initialize SDIO slot %d\n",
+ CONFIG_EXAMPLES_NSH_MMCSDSLOTNO);
+ return -ENODEV;
+ }
+
+ /* Now bind the SPI interface to the MMC/SD driver */
+
+ message("nsh_archinitialize: Bind SDIO to the MMC/SD driver, minor=%d\n",
+ CONFIG_EXAMPLES_NSH_MMCSDMINOR);
+ ret = mmcsd_slotinitialize(CONFIG_EXAMPLES_NSH_MMCSDMINOR, sdio);
+ if (ret != OK)
+ {
+ message("nsh_archinitialize: Failed to bind SDIO to the MMC/SD driver: %d\n", ret);
+ return ret;
+ }
+ message("nsh_archinitialize: Successfully bound SDIO to the MMC/SD driver\n");
+
+ /* Then let's guess and say that there is a card in the slot. I need to check to
+ * see if the VSN board supports a GPIO to detect if there is a card in
+ * the slot.
+ */
+ sdio_mediachange(sdio, true);
+
+#endif
+ return OK;
+}
+
diff --git a/nuttx/configs/vsn/src/up_spi.c b/nuttx/configs/vsn/src/spi.c
index bfc5f8682..742fcfd41 100644
--- a/nuttx/configs/vsn/src/up_spi.c
+++ b/nuttx/configs/vsn/src/spi.c
@@ -1,6 +1,6 @@
/************************************************************************************
- * configs/vsn/src/up_spi.c
- * arch/arm/src/board/up_spi.c
+ * configs/vsn/src/spi.c
+ * arch/arm/src/board/spi.c
*
* Copyright (C) 2009 Gregory Nutt. All rights reserved.
* Copyright (C) 2011 Uros Platise. All rights reserved.
@@ -42,20 +42,20 @@
************************************************************************************/
#include <nuttx/config.h>
+#include <nuttx/spi.h>
+#include <arch/board/board.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_gpio.h"
#include "stm32_internal.h"
-#include "vsn-internal.h"
+#include "vsn.h"
-#if defined(CONFIG_STM32_SPI1) || defined(CONFIG_STM32_SPI2)
+#if defined(CONFIG_STM32_SPI1) || defined(CONFIG_STM32_SPI2) || defined(CONFIG_STM32_SPI3)
/************************************************************************************
* Definitions
@@ -97,16 +97,15 @@
void weak_function stm32_spiinitialize(void)
{
- /* NOTE: Clocking for SPI1 and/or SPI2 was already provided in stm32_rcc.c.
+ /* NOTE: Clocking for SPI1 and/or SPI2 and SPI3 was already provided in stm32_rcc.c.
* Configurations of SPI pins is performed in stm32_spi.c.
- * Here, we only initialize chip select pins unique to the board
- * architecture.
+ * Here, we only initialize chip select pins unique to the board architecture.
*/
-#ifdef CONFIG_STM32_SPI1
- /* Configure the SPI-based FLASH CS GPIO */
+#ifdef CONFIG_STM32_SPI3
- stm32_configgpio(GPIO_FLASH_CS);
+ // Configure the SPI-based FRAM CS GPIO
+ stm32_configgpio(GPIO_FRAM_CS);
#endif
}
@@ -139,13 +138,6 @@ void weak_function stm32_spiinitialize(void)
void stm32_spi1select(FAR struct spi_dev_s *dev, enum spi_dev_e devid, bool selected)
{
spidbg("devid: %d CS: %s\n", (int)devid, selected ? "assert" : "de-assert");
-
- if (devid == SPIDEV_FLASH)
- {
- /* Set the GPIO low to select and high to de-select */
-
- stm32_gpiowrite(GPIO_FLASH_CS, !selected);
- }
}
uint8_t stm32_spi1status(FAR struct spi_dev_s *dev, enum spi_dev_e devid)
@@ -170,6 +162,11 @@ uint8_t stm32_spi2status(FAR struct spi_dev_s *dev, enum spi_dev_e devid)
void stm32_spi3select(FAR struct spi_dev_s *dev, enum spi_dev_e devid, bool selected)
{
spidbg("devid: %d CS: %s\n", (int)devid, selected ? "assert" : "de-assert");
+ if (devid == SPIDEV_FLASH)
+ {
+ /* Set the GPIO low to select and high to de-select */
+ stm32_gpiowrite(GPIO_FRAM_CS, !selected);
+ }
}
uint8_t stm32_spi3status(FAR struct spi_dev_s *dev, enum spi_dev_e devid)
diff --git a/nuttx/configs/vsn/src/up_sysclock.c b/nuttx/configs/vsn/src/sysclock.c
index c93b251c1..f812dd2c1 100644
--- a/nuttx/configs/vsn/src/up_sysclock.c
+++ b/nuttx/configs/vsn/src/sysclock.c
@@ -1,5 +1,5 @@
/****************************************************************************
- * configs/vsn-1.2/src/up_sysclock.c
+ * configs/vsn/src/sysclock.c
*
* Copyright (C) 2011 Uros Platise. All rights reserved.
*
diff --git a/nuttx/configs/vsn/src/up_nsh.c b/nuttx/configs/vsn/src/up_nsh.c
deleted file mode 100644
index 323e91a44..000000000
--- a/nuttx/configs/vsn/src/up_nsh.c
+++ /dev/null
@@ -1,215 +0,0 @@
-/****************************************************************************
- * config/vsn/src/up_nsh.c
- * arch/arm/src/board/up_nsh.c
- *
- * Copyright (C) 2009 Gregory Nutt. All rights reserved.
- * Copyright (C) 2011 Uros Platise. All rights reserved.
- *
- * Authors: Gregory Nutt <spudmonkey@racsa.co.cr>
- * Uros Platise <uros.platise@isotel.eu>
- *
- * 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 <stdbool.h>
-#include <stdio.h>
-#include <debug.h>
-#include <errno.h>
-
-#ifdef CONFIG_STM32_SPI1
-# include <nuttx/spi.h>
-# include <nuttx/mtd.h>
-#endif
-
-#ifdef CONFIG_STM32_SDIO
-# include <nuttx/sdio.h>
-# include <nuttx/mmcsd.h>
-#endif
-
-#include "vsn-internal.h"
-
-/****************************************************************************
- * Pre-Processor Definitions
- ****************************************************************************/
-
-/* Configuration ************************************************************/
-
-/* For now, don't build in any SPI1 support -- NSH is not using it */
-
-#undef CONFIG_STM32_SPI1
-
-/* PORT and SLOT number probably depend on the board configuration */
-
-#ifdef CONFIG_ARCH_BOARD_VSN
-# define CONFIG_EXAMPLES_NSH_HAVEUSBDEV 1
-# define CONFIG_EXAMPLES_NSH_HAVEMMCSD 1
-# if defined(CONFIG_EXAMPLES_NSH_MMCSDSLOTNO) && CONFIG_EXAMPLES_NSH_MMCSDSLOTNO != 0
-# error "Only one MMC/SD slot"
-# undef CONFIG_EXAMPLES_NSH_MMCSDSLOTNO
-# endif
-# ifndef CONFIG_EXAMPLES_NSH_MMCSDSLOTNO
-# define CONFIG_EXAMPLES_NSH_MMCSDSLOTNO 0
-# endif
-#else
- /* Add configuration for new STM32 boards here */
-# undef CONFIG_EXAMPLES_NSH_HAVEUSBDEV
-# undef CONFIG_EXAMPLES_NSH_HAVEMMCSD
-#endif
-
-/* Can't support USB features if USB is not enabled */
-
-#ifndef CONFIG_USBDEV
-# undef CONFIG_EXAMPLES_NSH_HAVEUSBDEV
-#endif
-
-/* Can't support MMC/SD features if mountpoints are disabled or if SDIO support
- * is not enabled.
- */
-
-#if defined(CONFIG_DISABLE_MOUNTPOINT) || !defined(CONFIG_STM32_SDIO)
-# undef CONFIG_EXAMPLES_NSH_HAVEMMCSD
-#endif
-
-#ifndef CONFIG_EXAMPLES_NSH_MMCSDMINOR
-# define CONFIG_EXAMPLES_NSH_MMCSDMINOR 0
-#endif
-
-/* Debug ********************************************************************/
-
-#ifdef CONFIG_CPP_HAVE_VARARGS
-# ifdef CONFIG_DEBUG
-# define message(...) lib_lowprintf(__VA_ARGS__)
-# else
-# define message(...) printf(__VA_ARGS__)
-# endif
-#else
-# ifdef CONFIG_DEBUG
-# define message lib_lowprintf
-# else
-# define message printf
-# endif
-#endif
-
-/****************************************************************************
- * Public Functions
- ****************************************************************************/
-
-/****************************************************************************
- * Name: nsh_archinitialize
- *
- * Description:
- * Perform architecture specific initialization
- *
- ****************************************************************************/
-
-int nsh_archinitialize(void)
-{
-#ifdef CONFIG_STM32_SPI1
- FAR struct spi_dev_s *spi;
- FAR struct mtd_dev_s *mtd;
-#endif
-#ifdef CONFIG_EXAMPLES_NSH_HAVEMMCSD
- FAR struct sdio_dev_s *sdio;
- int ret;
-#endif
-
- /* Configure SPI-based devices */
-
-#ifdef CONFIG_STM32_SPI1
- /* Get the SPI port */
-
- message("nsh_archinitialize: Initializing SPI port 0\n");
- spi = up_spiinitialize(0);
- if (!spi)
- {
- message("nsh_archinitialize: Failed to initialize SPI port 0\n");
- return -ENODEV;
- }
- message("nsh_archinitialize: Successfully initialized SPI port 0\n");
-
- /* Now bind the SPI interface to the M25P64/128 SPI FLASH driver */
-
- message("nsh_archinitialize: Bind SPI to the SPI flash driver\n");
- mtd = m25p_initialize(spi);
- if (!mtd)
- {
- message("nsh_archinitialize: Failed to bind SPI port 0 to the SPI FLASH driver\n");
- return -ENODEV;
- }
- message("nsh_archinitialize: Successfully bound SPI port 0 to the SPI FLASH driver\n");
-#warning "Now what are we going to do with this SPI FLASH driver?"
-#endif
-
- /* Create the SPI FLASH MTD instance */
- /* The M25Pxx is not a give media to implement a file system..
- * its block sizes are too large
- */
-
- /* Mount the SDIO-based MMC/SD block driver */
-
-#ifdef CONFIG_EXAMPLES_NSH_HAVEMMCSD
- /* First, get an instance of the SDIO interface */
-
- message("nsh_archinitialize: Initializing SDIO slot %d\n",
- CONFIG_EXAMPLES_NSH_MMCSDSLOTNO);
- sdio = sdio_initialize(CONFIG_EXAMPLES_NSH_MMCSDSLOTNO);
- if (!sdio)
- {
- message("nsh_archinitialize: Failed to initialize SDIO slot %d\n",
- CONFIG_EXAMPLES_NSH_MMCSDSLOTNO);
- return -ENODEV;
- }
-
- /* Now bind the SPI interface to the MMC/SD driver */
-
- message("nsh_archinitialize: Bind SDIO to the MMC/SD driver, minor=%d\n",
- CONFIG_EXAMPLES_NSH_MMCSDMINOR);
- ret = mmcsd_slotinitialize(CONFIG_EXAMPLES_NSH_MMCSDMINOR, sdio);
- if (ret != OK)
- {
- message("nsh_archinitialize: Failed to bind SDIO to the MMC/SD driver: %d\n", ret);
- return ret;
- }
- message("nsh_archinitialize: Successfully bound SDIO to the MMC/SD driver\n");
-
- /* Then let's guess and say that there is a card in the slot. I need to check to
- * see if the VSN board supports a GPIO to detect if there is a card in
- * the slot.
- */
-
- sdio_mediachange(sdio, true);
-#endif
- return OK;
-}
diff --git a/nuttx/configs/vsn/src/up_usbdev.c b/nuttx/configs/vsn/src/usbdev.c
index a30a8f8a1..db7fd1d9a 100644
--- a/nuttx/configs/vsn/src/up_usbdev.c
+++ b/nuttx/configs/vsn/src/usbdev.c
@@ -1,6 +1,6 @@
/************************************************************************************
- * configs/svsn/src/up_usbdev.c
- * arch/arm/src/board/up_boot.c
+ * configs/svsn/src/usbdev.c
+ * arch/arm/src/board/boot.c
*
* Copyright (C) 2009-2010 Gregory Nutt. All rights reserved.
* Copyright (c) 2011 Uros Platise. All rights reserved.
@@ -53,7 +53,7 @@
#include "up_arch.h"
#include "stm32_internal.h"
-#include "vsn-internal.h"
+#include "vsn.h"
/************************************************************************************
* Definitions
diff --git a/nuttx/configs/vsn/src/up_usbstrg.c b/nuttx/configs/vsn/src/usbstrg.c
index 2a34bab40..0942ae8e5 100644
--- a/nuttx/configs/vsn/src/up_usbstrg.c
+++ b/nuttx/configs/vsn/src/usbstrg.c
@@ -1,5 +1,5 @@
/****************************************************************************
- * configs/vsn/src/up_usbstrg.c
+ * configs/vsn/src/usbstrg.c
*
* Copyright (C) 2009 Gregory Nutt. All rights reserved.
* Copyright (c) 2011 Uros Platise. All rights reserved.
@@ -51,7 +51,7 @@
#include <nuttx/sdio.h>
#include <nuttx/mmcsd.h>
-#include "vsn-internal.h"
+#include "vsn.h"
#ifdef CONFIG_STM32_SDIO
diff --git a/nuttx/configs/vsn/src/vsn-internal.h b/nuttx/configs/vsn/src/vsn.h
index 832dff146..c065e1e75 100644
--- a/nuttx/configs/vsn/src/vsn-internal.h
+++ b/nuttx/configs/vsn/src/vsn.h
@@ -1,6 +1,6 @@
/************************************************************************************
- * configs/vsn/src/vsn-internal.h
- * arch/arm/src/board/vsn-internal.n
+ * configs/vsn/src/vsn.h
+ * arch/arm/src/board/vsn.n
*
* Copyright (C) 2009 Gregory Nutt. All rights reserved.
* Copyright (c) 2011 Uros Platise. All rights reserved.
@@ -44,6 +44,7 @@
* Included Files
************************************************************************************/
+#include <arch/board/board.h>
#include <nuttx/config.h>
#include <nuttx/compiler.h>
#include <stdint.h>
@@ -52,20 +53,6 @@
* Definitions
************************************************************************************/
-/* How many SPI modules does this chip support? The LM3S6918 supports 2 SPI
- * modules (others may support more -- in such case, the following must be
- * expanded).
- */
-
-#if STM32_NSPI < 1
-# undef CONFIG_STM32_SPI1
-# undef CONFIG_STM32_SPI2
-#elif STM32_NSPI < 2
-# undef CONFIG_STM32_SPI2
-#endif
-
-/* VSN 1.2 GPIOs **************************************************************/
-
/* LED */
#define GPIO_LED (GPIO_OUTPUT|GPIO_CNF_OUTPP|GPIO_MODE_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTB|GPIO_PIN2)
@@ -74,6 +61,32 @@
#define GPIO_PUSHBUTTON (GPIO_INPUT|GPIO_CNF_INFLOAT|GPIO_MODE_INPUT|GPIO_PORTC|GPIO_PIN5)
+/* Power Management Pins */
+
+#define GPIO_PVS (GPIO_OUTPUT|GPIO_CNF_OUTPP|GPIO_MODE_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTC|GPIO_PIN7)
+
+/* FRAM */
+
+#define GPIO_FRAM_CS (GPIO_OUTPUT|GPIO_CNF_OUTPP|GPIO_MODE_50MHz|GPIO_OUTPUT_SET|GPIO_PORTA|GPIO_PIN15)
+
+
+/* Debug ********************************************************************/
+
+#ifdef CONFIG_CPP_HAVE_VARARGS
+# ifdef CONFIG_DEBUG
+# define message(...) lib_lowprintf(__VA_ARGS__)
+# else
+# define message(...) printf(__VA_ARGS__)
+# endif
+#else
+# ifdef CONFIG_DEBUG
+# define message lib_lowprintf
+# else
+# define message printf
+# endif
+#endif
+
+
/************************************************************************************
* Public Types
************************************************************************************/
@@ -108,14 +121,18 @@ extern void weak_function stm32_spiinitialize(void);
extern void weak_function stm32_usbinitialize(void);
+
/************************************************************************************
- * Name: stm32_extcontextsave
+ * Power Module
*
* Description:
- * Save current GPIOs that will used by external memory configurations
- *
+ * - Provides power related board operations, such as voltage selection,
+ * proper reboot sequence, and power-off
************************************************************************************/
+extern void board_power_setbootvoltage(void); // Default voltage at boot time
+
+
#endif /* __ASSEMBLY__ */
#endif /* __CONFIGS_VSN_1_2_SRC_VSN_INTERNAL_H */