summaryrefslogtreecommitdiff
path: root/nuttx/configs
diff options
context:
space:
mode:
Diffstat (limited to 'nuttx/configs')
-rw-r--r--nuttx/configs/vsn/include/board.h37
-rw-r--r--nuttx/configs/vsn/include/power.h17
-rwxr-xr-xnuttx/configs/vsn/nsh/defconfig6
-rw-r--r--nuttx/configs/vsn/src/Makefile26
-rw-r--r--nuttx/configs/vsn/src/README.txt50
-rw-r--r--nuttx/configs/vsn/src/boot.c27
-rw-r--r--nuttx/configs/vsn/src/buttons.c34
-rw-r--r--nuttx/configs/vsn/src/chipcon.c83
-rw-r--r--nuttx/configs/vsn/src/leds.c28
-rw-r--r--nuttx/configs/vsn/src/power.c59
-rw-r--r--nuttx/configs/vsn/src/rtac.c82
-rw-r--r--nuttx/configs/vsn/src/sif.c502
-rw-r--r--nuttx/configs/vsn/src/spi.c37
-rw-r--r--nuttx/configs/vsn/src/sysclock.c115
-rw-r--r--nuttx/configs/vsn/src/vsn.h68
15 files changed, 968 insertions, 203 deletions
diff --git a/nuttx/configs/vsn/include/board.h b/nuttx/configs/vsn/include/board.h
index f5c690f1e..733f1fc32 100644
--- a/nuttx/configs/vsn/include/board.h
+++ b/nuttx/configs/vsn/include/board.h
@@ -105,7 +105,8 @@
/* On-board external frequency source is 9MHz (HSE) provided by the CC1101, so it is
* not available on power-up. Instead we are about to run on HSI*9 = 36 MHz, see
- * up_sysclock.c for details. */
+ * up_sysclock.c for details.
+ */
#define STM32_BOARD_XTAL 9000000UL
#define STM32_BOARD_HCLK 36000000UL
@@ -114,6 +115,7 @@
* When HSI: PLL multiplier is 9, out frequency 36 MHz
* When HSE: PLL multiplier is 8: out frequency is 9 MHz x 8 = 72MHz
*/
+
#define STM32_CFGR_PLLSRC_HSI 0
#define STM32_CFGR_PLLMUL_HSI RCC_CFGR_PLLMUL_CLKx9
@@ -134,13 +136,18 @@
/* APB2 clock (PCLK2) is HCLK (36MHz) */
-#define STM32_RCC_CFGR_PPRE2 RCC_CFGR_PPRE2_HCLK
-#define STM32_PCLK2_FREQUENCY STM32_BOARD_HCLK
+#define STM32_RCC_CFGR_PPRE2 RCC_CFGR_PPRE2_HCLK
+#define STM32_PCLK2_FREQUENCY STM32_BOARD_HCLK
/* APB1 clock (PCLK1) is HCLK (36MHz) */
-#define STM32_RCC_CFGR_PPRE1 RCC_CFGR_PPRE1_HCLK
-#define STM32_PCLK1_FREQUENCY STM32_BOARD_HCLK
+#define STM32_RCC_CFGR_PPRE1 RCC_CFGR_PPRE1_HCLK
+#define STM32_PCLK1_FREQUENCY STM32_BOARD_HCLK
+
+/* Timer 1..8 Frequencies */
+
+#define STM32_TIM27_FREQUENCY (STM32_BOARD_HCLK)
+#define STM32_TIM18_FREQUENCY (STM32_BOARD_HCLK)
/* USB divider -- Divide PLL clock by 1.5 */
@@ -247,28 +254,10 @@ EXTERN uint8_t up_buttons(void);
#endif
-/************************************************************************************
- * 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)
}
#endif
#endif /* __ASSEMBLY__ */
-#endif /* __ARCH_BOARD_BOARD_H */
+#endif /* __ARCH_BOARD_BOARD_H */
diff --git a/nuttx/configs/vsn/include/power.h b/nuttx/configs/vsn/include/power.h
index 960c40fb1..5be7ab795 100644
--- a/nuttx/configs/vsn/include/power.h
+++ b/nuttx/configs/vsn/include/power.h
@@ -38,11 +38,6 @@
#ifndef __ARCH_BOARD_POWER_H
#define __ARCH_BOARD_POWER_H
-
-/************************************************************************************
- * Included Files
- ************************************************************************************/
-
#ifndef __ASSEMBLY__
#undef EXTERN
#if defined(__cplusplus)
@@ -53,15 +48,21 @@ extern "C" {
#endif
/************************************************************************************
- * Public Power Supply Contol
+ * Public Functions
************************************************************************************/
+/** Perform system reset on board level
+ */
void board_power_reboot(void);
-/* If this function returns, it means, that it was not possible to power-off the board */
+/** Power off the board
+ *
+ * If it returns, then it was not possible to power-off the board due to some
+ * other constraints. In the case of VSN due to external power supply, press
+ * of a push-button or RTC alarm.
+ */
void board_power_off(void);
-
#undef EXTERN
#if defined(__cplusplus)
}
diff --git a/nuttx/configs/vsn/nsh/defconfig b/nuttx/configs/vsn/nsh/defconfig
index a6fffc4c6..b4055a00e 100755
--- a/nuttx/configs/vsn/nsh/defconfig
+++ b/nuttx/configs/vsn/nsh/defconfig
@@ -750,7 +750,7 @@ CONFIG_NSH_DISABLEBG=n
CONFIG_NSH_ROMFSETC=y
CONFIG_NSH_CONSOLE=y
CONFIG_NSH_TELNET=n
-CONFIG_NSH_ARCHINIT=y
+CONFIG_NSH_ARCHINIT=n
CONFIG_NSH_IOBUFFER_SIZE=512
CONFIG_NSH_DHCPC=n
CONFIG_NSH_NOMAC=n
@@ -831,3 +831,7 @@ CONFIG_PTHREAD_STACK_MIN=256
CONFIG_PTHREAD_STACK_DEFAULT=2048
CONFIG_HEAP_BASE=
CONFIG_HEAP_SIZE=
+
+# Application configuration
+
+CONFIG_APPS_DIR="../apps"
diff --git a/nuttx/configs/vsn/src/Makefile b/nuttx/configs/vsn/src/Makefile
index 8b00da4a7..66ea8f32f 100644
--- a/nuttx/configs/vsn/src/Makefile
+++ b/nuttx/configs/vsn/src/Makefile
@@ -38,17 +38,23 @@
-include $(TOPDIR)/Make.defs
+#$(TOPDIR)/$(CONFIG_APPS_DIR)
+APPDIR = $(TOPDIR)/../apps/
+
+-include $(APPDIR)/Make.defs
+
+APPNAME = sif
+PRIORITY = SCHED_PRIORITY_DEFAULT
+STACKSIZE = 4096
+
CFLAGS += -I$(TOPDIR)/sched
ASRCS =
AOBJS = $(ASRCS:.S=$(OBJEXT))
CSRCS = sysclock.c boot.c leds.c buttons.c spi.c \
- usbdev.c power.c
+ usbdev.c power.c sif.c
-ifeq ($(CONFIG_NSH_ARCHINIT),y)
-CSRCS += nsh.c
-endif
ifeq ($(CONFIG_USBSTRG),y)
CSRCS += usbstrg.c
endif
@@ -79,6 +85,16 @@ libboard$(LIBEXT): $(OBJS)
$(call ARCHIVE, $@, $${obj}); \
done ; )
+# Register application
+
+.context:
+ $(call REGISTER,$(APPNAME),$(PRIORITY),$(STACKSIZE),$(APPNAME)_main)
+ @touch $@
+
+context: .context
+
+# Create dependencies
+
.depend: Makefile $(SRCS)
@$(MKDEP) $(CC) -- $(CFLAGS) -- $(SRCS) >Make.dep
@touch $@
@@ -90,6 +106,6 @@ clean:
$(call CLEAN)
distclean: clean
- @rm -f Make.dep .depend
+ @rm -f Make.dep .depend .context
-include Make.dep
diff --git a/nuttx/configs/vsn/src/README.txt b/nuttx/configs/vsn/src/README.txt
index bacf82c17..81f3ee4e1 100644
--- a/nuttx/configs/vsn/src/README.txt
+++ b/nuttx/configs/vsn/src/README.txt
@@ -1,4 +1,8 @@
+VSN Board Support Package, for the NuttX, Uros Platise <uros.platise@isotel.eu>
+===============================================================================
+http://www.netClamps.com
+
The directory contains start-up and board level functions.
Execution starts in the following order:
@@ -8,5 +12,47 @@ Execution starts in the following order:
is set. It must be set for the VSN board.
- boot, performs initial chip and board initialization
- - ...
- - nsh, as central application last.
+ - sched/os_bringup.c then calls either user_start or exec_nuttapp()
+ with application as set in the .config
+
+
+Naming throughout the code
+==========================
+
+ - _init(): used to be called once only, after powerup, to perform board
+ initialization
+ - _start() or called via FS _open(): starts peripheral power, puts it
+ into operation
+ - _stop() or called via FS _close(): opposite to _start()
+
+
+System notifications (a sort of run-levels)
+===========================================
+
+On the VSN, NSH represents the core application as it supports scripts
+easily adaptable for any custom application configuration. NSH is
+invoked as follows (argument runs a script from the /etc/init.d directory):
+
+ - nsh init: on system powerup called by the NuttX APP_START
+
+TODOs:
+
+ - nsh xpowerup: run on external power used to:
+ - try to setup an USB serial connection
+ - configure SLIP mode, internet
+ - start other internet services, such as telnetd, ftpd, httpd
+
+ - nsh xpowerdown: run whenever USB recevied suspend signal or
+ external power has been removed.
+ - used to stop internet services
+
+ - nsh batdown: whenever battery is completely discharged
+
+
+Compile notes
+===============================
+
+To link-in the sif_main() utility do, in this folder:
+ - make context TOPDIR=<path to nuttx top dir>
+
+This will result in registering the application into the nuttapp.
diff --git a/nuttx/configs/vsn/src/boot.c b/nuttx/configs/vsn/src/boot.c
index eb4ba9ef5..501bb07b5 100644
--- a/nuttx/configs/vsn/src/boot.c
+++ b/nuttx/configs/vsn/src/boot.c
@@ -37,41 +37,26 @@
*
************************************************************************************/
-/************************************************************************************
- * Included Files
- ************************************************************************************/
-
-#include <nuttx/config.h>
+/** \file
+ * \author Gregory Nutt, Uros Platise
+ * \brief VSN Button
+ */
#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
+/** Initialize Board
*
- * 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)
{
diff --git a/nuttx/configs/vsn/src/buttons.c b/nuttx/configs/vsn/src/buttons.c
index 3025b373c..c0a0f7297 100644
--- a/nuttx/configs/vsn/src/buttons.c
+++ b/nuttx/configs/vsn/src/buttons.c
@@ -1,11 +1,9 @@
/****************************************************************************
* configs/vsn/src/buttons.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>
+ * 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
@@ -36,17 +34,18 @@
*
****************************************************************************/
-/****************************************************************************
- * Included Files
- ****************************************************************************/
+/** \file
+ * \author Uros Platise
+ * \brief VSN Button
+ */
+
+#ifdef CONFIG_ARCH_BUTTONS
#include <nuttx/config.h>
#include <stdint.h>
#include <arch/board/board.h>
#include "vsn.h"
-#ifdef CONFIG_ARCH_BUTTONS
-
/****************************************************************************
* Definitions
****************************************************************************/
@@ -59,12 +58,19 @@
* Private Functions
****************************************************************************/
-/****************************************************************************
- * Public Functions
- ****************************************************************************/
+/** Called from an interrupt
+ *
+ * \todo Measure the time button is being pressed, and then:
+ * - if short signal all processes (tasks and threads) with 'button user request': SIGUSR1
+ * - if long (>0.5 s) signal all with 'power-off request': SIGTERM
+ **/
+void buttons_callback(void)
+{
+}
+
/****************************************************************************
- * Name: up_buttoninit
+ * Public Functions
****************************************************************************/
void up_buttoninit(void)
@@ -72,13 +78,11 @@ void up_buttoninit(void)
stm32_configgpio(GPIO_PUSHBUTTON);
}
-/****************************************************************************
- * Name: up_buttons
- ****************************************************************************/
uint8_t up_buttons(void)
{
return stm32_gpioread(GPIO_PUSHBUTTON);
}
+
#endif /* CONFIG_ARCH_BUTTONS */
diff --git a/nuttx/configs/vsn/src/chipcon.c b/nuttx/configs/vsn/src/chipcon.c
new file mode 100644
index 000000000..c4428d66f
--- /dev/null
+++ b/nuttx/configs/vsn/src/chipcon.c
@@ -0,0 +1,83 @@
+/****************************************************************************
+ * configs/vsn/src/chipcon.c
+ *
+ * Copyright (C) 2011 Uros Platise. All rights reserved.
+ *
+ * Author: 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.
+ *
+ ****************************************************************************/
+
+/** \file
+ * \author Uros Platise
+ * \brief Chipcon CC1101 Interface
+ */
+
+
+/****************************************************************************
+ * Public Functions
+ ****************************************************************************/
+
+/** Set external clock frequency, or disable it
+ */
+int chipcon_setXclock(int prescaler)
+{
+ // check present state, if it is enabled (in the chip!)
+
+ // change state and with OK if everything is OK.
+
+ return ERROR;
+}
+
+
+int chipcon_setchannel(uint16_t channel)
+{
+}
+
+
+void chipcon_init(int spino)
+{
+ // create stream driver, where STDIN is packet oriented
+ // means that two messages received are kept separated
+ // in internal buffers.
+
+ // default mode is AUTO, RX enabled and auto TX on writes and
+ // when chipcon is IDLE.
+}
+
+
+void chipcon_open(void)
+{
+}
+
+
+void chipcon_ioctl(void)
+{
+ // access to setXclock
+}
diff --git a/nuttx/configs/vsn/src/leds.c b/nuttx/configs/vsn/src/leds.c
index c1cc1c573..e440e5fce 100644
--- a/nuttx/configs/vsn/src/leds.c
+++ b/nuttx/configs/vsn/src/leds.c
@@ -2,11 +2,9 @@
* 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.
*
- * Authors: Gregory Nutt <spudmonkey@racsa.co.cr>
- * Uros Platise <uros.platise@isotel.eu>
+ * 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
@@ -37,20 +35,22 @@
*
****************************************************************************/
-/****************************************************************************
- * Included Files
- ****************************************************************************/
+/** \file
+ * \author Uros Platise
+ * \brief VSN LED
+ */
#include <nuttx/config.h>
-
#include <arch/board/board.h>
+
+#ifdef CONFIG_ARCH_LEDS
+
#include <arch/stm32/irq.h>
#include <stdint.h>
#include <stdbool.h>
#include <debug.h>
-#include "up_arch.h"
#include "vsn.h"
@@ -79,6 +79,7 @@
irqstate_t irqidle_mask;
+
/****************************************************************************
* Private Functions
****************************************************************************/
@@ -87,23 +88,17 @@ static void led_setonoff(unsigned int bits)
{
}
+
/****************************************************************************
* Public Functions
****************************************************************************/
-/****************************************************************************
- * Name: up_ledinit
- ****************************************************************************/
-#ifdef CONFIG_ARCH_LEDS
void up_ledinit(void)
{
stm32_configgpio(GPIO_LED);
}
-/****************************************************************************
- * Name: up_ledon
- ****************************************************************************/
void up_ledon(int led)
{
@@ -113,9 +108,6 @@ void up_ledon(int led)
}
}
-/****************************************************************************
- * Name: up_ledoff
- ****************************************************************************/
void up_ledoff(int led)
{
diff --git a/nuttx/configs/vsn/src/power.c b/nuttx/configs/vsn/src/power.c
index 2e5ed1d13..9cbcfaac8 100644
--- a/nuttx/configs/vsn/src/power.c
+++ b/nuttx/configs/vsn/src/power.c
@@ -35,6 +35,11 @@
*
****************************************************************************/
+/** \file
+ * \author Uros Platise
+ * \brief VSN Power
+ */
+
#include <nuttx/config.h>
#include <arch/board/board.h>
@@ -44,50 +49,60 @@
#include <stdbool.h>
#include <debug.h>
-#include "stm32_gpio.h"
#include "vsn.h"
-#include "up_arch.h"
+/****************************************************************************
+ * Declarations and Structures
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Functions
+ ****************************************************************************/
+
void board_power_register(void);
void board_power_adjust(void);
void board_power_status(void);
+/****************************************************************************
+ * Public Functions
+ ****************************************************************************/
+
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);
+ 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.
+ // 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_off(void)
{
- // Check if external supply is not present, otherwise return
- // notifying that it is not possible to power-off the board
+ // Check if external supply is not present, otherwise return
+ // notifying that it is not possible to power-off the board
- // \todo
-
- // stop background processes
- irqsave();
+ // \todo
+
+ // stop background processes
+ irqsave();
- // switch to internal HSI and get the PD0 and PD1 as GPIO
- sysclock_select_hsi();
+ // switch to internal HSI and get the PD0 and PD1 as GPIO
+ sysclock_select_hsi();
- // trigger shutdown with pull-up resistor (not push-pull!) and wait.
- stm32_gpiowrite(GPIO_PCLR, true);
- for(;;);
+ // trigger shutdown with pull-up resistor (not push-pull!) and wait.
+ stm32_gpiowrite(GPIO_PCLR, true);
+ for(;;);
}
diff --git a/nuttx/configs/vsn/src/rtac.c b/nuttx/configs/vsn/src/rtac.c
new file mode 100644
index 000000000..b953bd851
--- /dev/null
+++ b/nuttx/configs/vsn/src/rtac.c
@@ -0,0 +1,82 @@
+/****************************************************************************
+ * config/vsn/src/rtac.c
+ * arch/arm/src/board/rtac.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.
+ *
+ ****************************************************************************/
+
+/** \file
+ * \author Uros Platise
+ * \brief Real Time Alarm Clock
+ *
+ * Implementation of the Real-Time Alarm Clock as per SNP Specifications.
+ * It provides real-time and phase controlled timer module while it
+ * cooperates with hardware RTC for low-power operation.
+ *
+ * It provides a replacement for a system 32-bit UTC time/date counter.
+ *
+ * It runs at maximum STM32 allowed precision of 16384 Hz, providing
+ * resolution of 61 us, required by the Sensor Network Protocol.
+ */
+
+/****************************************************************************
+ * Definitions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Data
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Public Functions
+ ****************************************************************************/
+
+/** Execute from a group of events
+ **/
+int rtac_execg(int group)
+{
+ // called by each thread to spawn its apps given by its ID or group ID of
+ // multiple threads, when group parameter is set.
+}
+
+
+/** Wait and execute from a group of events
+ **/
+int rtac_waitg(int group, int time)
+{
+ // blocking variant of rtac_exec with timeout if specified
+}
diff --git a/nuttx/configs/vsn/src/sif.c b/nuttx/configs/vsn/src/sif.c
new file mode 100644
index 000000000..cdd7967f9
--- /dev/null
+++ b/nuttx/configs/vsn/src/sif.c
@@ -0,0 +1,502 @@
+/****************************************************************************
+ * config/vsn/src/sif.c
+ * arch/arm/src/board/sif.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.
+ *
+ ****************************************************************************/
+
+/** \file
+ * \author Uros Platise
+ * \brief VSN Sensor Interface
+ *
+ * Public interface:
+ * - sif_init(): should be called just once after system starts, to
+ * initialize internal data structures, device driver and hardware
+ * - individual starts() and stops() that control gpio, usart, i2c, ...
+ * are wrapped throu open() and close()
+ * - read() and write() are used for streaming
+ * - ioctl() for configuration
+ *
+ * STDOUT Coding 16-bit (little endian):
+ * - MSB = 0 GPIOs, followed by the both GPIO config bytes
+ * - MSB = 1 Input AD, centered around 0x4000
+ *
+ * STDIN Coding 16-bit (little endian):
+ * - MSB = 0 GPIOs, followed by the both GPIO config bytes
+ * - MSB-1 = 0 Analog Output (PWM or Power)
+ * - MSB-1 = 1 Analog Reference Tap
+ *
+ * GPIO Update cycle:
+ * - if they follow the Analog Output, they are synced with them
+ * - if they follow the Analog Reference Tap, they are synced with them
+ * - if either is configured without sample rate value, they are updated
+ * immediately, same as them
+ *
+ * Implementation:
+ * - Complete internal states and updateing is made via the struct
+ * vsn_sif_s, which is also accessible thru the ioctl() with
+ * SNP Message descriptor.
+ **/
+
+#include <nuttx/config.h>
+#include <nuttx/fs.h>
+#include <semaphore.h>
+
+#include <stdio.h>
+#include <stdlib.h>
+#include <unistd.h>
+#include <string.h>
+#include <errno.h>
+
+#include "vsn.h"
+
+
+/****************************************************************************
+ * Declarations and Structures
+ ****************************************************************************/
+
+#define VSN_SIF_READ_BUFSIZE 128
+#define VSN_SIF_WRITE_BUFSIZE 128
+
+
+typedef unsigned char vsn_sif_state_t;
+
+# define VSN_SIF_STATE_POWERDOWN 0x00 ///< power-down
+
+# define VSN_SIF_STATE_ACT_GPIO 0x01 ///< gpio is active
+# define VSN_SIF_STATE_ACT_USART 0x02 ///< usart is active
+# define VSN_SIF_STATE_ACT_I2C 0x04 ///< i2c is active
+# define VSN_SIF_STATE_ACT_OWIR1 0x08 ///< 1-wire is active on first GPIO
+# define VSN_SIF_STATE_ACT_OWIR2 0x10 ///< 1-wire is active on second GPIO
+
+# define VSN_SIF_STATE_ACT_ANOUT 0x20 ///< analog output is active
+# define VSN_SIF_STATE_ACT_ANIN 0x40 ///< analog input is active
+
+
+typedef unsigned char vsn_sif_gpio_t;
+
+# define VSN_SIF_GPIO_STATE_MASK 7
+# define VSN_SIF_GPIO_HIGHZ 0 ///< High-Z
+# define VSN_SIF_GPIO_PULLUP 1 ///< Pull-Up
+# define VSN_SIF_GPIO_PULLDOWN 2 ///< Pull-Down
+# define VSN_SIF_GPIO_OUTLOW 3 ///< Set Low
+# define VSN_SIF_GPIO_OUTHIGH 4 ///< Set High
+
+# define VSN_SIF_GPIO_DISALT_MASK 0x10 ///< Disable Alternate Function, Mask Bit
+# define VSN_SIF_GPIO_TRIG_MASK 0x20 ///< Send data change to the stdout
+# define VSN_SIF_GPIO_READ_MASK 0x40 ///< Readout mask
+
+
+#define VSN_SIF_ANOUT_LOW 0 // Pseudo Analog Output acts as GPIO
+#define VSN_SIF_ANOUT_HIGH 1 // Pseudo Analog Output acts as GPIO high
+#define VSN_SIF_ANOUT_HIGHPWR 2 // ... acts as high power output
+#define VSN_SIF_ANOUT_PWM 3 // ... acts as PWM output
+#define VSN_SIF_ANOUT_PWMPWR 4 // acts as power PWM output
+
+#define VSN_SIF_ANIN_GAINMASK 7
+#define VSN_SIF_ANIN_GAIN1 0
+#define VSN_SIF_ANIN_GAIN2 1
+#define VSN_SIF_ANIN_GAIN4 2
+#define VSN_SIF_ANIN_GAIN8 3
+#define VSN_SIF_ANIN_GAIN16 4
+#define VSN_SIF_ANIN_GAIN32 5
+#define VSN_SIF_ANIN_GAIN64 6
+#define VSN_SIF_ANIN_GAIN128 7
+
+#define VSN_SIF_ANIN_BITS8
+#define VSN_SIF_ANIN_BITS9
+#define VSN_SIF_ANIN_BITS10
+#define VSN_SIF_ANIN_BITS11
+#define VSN_SIF_ANIN_BITS12
+#define VSN_SIF_ANIN_BITS13
+#define VSN_SIF_ANIN_BITS14
+
+#define VSN_SIF_ANIN_OVERSMP1
+#define VSN_SIF_ANIN_OVERSMP2
+#define VSN_SIF_ANIN_OVERSMP4
+#define VSN_SIF_ANIN_OVERSMP8
+#define VSN_SIF_ANIN_OVERSMP16
+
+
+struct vsn_sif_s {
+ vsn_sif_state_t state; // activity
+ unsigned char opencnt; // open count
+
+ vsn_sif_gpio_t gpio[2];
+
+ unsigned char anout_opts;
+ unsigned short int anout_width;
+ unsigned short int anout_period; // setting it to 0, disables PWM
+ unsigned short int anout_samplerate; // as written by write()
+
+ unsigned short int anref_width;
+ unsigned short int anref_period; // setting it to 0, disables PWM
+ unsigned short int anref_samplerate; // as written by write()
+
+ unsigned char anin_opts;
+ unsigned int anin_samplerate; // returned on read() as 16-bit results
+
+ /*--- Private Data ---*/
+
+ struct stm32_tim_dev_s * tim3; // Timer3 is used for PWM, and Analog RefTap
+ struct stm32_tim_dev_s * tim8; // Timer8 is used for Power Switch
+
+ sem_t exclusive_access;
+};
+
+
+/****************************************************************************
+ * Private data
+ ****************************************************************************/
+
+struct vsn_sif_s vsn_sif;
+
+
+/****************************************************************************
+ * Semaphores
+ ****************************************************************************/
+
+void sif_sem_wait(void)
+{
+ while( sem_wait( &vsn_sif.exclusive_access ) != 0 ) {
+ ASSERT(errno == EINTR);
+ }
+}
+
+
+void inline sif_sem_post(void)
+{
+ sem_post( &vsn_sif.exclusive_access );
+}
+
+
+/****************************************************************************
+ * GPIOs and Alternative Functions
+ ****************************************************************************/
+
+
+void sif_gpios_reset(void)
+{
+ vsn_sif.gpio[0] = vsn_sif.gpio[1] = VSN_SIF_GPIO_HIGHZ;
+
+ stm32_configgpio(GPIO_GP1_HIZ);
+ stm32_configgpio(GPIO_GP2_HIZ);
+}
+
+
+void sif_gpio1_update(void)
+{
+ uint32_t val;
+
+ switch(vsn_sif.gpio[0] & VSN_SIF_GPIO_STATE_MASK) {
+ case VSN_SIF_GPIO_HIGHZ: val = GPIO_GP1_HIZ; break;
+ case VSN_SIF_GPIO_PULLUP: val = GPIO_GP1_PUP; break;
+ case VSN_SIF_GPIO_PULLDOWN: val = GPIO_GP1_PDN; break;
+ case VSN_SIF_GPIO_OUTLOW: val = GPIO_GP1_LOW; break;
+ case VSN_SIF_GPIO_OUTHIGH: val = GPIO_GP1_HIGH;break;
+ default: return;
+ }
+ stm32_configgpio(val);
+
+ if ( stm32_gpioread(val) )
+ vsn_sif.gpio[0] |= VSN_SIF_GPIO_READ_MASK;
+ else vsn_sif.gpio[0] &= ~VSN_SIF_GPIO_READ_MASK;
+}
+
+
+void sif_gpio2_update(void)
+{
+ uint32_t val;
+
+ switch(vsn_sif.gpio[1]) {
+ case VSN_SIF_GPIO_HIGHZ: val = GPIO_GP2_HIZ; break;
+ case VSN_SIF_GPIO_PULLUP: val = GPIO_GP2_PUP; break;
+ case VSN_SIF_GPIO_PULLDOWN: val = GPIO_GP2_PDN; break;
+ case VSN_SIF_GPIO_OUTLOW: val = GPIO_GP2_LOW; break;
+ case VSN_SIF_GPIO_OUTHIGH: val = GPIO_GP2_HIGH;break;
+ default: return;
+ }
+ stm32_configgpio(val);
+
+ if ( stm32_gpioread(val) )
+ vsn_sif.gpio[1] |= VSN_SIF_GPIO_READ_MASK;
+ else vsn_sif.gpio[1] &= ~VSN_SIF_GPIO_READ_MASK;
+}
+
+
+int sif_gpios_lock(vsn_sif_state_t peripheral)
+{
+ return ERROR;
+}
+
+
+int sif_gpios_unlock(vsn_sif_state_t peripheral)
+{
+ return ERROR;
+}
+
+
+/****************************************************************************
+ * Analog Outputs
+ ****************************************************************************/
+
+static volatile int test = 0, test_irq;
+
+
+static int sif_anout_isr(int irq, void *context)
+{
+ STM32_TIM_ACKINT(vsn_sif.tim8, 0);
+
+ test++;
+ test_irq = irq;
+
+ return OK;
+}
+
+
+int sif_anout_init(void)
+{
+ vsn_sif.tim3 = stm32_tim_init(3);
+ vsn_sif.tim8 = stm32_tim_init(8);
+
+ if (!vsn_sif.tim3 || !vsn_sif.tim8) return ERROR;
+
+ // Use the TIM3 as PWM modulated analogue output
+
+ STM32_TIM_SETCHANNEL(vsn_sif.tim3, GPIO_OUT_PWM_TIM3_CH4, STM32_TIM_CH_OUTPWM | STM32_TIM_CH_POLARITY_NEG);
+ STM32_TIM_SETPERIOD(vsn_sif.tim3, 4096);
+ STM32_TIM_SETCOMPARE(vsn_sif.tim3, GPIO_OUT_PWM_TIM3_CH4, 1024);
+
+ STM32_TIM_SETCLOCK(vsn_sif.tim3, 36e6);
+ STM32_TIM_SETMODE(vsn_sif.tim3, STM32_TIM_MODE_UP);
+ stm32_configgpio(GPIO_OUT_HIZ);
+
+ // Use the TIM8 to drive the upper power mosfet
+
+ STM32_TIM_SETISR(vsn_sif.tim8, sif_anout_isr, 0);
+ STM32_TIM_ENABLEINT(vsn_sif.tim8, 0);
+
+ STM32_TIM_SETCHANNEL(vsn_sif.tim8, GPIO_OUT_PWRPWM_TIM8_CH1P, STM32_TIM_CH_OUTPWM | STM32_TIM_CH_POLARITY_NEG);
+ STM32_TIM_SETPERIOD(vsn_sif.tim8, 4096);
+ STM32_TIM_SETCOMPARE(vsn_sif.tim8, GPIO_OUT_PWRPWM_TIM8_CH1P, 0);
+
+ STM32_TIM_SETCLOCK(vsn_sif.tim8, 36e6);
+ STM32_TIM_SETMODE(vsn_sif.tim8, STM32_TIM_MODE_UP);
+ stm32_configgpio(GPIO_OUT_PWRPWM);
+
+ return OK;
+}
+
+
+void sif_anout_update(void)
+{
+}
+
+
+void sif_anout_callback(void)
+{
+ // called at rate of PWM interrupt
+}
+
+
+/****************************************************************************
+ * Analog Input Reference Tap
+ ****************************************************************************/
+
+
+void sif_anref_init(void)
+{
+}
+
+
+/****************************************************************************
+ * Analog Input Sampler Unit
+ ****************************************************************************/
+
+
+void sif_anin_reset(void)
+{
+}
+
+
+/****************************************************************************
+ * Device driver functions
+ ****************************************************************************/
+
+int devsif_open(FAR struct file *filep)
+{
+ sif_sem_wait();
+ vsn_sif.opencnt++;
+
+ // Start Hardware
+
+ sif_sem_post();
+ return 0;
+}
+
+
+int devsif_close(FAR struct file *filep)
+{
+ sif_sem_wait();
+
+ if (--vsn_sif.opencnt) {
+
+ // suspend (powerdown) hardware
+
+ sif_gpios_reset();
+
+ //STM32_TIM_SETCLOCK(vsn_sif.tim3, 0);
+ //STM32_TIM_SETCLOCK(vsn_sif.tim8, 0);
+ }
+
+ sif_sem_post();
+ return 0;
+}
+
+
+static ssize_t devsif_read(FAR struct file *filp, FAR char *buffer, size_t len)
+{
+ sif_sem_wait();
+ memset(buffer, 0, len);
+ sif_sem_post();
+ return len;
+}
+
+
+static ssize_t devsif_write(FAR struct file *filp, FAR const char *buffer, size_t len)
+{
+ sif_sem_wait();
+ printf("getpid: %d\n", getpid() );
+ sif_sem_post();
+ return len;
+}
+
+
+#ifndef CONFIG_DISABLE_POLL
+static int devsif_poll(FAR struct file *filp, FAR struct pollfd *fds,
+ bool setup)
+{
+ if (setup) {
+ fds->revents |= (fds->events & (POLLIN|POLLOUT));
+
+ if (fds->revents != 0) {
+ sem_post(fds->sem);
+ }
+ }
+ return OK;
+}
+#endif
+
+
+int devsif_ioctl(FAR struct file *filep, int cmd, unsigned long arg)
+{
+ sif_sem_wait();
+ sif_sem_post();
+ return 0;
+}
+
+
+/****************************************************************************
+ * Public Functions
+ ****************************************************************************/
+
+
+static const struct file_operations devsif_fops = {
+ devsif_open, /* open */
+ devsif_close, /* close */
+ devsif_read, /* read */
+ devsif_write, /* write */
+ 0, /* seek */
+ devsif_ioctl /* ioctl */
+#ifndef CONFIG_DISABLE_POLL
+ , devsif_poll /* poll */
+#endif
+};
+
+
+/** Bring up the Sensor Interface by initializing all of the desired
+ * hardware components.
+ **/
+
+int sif_init(void)
+{
+ /* Initialize data-structure */
+
+ vsn_sif.state = VSN_SIF_STATE_POWERDOWN;
+ vsn_sif.opencnt = 0;
+ sem_init(&vsn_sif.exclusive_access, 0, 1);
+
+ /* Initialize hardware */
+
+ sif_gpios_reset();
+ if ( sif_anout_init() != OK ) return -1;
+
+ /* If everything is okay, register the driver */
+
+ (void)register_driver("/dev/sif0", &devsif_fops, 0666, NULL);
+ return OK;
+}
+
+
+/** SIF Utility
+ *
+ * Provides direct access to the sensor connector, readings, and diagnostic.
+ **/
+
+int sif_main(int argc, char *argv[])
+{
+ if (argc >= 2) {
+ if (!strcmp(argv[1], "init")) {
+ return sif_init();
+ }
+ else if (!strcmp(argv[1], "gpio") && argc == 4) {
+ vsn_sif.gpio[0] = atoi(argv[2]);
+ vsn_sif.gpio[1] = atoi(argv[3]);
+ sif_gpio1_update();
+ sif_gpio2_update();
+ printf("GPIO States: %2x %2x\n", vsn_sif.gpio[0], vsn_sif.gpio[1] );
+ return 0;
+ }
+ else if (!strcmp(argv[1], "pwr") && argc == 3) {
+ int val = atoi(argv[2]);
+ STM32_TIM_SETCOMPARE(vsn_sif.tim8, GPIO_OUT_PWRPWM_TIM8_CH1P, val);
+ return 0;
+ }
+ else if (!strcmp(argv[1], "c")) {
+ }
+ }
+
+ fprintf(stderr, "%s:\tinit\n\tgpio\tA B\n\tpwr\tval\n", argv[0]);
+ fprintf(stderr, "test = %.8x, test irq = %.8x\n", test, test_irq);
+ return -1;
+}
diff --git a/nuttx/configs/vsn/src/spi.c b/nuttx/configs/vsn/src/spi.c
index 742fcfd41..a452197b7 100644
--- a/nuttx/configs/vsn/src/spi.c
+++ b/nuttx/configs/vsn/src/spi.c
@@ -37,12 +37,17 @@
*
************************************************************************************/
-/************************************************************************************
- * Included Files
- ************************************************************************************/
+/** \file
+ * \author Gregory Nutt, Uros Platise
+ * \brief SPI Slave Selects
+ */
+
#include <nuttx/config.h>
#include <nuttx/spi.h>
+
+#if defined(CONFIG_STM32_SPI1) || defined(CONFIG_STM32_SPI2) || defined(CONFIG_STM32_SPI3)
+
#include <arch/board/board.h>
#include <stdint.h>
@@ -55,7 +60,6 @@
#include "stm32_internal.h"
#include "vsn.h"
-#if defined(CONFIG_STM32_SPI1) || defined(CONFIG_STM32_SPI2) || defined(CONFIG_STM32_SPI3)
/************************************************************************************
* Definitions
@@ -79,22 +83,15 @@
# define spivdbg(x...)
#endif
-/************************************************************************************
- * Private Functions
- ************************************************************************************/
/************************************************************************************
* Public Functions
************************************************************************************/
-/************************************************************************************
- * Name: stm32_spiinitialize
- *
- * Description:
- * Called to configure SPI chip select GPIO pins for the VSN board.
- *
- ************************************************************************************/
+/** Called to configure SPI chip select GPIO pins for the VSN board.
+ */
+
void weak_function stm32_spiinitialize(void)
{
/* NOTE: Clocking for SPI1 and/or SPI2 and SPI3 was already provided in stm32_rcc.c.
@@ -109,10 +106,8 @@ void weak_function stm32_spiinitialize(void)
#endif
}
-/****************************************************************************
- * Name: stm32_spi1/2/3select and stm32_spi1/2/3status
+/** Selects: stm32_spi1/2/3select and stm32_spi1/2/3status
*
- * Description:
* The external functions, stm32_spi1/2/3select and stm32_spi1/2/3status 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
@@ -132,9 +127,10 @@ void weak_function stm32_spiinitialize(void)
* mmcsd_spislotinitialize(), for example, will bind the SPI driver to
* the SPI MMC/SD driver).
*
- ****************************************************************************/
+ **/
#ifdef CONFIG_STM32_SPI1
+
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");
@@ -144,9 +140,11 @@ uint8_t stm32_spi1status(FAR struct spi_dev_s *dev, enum spi_dev_e devid)
{
return SPI_STATUS_PRESENT;
}
+
#endif
#ifdef CONFIG_STM32_SPI2
+
void stm32_spi2select(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");
@@ -156,9 +154,11 @@ uint8_t stm32_spi2status(FAR struct spi_dev_s *dev, enum spi_dev_e devid)
{
return SPI_STATUS_PRESENT;
}
+
#endif
#ifdef CONFIG_STM32_SPI3
+
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");
@@ -173,6 +173,7 @@ uint8_t stm32_spi3status(FAR struct spi_dev_s *dev, enum spi_dev_e devid)
{
return SPI_STATUS_PRESENT;
}
+
#endif
#endif /* CONFIG_STM32_SPI1 || CONFIG_STM32_SPI2 */
diff --git a/nuttx/configs/vsn/src/sysclock.c b/nuttx/configs/vsn/src/sysclock.c
index 928282b12..f65ae0670 100644
--- a/nuttx/configs/vsn/src/sysclock.c
+++ b/nuttx/configs/vsn/src/sysclock.c
@@ -35,18 +35,16 @@
****************************************************************************/
/** \file
- */
+ * \author Uros Platise
+ * \brief VSN System Clock Configuration
+ */
-#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"
-#include "chip.h"
+#include "vsn.h"
- /*--- Private ---*/
+/****************************************************************************
+ * Private Functions
+ ****************************************************************************/
/** Selects internal HSI Clock, SYSCLK = 36 MHz, HCLK = 36 MHz
* - HSI at 8 MHz, :2 enters DPLL * 9, to get 36 MHz
@@ -67,28 +65,28 @@
*/
void sysclock_select_hsi(void)
{
- uint32_t regval;
-
- // Are we running on HSE?
- regval = getreg32(STM32_RCC_CR);
- if (regval & RCC_CR_HSEON) {
-
- // \todo: check is if we are running on HSE, we need the step down sequenuce from HSE -> HSI
-
- return; // do nothing at this time
- }
-
- // Set FLASH prefetch buffer and 1 wait state
- regval = getreg32(STM32_FLASH_ACR);
- regval &= ~ACR_LATENCY_MASK;
- regval |= (ACR_LATENCY_1|ACR_PRTFBE);
- putreg32(regval, STM32_FLASH_ACR);
-
+ uint32_t regval;
+
+ // Are we running on HSE?
+ regval = getreg32(STM32_RCC_CR);
+ if (regval & RCC_CR_HSEON) {
+
+ // \todo: check is if we are running on HSE, we need the step down sequenuce from HSE -> HSI
+
+ return; // do nothing at this time
+ }
+
+ // Set FLASH prefetch buffer and 1 wait state
+ regval = getreg32(STM32_FLASH_ACR);
+ regval &= ~ACR_LATENCY_MASK;
+ regval |= (ACR_LATENCY_1|ACR_PRTFBE);
+ putreg32(regval, STM32_FLASH_ACR);
+
// Set the HCLK source/divider
- regval = getreg32(STM32_RCC_CFGR);
- regval &= ~RCC_CFGR_HPRE_MASK;
- regval |= STM32_RCC_CFGR_HPRE_HSI;
- putreg32(regval, STM32_RCC_CFGR);
+ regval = getreg32(STM32_RCC_CFGR);
+ regval &= ~RCC_CFGR_HPRE_MASK;
+ regval |= STM32_RCC_CFGR_HPRE_HSI;
+ putreg32(regval, STM32_RCC_CFGR);
// Set the PCLK2 divider
regval = getreg32(STM32_RCC_CFGR);
@@ -101,20 +99,27 @@ void sysclock_select_hsi(void)
regval &= ~RCC_CFGR_PPRE1_MASK;
regval |= STM32_RCC_CFGR_PPRE1;
putreg32(regval, STM32_RCC_CFGR);
+
+ // Set the TIM1..8 clock multipliers
+#ifdef STM32_TIM27_FREQMUL2
+#endif
+
+#ifdef STM32_TIM18_FREQMUL2
+#endif
// Set the PLL source = HSI, divider (/2) and multipler (*9)
- regval = getreg32(STM32_RCC_CFGR);
- regval &= ~(RCC_CFGR_PLLSRC|RCC_CFGR_PLLXTPRE|RCC_CFGR_PLLMUL_MASK);
- regval |= (STM32_CFGR_PLLSRC_HSI|STM32_CFGR_PLLMUL_HSI);
- putreg32(regval, STM32_RCC_CFGR);
+ regval = getreg32(STM32_RCC_CFGR);
+ regval &= ~(RCC_CFGR_PLLSRC|RCC_CFGR_PLLXTPRE|RCC_CFGR_PLLMUL_MASK);
+ regval |= (STM32_CFGR_PLLSRC_HSI|STM32_CFGR_PLLMUL_HSI);
+ putreg32(regval, STM32_RCC_CFGR);
// Enable the PLL
- regval = getreg32(STM32_RCC_CR);
- regval |= RCC_CR_PLLON;
- putreg32(regval, STM32_RCC_CR);
+ regval = getreg32(STM32_RCC_CR);
+ regval |= RCC_CR_PLLON;
+ putreg32(regval, STM32_RCC_CR);
// Wait until the PLL is ready
- while ((getreg32(STM32_RCC_CR) & RCC_CR_PLLRDY) == 0);
+ while ((getreg32(STM32_RCC_CR) & RCC_CR_PLLRDY) == 0);
// Select the system clock source (probably the PLL)
regval = getreg32(STM32_RCC_CFGR);
@@ -126,9 +131,9 @@ void sysclock_select_hsi(void)
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);
+ regval = getreg32(STM32_AFIO_MAPR);
+ regval |= AFIO_MAPR_PD01_REMAP;
+ putreg32(regval, STM32_AFIO_MAPR);
}
@@ -146,21 +151,23 @@ void sysclock_select_hsi(void)
*/
int sysclock_select_hse(void)
{
- uint32_t regval;
+ 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.
-
- return 0;
+ 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.
+
+ return 0;
}
- /*--- Interrupts ---*/
+/****************************************************************************
+ * Interrupts, Callbacks
+ ****************************************************************************/
/** TODO: Interrupt on lost HSE clock, change it to HSI, ... restarting is
@@ -173,7 +180,9 @@ void sysclock_hse_lost(void)
}
- /*--- Public API ---*/
+/****************************************************************************
+ * Public Functions
+ ****************************************************************************/
/** Setup system clock, enabled when:
* - CONFIG_ARCH_BOARD_STM32_CUSTOM_CLOCKCONFIG
@@ -181,5 +190,5 @@ void sysclock_hse_lost(void)
*/
void stm32_board_clockconfig(void)
{
- sysclock_select_hsi();
+ sysclock_select_hsi();
}
diff --git a/nuttx/configs/vsn/src/vsn.h b/nuttx/configs/vsn/src/vsn.h
index 33282c5a1..5d017b07a 100644
--- a/nuttx/configs/vsn/src/vsn.h
+++ b/nuttx/configs/vsn/src/vsn.h
@@ -2,11 +2,9 @@
* 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>
+ * 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
@@ -37,20 +35,21 @@
*
************************************************************************************/
-#ifndef __CONFIGS_VSN_1_2_SRC_VSN_INTERNAL_H
+#ifndef __CONFIGS_VSN_SRC_VSN_INTERNAL_H
#define __CONFIGS_VSN_SRC_VSN_INTERNAL_H
-/************************************************************************************
- * Included Files
- ************************************************************************************/
-
-#include <arch/board/board.h>
#include <nuttx/config.h>
+#include <arch/board/board.h>
#include <nuttx/compiler.h>
#include <stdint.h>
+#include "stm32.h"
+#include "up_internal.h"
+#include "up_arch.h"
+
+
/************************************************************************************
- * Definitions
+ * PIN Definitions
************************************************************************************/
/* LED */
@@ -69,12 +68,53 @@
#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 */
+/* FRAM (alt pins are not listed here and are a part of SPI) */
#define GPIO_FRAM_CS (GPIO_OUTPUT|GPIO_CNF_OUTPP |GPIO_MODE_50MHz|GPIO_PORTA|GPIO_PIN15|GPIO_OUTPUT_SET)
+/* Sensor Interface */
+
+#define GPIO_GP1_HIZ (GPIO_INPUT |GPIO_CNF_INFLOAT |GPIO_MODE_INPUT|GPIO_PORTB|GPIO_PIN10)
+#define GPIO_GP1_PUP (GPIO_INPUT |GPIO_CNF_INPULLUP |GPIO_MODE_INPUT|GPIO_PORTB|GPIO_PIN10)
+#define GPIO_GP1_PDN (GPIO_INPUT |GPIO_CNF_INPULLDWN|GPIO_MODE_INPUT|GPIO_PORTB|GPIO_PIN10)
+#define GPIO_GP1_LOW (GPIO_OUTPUT|GPIO_CNF_OUTPP |GPIO_MODE_2MHz |GPIO_PORTB|GPIO_PIN10|GPIO_OUTPUT_CLEAR)
+#define GPIO_GP1_HIGH (GPIO_OUTPUT|GPIO_CNF_OUTPP |GPIO_MODE_2MHz |GPIO_PORTB|GPIO_PIN10|GPIO_OUTPUT_SET)
+
+#define GPIO_GP2_HIZ (GPIO_INPUT |GPIO_CNF_INFLOAT |GPIO_MODE_INPUT|GPIO_PORTB|GPIO_PIN11)
+#define GPIO_GP2_PUP (GPIO_INPUT |GPIO_CNF_INPULLUP |GPIO_MODE_INPUT|GPIO_PORTB|GPIO_PIN11)
+#define GPIO_GP2_PDN (GPIO_INPUT |GPIO_CNF_INPULLDWN|GPIO_MODE_INPUT|GPIO_PORTB|GPIO_PIN11)
+#define GPIO_GP2_LOW (GPIO_OUTPUT|GPIO_CNF_OUTPP |GPIO_MODE_2MHz |GPIO_PORTB|GPIO_PIN11|GPIO_OUTPUT_CLEAR)
+#define GPIO_GP2_HIGH (GPIO_OUTPUT|GPIO_CNF_OUTPP |GPIO_MODE_2MHz |GPIO_PORTB|GPIO_PIN11|GPIO_OUTPUT_SET)
+
+#define GPIO_OPA_INPUT (GPIO_INPUT |GPIO_CNF_ANALOGIN |GPIO_MODE_INPUT|GPIO_PORTC|GPIO_PIN0 )
+#define GPIO_OPA_ENABLE (GPIO_OUTPUT|GPIO_CNF_OUTPP |GPIO_MODE_2MHz |GPIO_PORTC|GPIO_PIN1 |GPIO_OUTPUT_CLEAR)
+#define GPIO_OPA_REFAIN (GPIO_INPUT |GPIO_CNF_ANALOGIN |GPIO_MODE_INPUT|GPIO_PORTB|GPIO_PIN0 )
+#define GPIO_OPA_REFPWM (GPIO_ALT |GPIO_CNF_AFPP |GPIO_MODE_50MHz|GPIO_PORTB|GPIO_PIN0 )
+
+#define GPIO_OUT_PWRON (GPIO_OUTPUT|GPIO_CNF_OUTPP |GPIO_MODE_2MHz |GPIO_PORTC|GPIO_PIN6 |GPIO_OUTPUT_CLEAR)
+#define GPIO_OUT_PWROFF (GPIO_OUTPUT|GPIO_CNF_OUTPP |GPIO_MODE_2MHz |GPIO_PORTC|GPIO_PIN6 |GPIO_OUTPUT_SET)
+#define GPIO_OUT_PWRPWM (GPIO_ALT |GPIO_CNF_AFPP |GPIO_MODE_10MHz|GPIO_PORTC|GPIO_PIN6 )
+#define GPIO_OUT_PWRPWM_TIM8_CH1P 1 /* TIM8.CH1 */
-/* Debug ********************************************************************/
+#define GPIO_OUT_HIZ (GPIO_INPUT |GPIO_CNF_INFLOAT |GPIO_MODE_INPUT|GPIO_PORTB|GPIO_PIN1 )
+#define GPIO_OUT_PUP (GPIO_INPUT |GPIO_CNF_INPULLUP |GPIO_MODE_INPUT|GPIO_PORTB|GPIO_PIN1 )
+#define GPIO_OUT_PDN (GPIO_INPUT |GPIO_CNF_INPULLDWN|GPIO_MODE_INPUT|GPIO_PORTB|GPIO_PIN1 )
+#define GPIO_OUT_LOW (GPIO_OUTPUT|GPIO_CNF_OUTPP |GPIO_MODE_2MHz |GPIO_PORTB|GPIO_PIN1 |GPIO_OUTPUT_CLEAR)
+#define GPIO_OUT_HIGH (GPIO_OUTPUT|GPIO_CNF_OUTPP |GPIO_MODE_2MHz |GPIO_PORTB|GPIO_PIN1 |GPIO_OUTPUT_SET)
+#define GPIO_OUT_AIN (GPIO_INPUT |GPIO_CNF_ANALOGIN |GPIO_MODE_INPUT|GPIO_PORTB|GPIO_PIN1 )
+#define GPIO_OUT_PWM (GPIO_ALT |GPIO_CNF_AFPP |GPIO_MODE_10MHz|GPIO_PORTB|GPIO_PIN1 )
+#define GPIO_OUT_PWM_TIM3_CH4 4 /* TIM3.CH4 */
+
+
+/* Radio Connector */
+
+
+/* Expansion Connector */
+
+
+/************************************************************************************
+ * Debugging
+ ************************************************************************************/
#ifdef CONFIG_CPP_HAVE_VARARGS
# ifdef CONFIG_DEBUG
@@ -92,10 +132,6 @@
/************************************************************************************
- * Public Types
- ************************************************************************************/
-
-/************************************************************************************
* Public data
************************************************************************************/