summaryrefslogtreecommitdiff
path: root/nuttx/configs
diff options
context:
space:
mode:
authorpatacongo <patacongo@42af7a65-404d-4744-a932-0658087f49c3>2011-03-14 14:14:54 +0000
committerpatacongo <patacongo@42af7a65-404d-4744-a932-0658087f49c3>2011-03-14 14:14:54 +0000
commitee2220174467b0e456446f5faaef1bd1660f786e (patch)
tree61937f54d7558e15f984b0450c2958e9ed45b5bd /nuttx/configs
parent38121cceb67b2408c5aab1d3e9998accef0d83c8 (diff)
downloadpx4-nuttx-ee2220174467b0e456446f5faaef1bd1660f786e.tar.gz
px4-nuttx-ee2220174467b0e456446f5faaef1bd1660f786e.tar.bz2
px4-nuttx-ee2220174467b0e456446f5faaef1bd1660f786e.zip
VSN/apps update
git-svn-id: svn://svn.code.sf.net/p/nuttx/code/trunk@3378 42af7a65-404d-4744-a932-0658087f49c3
Diffstat (limited to 'nuttx/configs')
-rw-r--r--nuttx/configs/vsn/include/board.h33
-rw-r--r--nuttx/configs/vsn/include/power.h71
-rwxr-xr-xnuttx/configs/vsn/nsh/defconfig45
-rw-r--r--nuttx/configs/vsn/src/README.txt10
-rw-r--r--nuttx/configs/vsn/src/boot.c216
-rw-r--r--nuttx/configs/vsn/src/leds.c18
-rw-r--r--nuttx/configs/vsn/src/power.c48
-rw-r--r--nuttx/configs/vsn/src/ramtron.c7
-rw-r--r--nuttx/configs/vsn/src/sysclock.c13
-rw-r--r--nuttx/configs/vsn/src/vsn.h276
10 files changed, 450 insertions, 287 deletions
diff --git a/nuttx/configs/vsn/include/board.h b/nuttx/configs/vsn/include/board.h
index f4ad540c7..5c07f075e 100644
--- a/nuttx/configs/vsn/include/board.h
+++ b/nuttx/configs/vsn/include/board.h
@@ -1,5 +1,5 @@
/************************************************************************************
- * configs/vsn-1.2/include/board.h
+ * configs/vsn/include/board.h
* include/arch/board/board.h
*
* Copyright (C) 2009 Gregory Nutt. All rights reserved.
@@ -183,10 +183,11 @@ extern "C" {
#endif
/************************************************************************************
- * Public Function Prototypes
+ * Board Clock Configuration, called immediatelly after boot
************************************************************************************/
- EXTERN void stm32_board_clockconfig(void);
+EXTERN void stm32_board_clockconfig(void);
+
/************************************************************************************
* Name: stm32_boardinitialize
@@ -200,15 +201,9 @@ extern "C" {
EXTERN void stm32_boardinitialize(void);
+
/************************************************************************************
- * Button support.
- *
- * Description:
- * up_buttoninit() must be called to initialize button resources. After that,
- * up_buttons() may be called to collect the state of all buttons. up_buttons()
- * returns an 8-bit bit set with each bit associated with a button. See the
- * BUTTON_* and JOYSTICK_* definitions above for the meaning of each bit.
- *
+ * Button support. (TODO: button is not yet supported)
************************************************************************************/
#ifdef CONFIG_ARCH_BUTTONS
@@ -216,11 +211,25 @@ EXTERN void up_buttoninit(void);
EXTERN uint8_t up_buttons(void);
#endif
-/* Other peripherals startup routines, all returning OK on success */
+
+/************************************************************************************
+ * Memories
+ * - SDcard is tested to work up to 2 GB
+ * - RAMTRON has size of 128 kB
+ ************************************************************************************/
+
EXTERN int up_sdcard(void);
EXTERN int up_ramtron(void);
+/************************************************************************************
+ * Public Power Supply Contol
+ ************************************************************************************/
+
+void board_power_reboot(void);
+void board_power_off(void);
+
+
#undef EXTERN
#if defined(__cplusplus)
}
diff --git a/nuttx/configs/vsn/include/power.h b/nuttx/configs/vsn/include/power.h
new file mode 100644
index 000000000..960c40fb1
--- /dev/null
+++ b/nuttx/configs/vsn/include/power.h
@@ -0,0 +1,71 @@
+/************************************************************************************
+ * configs/vsn/include/power.h
+ * include/arch/board/power.h
+ *
+ * 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.
+ *
+ ************************************************************************************/
+
+#ifndef __ARCH_BOARD_POWER_H
+#define __ARCH_BOARD_POWER_H
+
+
+/************************************************************************************
+ * Included Files
+ ************************************************************************************/
+
+#ifndef __ASSEMBLY__
+#undef EXTERN
+#if defined(__cplusplus)
+#define EXTERN extern "C"
+extern "C" {
+#else
+#define EXTERN extern
+#endif
+
+/************************************************************************************
+ * Public Power Supply Contol
+ ************************************************************************************/
+
+void board_power_reboot(void);
+
+/* If this function returns, it means, that it was not possible to power-off the board */
+void board_power_off(void);
+
+
+#undef EXTERN
+#if defined(__cplusplus)
+}
+#endif
+
+#endif /* __ASSEMBLY__ */
+#endif /* __ARCH_BOARD_POWER_H */
diff --git a/nuttx/configs/vsn/nsh/defconfig b/nuttx/configs/vsn/nsh/defconfig
index e6503f376..0f9496997 100755
--- a/nuttx/configs/vsn/nsh/defconfig
+++ b/nuttx/configs/vsn/nsh/defconfig
@@ -819,34 +819,49 @@ CONFIG_HEAP_SIZE=
########################################################################
+# STM32 JTAG Options
+#
+# Full JTAG Enable (Parallel and Serial)
+CONFIG_STM32_JTAG_FULL_ENABLE=n
+
+# Full but without the JNTRST pin
+CONFIG_STM32_JTAG_NOJNTRST_ENABLE=n
+
+# Serial (SWJ) dual pin only which, can coexist besides the FRAM on SPI3
+CONFIG_STM32_JTAG_SW_ENABLE=n
+
+
+########################################################################
#
# Applications to be included within the NuttX binary as described
-# under the apps/README.txt
+# under the ../apps/README.txt
#
-# Set this config parameter above to: CONFIG_TASK_NAME_SIZE=16
-# in order to enable argv[0]=<task name> argument. Otherwise argv[0]
-# will be noname.
+# Set thi config parameter above to: CONFIG_TASK_NAME_SIZE=16
+# In order to enable argv[0]=<task name> argument set the option
+# CONFIG_TASK_NAME_SIZE=16
#
-# Include builtin NuttX application (disabling this option will
-# exclude all of the apps found under the nuttx/apps directory, but
-# not the apps found under the ../apps directory unless _APPS_USER=n.
+# Include builtin NuttX applications (general option)
CONFIG_BUILTIN_APPS_NUTTX=y
+# Invoke the following application after NuttX starts
+#CONFIG_BUILTIN_APP_START="hello"
+
# Individual selection of built-in applications:
+
+# Hello world provide a simple skeleton/demo application
CONFIG_BUILTIN_APPS_HELLO=y
-# Include user (external) applications located under ../apps directory?
-CONFIG_BUILTIN_APPS_USER=y
+# Provide poweroff command to switch off the board
+CONFIG_BUILTIN_APPS_POWEROFF=y
-# Invoke the following application after NuttX starts
-# (enter app name, as: hello)
-CONFIG_BUILTIN_APP_START=
+# Provide JAVA Virtual Machine (the Darjeeling JVM)
+CONFIG_BUILTIN_APPS_JVM=n
-# CONFIG_EXAMPLES_NSH_BUILTIN_APPS - Support for running the builtin
-# apps from command line. See apps/README for more information.
+# CONFIG_EXAMPLES_NSH_BUILTIN_APPS - Enable invocation of all builtin
+# apps from nsh command line. See apps/README for more information.
#
CONFIG_EXAMPLES_NSH_BUILTIN_APPS=y
-CONFIG_SCHED_WAITPID=y
+ CONFIG_SCHED_WAITPID=y
#
########################################################################
diff --git a/nuttx/configs/vsn/src/README.txt b/nuttx/configs/vsn/src/README.txt
index bacf82c17..f08e8fe06 100644
--- a/nuttx/configs/vsn/src/README.txt
+++ b/nuttx/configs/vsn/src/README.txt
@@ -10,3 +10,13 @@ Execution starts in the following order:
- boot, performs initial chip and board initialization
- ...
- nsh, as central application last.
+
+
+
+
+JTAG options:
+=============
+
+CONFIG_STM32_JTAG_FULL_ENABLE // Complete parallel and serial
+CONFIG_STM32_JTAG_NOJNTRST_ENABLE // no JNTRST pin
+CONFIG_STM32_JTAG_SW_ENABLE // serial (dual pin) only (can coexist besides the FRAM on SPI3)
diff --git a/nuttx/configs/vsn/src/boot.c b/nuttx/configs/vsn/src/boot.c
index 2f959333d..eb4ba9ef5 100644
--- a/nuttx/configs/vsn/src/boot.c
+++ b/nuttx/configs/vsn/src/boot.c
@@ -1,112 +1,104 @@
-/************************************************************************************
- * 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.
- *
- * 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 <debug.h>
-
-#include <arch/board/board.h>
-
-#include "stm32_gpio.h"
-#include "up_arch.h"
-#include "vsn.h"
-
-/************************************************************************************
- * Definitions
- ************************************************************************************/
-
-/************************************************************************************
- * Private Functions
- ************************************************************************************/
-
-/************************************************************************************
- * Public Functions
- ************************************************************************************/
-
-/************************************************************************************
- * Name: stm32_boardinitialize
- *
- * Description:
- * All STM32 architectures must provide the following entry point. This entry point
- * is called early in the intitialization -- after all memory has been configured
- * and mapped but before any devices have been initialized.
- *
- ************************************************************************************/
-
-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) || defined(CONFIG_STM32_SPI3)
- if (stm32_spiinitialize) stm32_spiinitialize();
-#endif
-
- /* Initialize USB is 1) USBDEV is selected, 2) the USB controller is not
- * disabled, and 3) the weak function stm32_usbinitialize() has been brought
- * into the build.
- */
-
-#if defined(CONFIG_USBDEV) && defined(CONFIG_STM32_USB)
- if (stm32_usbinitialize) stm32_usbinitialize();
-#endif
-
- /* Configure on-board LEDs if LED support has been selected. */
-
-#ifdef CONFIG_ARCH_LEDS
- up_ledinit();
-#endif
-}
+/************************************************************************************
+ * 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.
+ *
+ * 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 <debug.h>
+
+#include <arch/board/board.h>
+
+#include "stm32_gpio.h"
+#include "up_arch.h"
+#include "vsn.h"
+
+/************************************************************************************
+ * Definitions
+ ************************************************************************************/
+
+/************************************************************************************
+ * Private Functions
+ ************************************************************************************/
+
+/************************************************************************************
+ * Public Functions
+ ************************************************************************************/
+
+/************************************************************************************
+ * Name: stm32_boardinitialize
+ *
+ * Description:
+ * All STM32 architectures must provide the following entry point. This entry point
+ * is called early in the intitialization -- after all memory has been configured
+ * and mapped but before any devices have been initialized.
+ *
+ ************************************************************************************/
+
+void stm32_boardinitialize(void)
+{
+ /* Set start-up board voltage */
+
+ board_power_init();
+
+ /* 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) || defined(CONFIG_STM32_SPI3)
+ if (stm32_spiinitialize) stm32_spiinitialize();
+#endif
+
+ /* Initialize USB is 1) USBDEV is selected, 2) the USB controller is not
+ * disabled, and 3) the weak function stm32_usbinitialize() has been brought
+ * into the build.
+ */
+
+#if defined(CONFIG_USBDEV) && defined(CONFIG_STM32_USB)
+ if (stm32_usbinitialize) stm32_usbinitialize();
+#endif
+
+ /* Configure on-board LEDs if LED support has been selected. */
+
+#ifdef CONFIG_ARCH_LEDS
+ up_ledinit();
+#endif
+}
diff --git a/nuttx/configs/vsn/src/leds.c b/nuttx/configs/vsn/src/leds.c
index ef3c87144..c1cc1c573 100644
--- a/nuttx/configs/vsn/src/leds.c
+++ b/nuttx/configs/vsn/src/leds.c
@@ -43,13 +43,17 @@
#include <nuttx/config.h>
+#include <arch/board/board.h>
+#include <arch/stm32/irq.h>
+
#include <stdint.h>
#include <stdbool.h>
#include <debug.h>
-#include <arch/board/board.h>
+#include "up_arch.h"
#include "vsn.h"
+
/****************************************************************************
* Definitions
****************************************************************************/
@@ -72,6 +76,8 @@
/****************************************************************************
* Private Data
****************************************************************************/
+
+irqstate_t irqidle_mask;
/****************************************************************************
* Private Functions
@@ -101,7 +107,10 @@ void up_ledinit(void)
void up_ledon(int led)
{
- if (led==LED_IDLE) stm32_gpiowrite(GPIO_LED, true);
+ if (led==LED_IDLE) {
+ irqidle_mask = irqsave();
+ stm32_gpiowrite(GPIO_LED, true);
+ }
}
/****************************************************************************
@@ -110,7 +119,10 @@ void up_ledon(int led)
void up_ledoff(int led)
{
- if (led==LED_IDLE) stm32_gpiowrite(GPIO_LED, false);
+ if (led==LED_IDLE) {
+ stm32_gpiowrite(GPIO_LED, false);
+ irqrestore(irqidle_mask);
+ }
}
#endif /* CONFIG_ARCH_LEDS */
diff --git a/nuttx/configs/vsn/src/power.c b/nuttx/configs/vsn/src/power.c
index 2e23ed033..c7c73448a 100644
--- a/nuttx/configs/vsn/src/power.c
+++ b/nuttx/configs/vsn/src/power.c
@@ -1,6 +1,6 @@
/****************************************************************************
- * config/vsn/src/ramtron.c
- * arch/arm/src/board/ramtron.c
+ * config/vsn/src/power.c
+ * arch/arm/src/board/power.c
*
* Copyright (C) 2011 Uros Platise. All rights reserved.
*
@@ -37,21 +37,57 @@
#include <nuttx/config.h>
+#include <arch/board/board.h>
+#include <arch/stm32/irq.h>
+
#include <stdint.h>
#include <stdbool.h>
#include <debug.h>
-#include <arch/board/board.h>
+#include "stm32_gpio.h"
#include "vsn.h"
+#include "up_arch.h"
+
void board_power_register(void);
void board_power_adjust(void);
void board_power_status(void);
-void board_power_setbootvoltage(void)
+
+
+void board_power_init(void)
{
stm32_configgpio(GPIO_PVS);
+ stm32_configgpio(GPIO_PST);
+ stm32_configgpio(GPIO_XPWR);
+ stm32_configgpio(GPIO_SCTC);
+ stm32_configgpio(GPIO_PCLR);
+}
+
+
+void board_power_reboot(void)
+{
+ // low-level board reset (not just MCU reset)
+ // if external power is present, stimulate power-off as board
+ // will wake-up immediatelly, if power is not present, set an alarm
+ // before power off the board.
}
-void board_power_reboot(void);
-void board_power_off(void);
+
+void board_power_off(void)
+{
+ // Check if external supply is not present, otherwise return
+ // notifying that it is not possible to power-off the board
+
+ // \todo
+
+ // stop backgorund processes
+ irqsave();
+
+ // switch to internal HSI and get the PD0 and PD1 as GPIO
+ stm32_board_select_hsi();
+
+ // trigger shutdown with pull-up resistor (not push-pull!) and wait.
+ stm32_gpiowrite(GPIO_PCLR, true);
+ for(;;);
+}
diff --git a/nuttx/configs/vsn/src/ramtron.c b/nuttx/configs/vsn/src/ramtron.c
index 24f43d0ff..01cf93311 100644
--- a/nuttx/configs/vsn/src/ramtron.c
+++ b/nuttx/configs/vsn/src/ramtron.c
@@ -61,6 +61,11 @@ int up_ramtron(void)
int retval;
/* Get the SPI port */
+
+#if defined(CONFIG_STM32_JTAG_FULL_ENABLE) || defined(CONFIG_STM32_JTAG_NOJNTRST_ENABLE)
+ message("RAMTRON: Cannot open SPI3 port as JTAG is enabled. Switch to Serial JTAG mode.\n");
+ return -ENODEV;
+#endif
spi = up_spiinitialize(3);
if (!spi)
@@ -70,7 +75,7 @@ int up_ramtron(void)
}
message("RAMTRON: Initialized SPI3\n");
- mtd = ramtron_initialize(spi);
+ mtd = (struct mtd_dev_s *)ramtron_initialize(spi);
if (!mtd)
{
message("RAMTRON: Device not found\n");
diff --git a/nuttx/configs/vsn/src/sysclock.c b/nuttx/configs/vsn/src/sysclock.c
index f812dd2c1..79cc80ff2 100644
--- a/nuttx/configs/vsn/src/sysclock.c
+++ b/nuttx/configs/vsn/src/sysclock.c
@@ -39,6 +39,7 @@
#include <arch/board/board.h>
#include "stm32_rcc.h"
+#include "stm32_gpio.h"
#include "stm32_flash.h"
#include "up_internal.h"
#include "up_arch.h"
@@ -123,6 +124,11 @@ void stm32_board_select_hsi(void)
// Wait until the selected source is used as the system clock source
while ((getreg32(STM32_RCC_CFGR) & RCC_CFGR_SWS_MASK) != STM32_SYSCLK_SWS);
+
+ // map port PD0 and PD1 on OSC pins
+ regval = getreg32(STM32_AFIO_MAPR);
+ regval |= AFIO_MAPR_PD01_REMAP;
+ putreg32(regval, STM32_AFIO_MAPR);
}
@@ -140,6 +146,13 @@ void stm32_board_select_hsi(void)
*/
int stm32_board_select_hse(void)
{
+ uint32_t regval;
+
+ // be sure to release PD0 and PD1 pins from the OSC pins
+ regval = getreg32(STM32_AFIO_MAPR);
+ regval &= ~AFIO_MAPR_PD01_REMAP;
+ putreg32(regval, STM32_AFIO_MAPR);
+
// if (is cc1101 9 MHz clock output enabled), otherwise return with -1
// I think that clock register provides HSE valid signal to detect that as well.
diff --git a/nuttx/configs/vsn/src/vsn.h b/nuttx/configs/vsn/src/vsn.h
index c065e1e75..33282c5a1 100644
--- a/nuttx/configs/vsn/src/vsn.h
+++ b/nuttx/configs/vsn/src/vsn.h
@@ -1,138 +1,138 @@
-/************************************************************************************
- * 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.
- *
- * 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.
- *
- ************************************************************************************/
-
-#ifndef __CONFIGS_VSN_1_2_SRC_VSN_INTERNAL_H
-#define __CONFIGS_VSN_1_2_SRC_VSN_INTERNAL_H
-
-/************************************************************************************
- * Included Files
- ************************************************************************************/
-
-#include <arch/board/board.h>
-#include <nuttx/config.h>
-#include <nuttx/compiler.h>
-#include <stdint.h>
-
-/************************************************************************************
- * Definitions
- ************************************************************************************/
-
-/* LED */
-
-#define GPIO_LED (GPIO_OUTPUT|GPIO_CNF_OUTPP|GPIO_MODE_2MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTB|GPIO_PIN2)
-
-/* BUTTON - Note that after a good second button causes hardware reset */
-
-#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
- ************************************************************************************/
-
-/************************************************************************************
- * Public data
- ************************************************************************************/
-
-#ifndef __ASSEMBLY__
-
-/************************************************************************************
- * Public Functions
- ************************************************************************************/
-
-/************************************************************************************
- * Name: stm32_spiinitialize
- *
- * Description:
- * Called to configure SPI chip select GPIO pins for the VSN board.
- *
- ************************************************************************************/
-
-extern void weak_function stm32_spiinitialize(void);
-
-/************************************************************************************
- * Name: stm32_usbinitialize
- *
- * Description:
- * Called to setup USB-related GPIO pins for the VSN board.
- *
- ************************************************************************************/
-
-extern void weak_function stm32_usbinitialize(void);
-
-
-/************************************************************************************
- * Power Module
- *
- * Description:
- * - 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 */
-
+/************************************************************************************
+ * 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.
+ *
+ * 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.
+ *
+ ************************************************************************************/
+
+#ifndef __CONFIGS_VSN_1_2_SRC_VSN_INTERNAL_H
+#define __CONFIGS_VSN_SRC_VSN_INTERNAL_H
+
+/************************************************************************************
+ * Included Files
+ ************************************************************************************/
+
+#include <arch/board/board.h>
+#include <nuttx/config.h>
+#include <nuttx/compiler.h>
+#include <stdint.h>
+
+/************************************************************************************
+ * Definitions
+ ************************************************************************************/
+
+/* LED */
+
+#define GPIO_LED (GPIO_OUTPUT|GPIO_CNF_OUTPP |GPIO_MODE_2MHz |GPIO_PORTB|GPIO_PIN2 |GPIO_OUTPUT_CLEAR)
+
+/* BUTTON - Note that after a good second button causes hardware reset */
+
+#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_PORTC|GPIO_PIN7 |GPIO_OUTPUT_CLEAR)
+#define GPIO_PST (GPIO_INPUT |GPIO_CNF_INPULLDWN|GPIO_MODE_INPUT|GPIO_PORTC|GPIO_PIN13)
+#define GPIO_SCTC (GPIO_INPUT |GPIO_CNF_INPULLDWN|GPIO_MODE_INPUT|GPIO_PORTA|GPIO_PIN8 )
+#define GPIO_PCLR (GPIO_INPUT |GPIO_CNF_INPULLDWN|GPIO_MODE_INPUT|GPIO_PORTD|GPIO_PIN1 ) // by default this pin is OSCOUT, requires REMAP
+#define GPIO_XPWR (GPIO_INPUT |GPIO_CNF_INFLOAT |GPIO_MODE_INPUT|GPIO_PORTC|GPIO_PIN4 )
+
+/* FRAM */
+
+#define GPIO_FRAM_CS (GPIO_OUTPUT|GPIO_CNF_OUTPP |GPIO_MODE_50MHz|GPIO_PORTA|GPIO_PIN15|GPIO_OUTPUT_SET)
+
+
+/* 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
+ ************************************************************************************/
+
+/************************************************************************************
+ * Public data
+ ************************************************************************************/
+
+#ifndef __ASSEMBLY__
+
+/************************************************************************************
+ * Public Functions
+ ************************************************************************************/
+
+/************************************************************************************
+ * Name: stm32_spiinitialize
+ *
+ * Description:
+ * Called to configure SPI chip select GPIO pins for the VSN board.
+ *
+ ************************************************************************************/
+
+extern void weak_function stm32_spiinitialize(void);
+
+/************************************************************************************
+ * Name: stm32_usbinitialize
+ *
+ * Description:
+ * Called to setup USB-related GPIO pins for the VSN board.
+ *
+ ************************************************************************************/
+
+extern void weak_function stm32_usbinitialize(void);
+
+
+/************************************************************************************
+ * Init Power Module and set board system voltage
+ ************************************************************************************/
+
+extern void board_power_init(void);
+
+
+#endif /* __ASSEMBLY__ */
+#endif /* __CONFIGS_VSN_SRC_VSN_INTERNAL_H */
+