summaryrefslogtreecommitdiff
path: root/nuttx/configs/vsn
diff options
context:
space:
mode:
authorGregory Nutt <gnutt@nuttx.org>2014-04-13 16:22:22 -0600
committerGregory Nutt <gnutt@nuttx.org>2014-04-13 16:22:22 -0600
commit70b6bb22af51defd713adfd452309f32f0e523aa (patch)
treeb483c578cf6ae76888b89188bedb03f539ab4cd3 /nuttx/configs/vsn
parent3cf6b4d6577c2f467dbb25dd0da8cdc6ad32a7b4 (diff)
downloadpx4-nuttx-70b6bb22af51defd713adfd452309f32f0e523aa.tar.gz
px4-nuttx-70b6bb22af51defd713adfd452309f32f0e523aa.tar.bz2
px4-nuttx-70b6bb22af51defd713adfd452309f32f0e523aa.zip
More trailing whilespace removal
Diffstat (limited to 'nuttx/configs/vsn')
-rw-r--r--nuttx/configs/vsn/README.txt10
-rw-r--r--nuttx/configs/vsn/include/board.h24
-rw-r--r--nuttx/configs/vsn/include/muxbus.h12
-rw-r--r--nuttx/configs/vsn/include/power.h4
-rw-r--r--nuttx/configs/vsn/nsh/Make.defs2
-rw-r--r--nuttx/configs/vsn/src/Makefile2
-rw-r--r--nuttx/configs/vsn/src/README.txt22
-rw-r--r--nuttx/configs/vsn/src/buttons.c4
-rw-r--r--nuttx/configs/vsn/src/chipcon.c2
-rw-r--r--nuttx/configs/vsn/src/leds.c2
-rw-r--r--nuttx/configs/vsn/src/muxbus.c60
-rw-r--r--nuttx/configs/vsn/src/power.c8
-rw-r--r--nuttx/configs/vsn/src/rtac.c18
-rw-r--r--nuttx/configs/vsn/src/spi.c10
-rw-r--r--nuttx/configs/vsn/src/sysclock.c46
-rw-r--r--nuttx/configs/vsn/src/usbmsc.c2
-rw-r--r--nuttx/configs/vsn/src/vsn.h16
17 files changed, 122 insertions, 122 deletions
diff --git a/nuttx/configs/vsn/README.txt b/nuttx/configs/vsn/README.txt
index 7457800d9..a7096840d 100644
--- a/nuttx/configs/vsn/README.txt
+++ b/nuttx/configs/vsn/README.txt
@@ -94,7 +94,7 @@ IDEs
NuttX is built using command-line make. It can be used with an IDE, but some
effort will be required to create the project.
-
+
Makefile Build
--------------
Under Eclipse, it is pretty easy to set up an "empty makefile project" and
@@ -191,7 +191,7 @@ NXFLAT Toolchain
tools -- just the NXFLAT tools. The buildroot with the NXFLAT tools can
be downloaded from the NuttX SourceForge download site
(https://sourceforge.net/projects/nuttx/files/).
-
+
This GNU toolchain builds and executes in the Linux or Cygwin environment.
1. You must have already configured Nuttx in <some-dir>/nuttx.
@@ -247,7 +247,7 @@ VSN-specific Configuration Options
CONFIG_ARCH_BOARD=vsn (for the VSN development board)
CONFIG_ARCH_BOARD_name - For use in C code
-
+
CONFIG_ARCH_BOARD_VSN=y
CONFIG_ARCH_LOOPSPERMSEC - Must be calibrated for correct operation
@@ -302,8 +302,8 @@ Where <subdir> is one of the following:
Configures the NuttShell (nsh) located at examples/nsh. The
Configuration enables both the serial and telnetd NSH interfaces.
- The default configuration sets up a console on front-panel RS-232
- interface, sets up device driver of all supported equipment and
+ The default configuration sets up a console on front-panel RS-232
+ interface, sets up device driver of all supported equipment and
links in VSN default applications.
NOTES:
diff --git a/nuttx/configs/vsn/include/board.h b/nuttx/configs/vsn/include/board.h
index 766b6197d..fc88bb302 100644
--- a/nuttx/configs/vsn/include/board.h
+++ b/nuttx/configs/vsn/include/board.h
@@ -4,7 +4,7 @@
*
* Copyright (C) 2009 Gregory Nutt. All rights reserved.
* Copyright (C) 2011 Uros Platise. All rights reserved
- *
+ *
* Authors: Gregory Nutt <gnutt@nuttx.org>
* Uros Platise <uros.platise@isotel.eu>
*
@@ -62,8 +62,8 @@
/* Clocking *************************************************************************/
/* 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.
+ * not available on power-up. Instead we are about to run on HSI*9 = 36 MHz, see
+ * up_sysclock.c for details.
*/
#define STM32_BOARD_XTAL 9000000UL
@@ -71,9 +71,9 @@
/* PLL source is either HSI or HSE
* When HSI: PLL multiplier is 9, out frequency 36 MHz
- * When HSE: PLL multiplier is 8: out frequency is 9 MHz x 8 = 72MHz
+ * 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
@@ -125,17 +125,17 @@
#define STM32_CFGR_USBPRE 0
-/* SDIO dividers. Note that slower clocking is required when DMA is disabled
+/* SDIO dividers. Note that slower clocking is required when DMA is disabled
* in order to avoid RX overrun/TX underrun errors due to delayed responses
- * to service FIFOs in interrupt driven mode.
- *
+ * to service FIFOs in interrupt driven mode.
+ *
* SDcard default speed has max SDIO_CK freq of 25 MHz (12.5 Mbps)
* After selection of high speed freq may be 50 MHz (25 Mbps)
* Recommended default voltage: 3.3 V
*
- * HCLK=36MHz, SDIOCLK=36 MHz, SDIO_CK=HCLK/(88+2)=400 KHz
+ * HCLK=36MHz, SDIOCLK=36 MHz, SDIO_CK=HCLK/(88+2)=400 KHz
*/
-
+
#define SDIO_INIT_CLKDIV (88 << SDIO_CLKCR_CLKDIV_SHIFT)
/* DMA ON: HCLK=36 MHz, SDIOCLK=36MHz, SDIO_CK=HCLK/(0+2)=18 MHz
@@ -143,7 +143,7 @@
*/
#ifdef CONFIG_SDIO_DMA
-# define SDIO_MMCXFR_CLKDIV (0 << SDIO_CLKCR_CLKDIV_SHIFT)
+# define SDIO_MMCXFR_CLKDIV (0 << SDIO_CLKCR_CLKDIV_SHIFT)
#else
# ifndef CONFIG_DEBUG
# define SDIO_MMCXFR_CLKDIV (1 << SDIO_CLKCR_CLKDIV_SHIFT)
@@ -199,7 +199,7 @@ extern "C" {
/************************************************************************************
* Board Clock Configuration, called immediatelly after boot
************************************************************************************/
-
+
/************************************************************************************
* Name: stm32_boardinitialize
*
diff --git a/nuttx/configs/vsn/include/muxbus.h b/nuttx/configs/vsn/include/muxbus.h
index 595ded46f..ba22f8426 100644
--- a/nuttx/configs/vsn/include/muxbus.h
+++ b/nuttx/configs/vsn/include/muxbus.h
@@ -3,7 +3,7 @@
* include/arch/board/muxbus.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
@@ -56,20 +56,20 @@ extern "C" {
*/
void vsn_muxbus_init(void);
-/**
+/**
* Simple Lock / Unlock Mechanism for the SDIO Interface
- *
+ *
* NOTE: This function is provided for the stm32_sdio driver.
*/
extern void stm32_muxbus_sdio_lock(bool lock);
/**
- * Set PGA Gain of the Analog Devices AD8231 on bus shared with the
+ * Set PGA Gain of the Analog Devices AD8231 on bus shared with the
* SDIO interface
- *
+ *
* \param gain sets the front-end gain as 2^{gain}, where gain = 0..7.
* Setting gain outside that range shutdowns the front-end.
- *
+ *
* \return gain set or -1 if front end is put into shutdown.
*/
extern int vsn_muxbus_setpgagain(int gain);
diff --git a/nuttx/configs/vsn/include/power.h b/nuttx/configs/vsn/include/power.h
index 23ec8e20c..30b9105c4 100644
--- a/nuttx/configs/vsn/include/power.h
+++ b/nuttx/configs/vsn/include/power.h
@@ -3,7 +3,7 @@
* 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
@@ -56,7 +56,7 @@ extern "C" {
void board_power_reboot(void);
/** 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.
diff --git a/nuttx/configs/vsn/nsh/Make.defs b/nuttx/configs/vsn/nsh/Make.defs
index 0e2541a93..db06a07d4 100644
--- a/nuttx/configs/vsn/nsh/Make.defs
+++ b/nuttx/configs/vsn/nsh/Make.defs
@@ -52,7 +52,7 @@ ifeq ($(WINTOOL),y)
ARCHXXINCLUDES = -I. -isystem "${shell cygpath -w $(TOPDIR)/include}" -isystem "${shell cygpath -w $(TOPDIR)/include/cxx}"
ARCHSCRIPT = -T "${shell cygpath -w $(TOPDIR)/configs/$(CONFIG_ARCH_BOARD)/scripts/$(LDSCRIPT)}"
else
- # Linux/Cygwin-native toolchain
+ # Linux/Cygwin-native toolchain
MKDEP = $(TOPDIR)/tools/mkdeps.sh
ARCHINCLUDES = -I. -isystem $(TOPDIR)/include
ARCHXXINCLUDES = -I. -isystem $(TOPDIR)/include -isystem $(TOPDIR)/include/cxx
diff --git a/nuttx/configs/vsn/src/Makefile b/nuttx/configs/vsn/src/Makefile
index b0eba0a20..6ee276000 100644
--- a/nuttx/configs/vsn/src/Makefile
+++ b/nuttx/configs/vsn/src/Makefile
@@ -49,7 +49,7 @@ STACKSIZE = 4096
CFLAGS += -I$(TOPDIR)/sched
-ASRCS =
+ASRCS =
AOBJS = $(ASRCS:.S=$(OBJEXT))
CSRCS = sysclock.c boot.c leds.c buttons.c spi.c \
diff --git a/nuttx/configs/vsn/src/README.txt b/nuttx/configs/vsn/src/README.txt
index 732ede5e6..3760d55b3 100644
--- a/nuttx/configs/vsn/src/README.txt
+++ b/nuttx/configs/vsn/src/README.txt
@@ -3,14 +3,14 @@ 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.
+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
- sched/os_bringup.c then calls user entry defined in the .config file.
@@ -20,39 +20,39 @@ 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
+ - _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
+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:
-
+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 builtin application
registry.
diff --git a/nuttx/configs/vsn/src/buttons.c b/nuttx/configs/vsn/src/buttons.c
index c8a9b6bac..9c4ad37b5 100644
--- a/nuttx/configs/vsn/src/buttons.c
+++ b/nuttx/configs/vsn/src/buttons.c
@@ -62,11 +62,11 @@
****************************************************************************/
/** 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)
{
}
diff --git a/nuttx/configs/vsn/src/chipcon.c b/nuttx/configs/vsn/src/chipcon.c
index c4428d66f..4e4ad3fec 100644
--- a/nuttx/configs/vsn/src/chipcon.c
+++ b/nuttx/configs/vsn/src/chipcon.c
@@ -2,7 +2,7 @@
* 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
diff --git a/nuttx/configs/vsn/src/leds.c b/nuttx/configs/vsn/src/leds.c
index 141b39593..77a5fd7ea 100644
--- a/nuttx/configs/vsn/src/leds.c
+++ b/nuttx/configs/vsn/src/leds.c
@@ -72,7 +72,7 @@
/****************************************************************************
* Private Data
****************************************************************************/
-
+
irqstate_t irqidle_mask;
/****************************************************************************
diff --git a/nuttx/configs/vsn/src/muxbus.c b/nuttx/configs/vsn/src/muxbus.c
index 76304d67d..1a1ba02c2 100644
--- a/nuttx/configs/vsn/src/muxbus.c
+++ b/nuttx/configs/vsn/src/muxbus.c
@@ -66,7 +66,7 @@ sem_t vsn_muxbus_sem;
void vsn_muxbus_takeownership(void)
{
while (sem_wait(&vsn_muxbus_sem) != 0) {
-
+
/* The only case that an error should occr here is if the wait was
* awakened by a signal.
*/
@@ -81,7 +81,7 @@ void vsn_muxbus_sdio_release(void)
stm32_unconfiggpio(GPIO_SDIO_D0);
stm32_unconfiggpio(GPIO_SDIO_CK);
stm32_unconfiggpio(GPIO_SDIO_CMD);
-
+
vsn_muxbus_ownedbysdio = FALSE;
}
@@ -108,18 +108,18 @@ void vsn_muxbus_init(void)
stm32_configgpio(GPIO_PGIA_AEN);
/* setup semaphore in non-locked condition */
-
+
sem_init(&vsn_muxbus_sem, 0, 1);
-
+
/* by default give the bus to the SDIO */
-
+
vsn_muxbus_sdio_access();
}
-/**
+/**
* We could do extra checks: who is the owner to prevent
- * unlocking from SDIO side eventhough it was not locked
+ * unlocking from SDIO side eventhough it was not locked
* by him, but temporarily by the PGA
*/
void stm32_muxbus_sdio_lock(bool lock)
@@ -133,18 +133,18 @@ void stm32_muxbus_sdio_lock(bool lock)
/**
* The following rules apply for the SDcard:
- *
+ *
* - CMD serial line always starts with 0 (start-bit) and ends with 1 (stop-bit)
- * The total length is always 48 bits protected by CRCs. When changing the
+ * The total length is always 48 bits protected by CRCs. When changing the
* gain, CMD must be seen as 1 on CK changes.
- *
+ *
* - An alternative mechanism would be to use suspend/resume commands
- *
+ *
* - If SDcard internal shift-register is 8-bit oriented there might be a need
- * to shift 7 dummy bits to properly detect invalid start of packet
- * (with start bit set as 1) to invalidate bus transitions (in case CK
+ * to shift 7 dummy bits to properly detect invalid start of packet
+ * (with start bit set as 1) to invalidate bus transitions (in case CK
* is changing).
- *
+ *
* SDIO returns the bus in HiZ states, where CLK = 0, D = CMD = external pull-up
*/
int vsn_muxbus_setpgagain(int gain)
@@ -152,47 +152,47 @@ int vsn_muxbus_setpgagain(int gain)
/* Shutdown the Analog Devices AD8231 and exit if gain is invalid */
stm32_gpiowrite(GPIO_PGIA_AEN, FALSE);
-
+
if (gain < 0 || gain > 7)
return -1;
vsn_muxbus_takeownership();
vsn_muxbus_sdio_release();
-
+
/* If we have to set CLK = 1, made that first as D, CMD are 1 by pull-ups */
-
+
if (gain & 2)
stm32_configgpio(GPIO_PGIA_A1_H);
else stm32_configgpio(GPIO_PGIA_A1_L);
-
+
/* Set the D and CMD bits */
-
+
if (gain & 1)
stm32_configgpio(GPIO_PGIA_A0_H);
else stm32_configgpio(GPIO_PGIA_A0_L);
-
+
if (gain & 4)
stm32_configgpio(GPIO_PGIA_A2_H);
else stm32_configgpio(GPIO_PGIA_A2_L);
-
+
/* Sample GAIN on rising edge */
-
+
stm32_gpiowrite(GPIO_PGIA_AEN, TRUE);
-
+
/* Release D and CMD pins to 1; however shorten rising edge actively */
-
+
stm32_gpiowrite(GPIO_PGIA_A0_H, TRUE);
stm32_gpiowrite(GPIO_PGIA_A2_H, TRUE);
-
+
stm32_unconfiggpio(GPIO_PGIA_A0_H);
stm32_unconfiggpio(GPIO_PGIA_A2_H);
-
+
/* Release CLK by going down and return the bus */
-
- stm32_unconfiggpio(GPIO_PGIA_A1_L);
-
+
+ stm32_unconfiggpio(GPIO_PGIA_A1_L);
+
vsn_muxbus_sdio_access();
sem_post(&vsn_muxbus_sem);
-
+
return gain;
}
diff --git a/nuttx/configs/vsn/src/power.c b/nuttx/configs/vsn/src/power.c
index 56991cf33..72659f026 100644
--- a/nuttx/configs/vsn/src/power.c
+++ b/nuttx/configs/vsn/src/power.c
@@ -54,11 +54,11 @@
/****************************************************************************
* Declarations and Structures
- ****************************************************************************/
+ ****************************************************************************/
/****************************************************************************
* Private Functions
- ****************************************************************************/
+ ****************************************************************************/
void board_power_register(void);
void board_power_adjust(void);
@@ -68,7 +68,7 @@ void board_power_status(void);
/****************************************************************************
* Public Functions
- ****************************************************************************/
+ ****************************************************************************/
void board_power_init(void)
{
@@ -95,7 +95,7 @@ void board_power_off(void)
// notifying that it is not possible to power-off the board
// \todo
-
+
// stop background processes
irqsave();
diff --git a/nuttx/configs/vsn/src/rtac.c b/nuttx/configs/vsn/src/rtac.c
index 68b94a169..3a6b81756 100644
--- a/nuttx/configs/vsn/src/rtac.c
+++ b/nuttx/configs/vsn/src/rtac.c
@@ -38,14 +38,14 @@
/** \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
+ * 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
+ *
+ * It runs at maximum STM32 allowed precision of 16384 Hz, providing
* resolution of 61 us, required by the Sensor Network Protocol.
*/
@@ -83,22 +83,22 @@ int rtac_waitg(int group, int time)
/** Power optimization of base systick timer
- *
+ *
* 1. Simple method to skip wake-ups:
* - ask timers about the min. period, which is Ns * systick
* - set the preload register with floor(Ns) * DEFAULT_PRELOAD
* - on wake-up call routines Ns times.
- *
+ *
* 2. If intermediate ISR occuried then:
* - check how many periods have passed by reading the counter: Np
* - set the new counter value as (counter % DEFAULT_PRELOAD)
* - call timer routines Np times; the next call is as usual, starting
* at 1. point above
- *
+ *
* This is okay if ISR's do not read timers, if they read timers then:
* - on ISR wake-up the code described under 2. must be called first
* (on wake-up from IDLE)
- *
+ *
* BUT: the problem is that SYSTICK does not run in Stop mode but RTC
* only, so it might be better to replace SYSTICK with RTAC (this
* module) and do the job above, permitting ultra low power modes of
diff --git a/nuttx/configs/vsn/src/spi.c b/nuttx/configs/vsn/src/spi.c
index 173857948..2570e4292 100644
--- a/nuttx/configs/vsn/src/spi.c
+++ b/nuttx/configs/vsn/src/spi.c
@@ -92,14 +92,14 @@
/** 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.
* Configurations of SPI pins is performed in stm32_spi.c.
* Here, we only initialize chip select pins unique to the board architecture.
*/
-
+
#ifdef CONFIG_STM32_SPI2
stm32_configgpio(GPIO_CC1101_CS);
#endif
@@ -151,9 +151,9 @@ uint8_t stm32_spi1status(FAR struct spi_dev_s *dev, enum spi_dev_e devid)
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");
-
+
if (devid == SPIDEV_WIRELESS) {
-
+
stm32_gpiowrite(GPIO_CC1101_CS, !selected);
/* Wait for MISO to go low, indicates that Quart has stabilized */
@@ -162,7 +162,7 @@ void stm32_spi2select(FAR struct spi_dev_s *dev, enum spi_dev_e devid, bool sele
{
while (stm32_gpioread(GPIO_SPI2_MISO) ) up_waste();
}
-
+
}
}
diff --git a/nuttx/configs/vsn/src/sysclock.c b/nuttx/configs/vsn/src/sysclock.c
index 8b1a0be34..abb05e613 100644
--- a/nuttx/configs/vsn/src/sysclock.c
+++ b/nuttx/configs/vsn/src/sysclock.c
@@ -2,7 +2,7 @@
* configs/vsn/src/sysclock.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
@@ -44,7 +44,7 @@
/****************************************************************************
* Private Functions
- ****************************************************************************/
+ ****************************************************************************/
/** Selects internal HSI Clock, SYSCLK = 36 MHz, HCLK = 36 MHz
* - HSI at 8 MHz, :2 enters DPLL * 9, to get 36 MHz
@@ -53,14 +53,14 @@
* - Flash Wait State = 1, since it is 64-bit prefetch, it satisfies two 32-bit instructions
* (and branch losses a single cycle only, I found this as the best performance vs. frequency)
* - Sleep with peripherals disabled is about 2.5 mA @ 36 MHz, HSI
- *
+ *
* \todo:
* - dynamic clock scalling according to cross-peripheral requirements, AHB prescaler could
* change if all other prescalers increase, to maintain the ratio and to have min. HCLK
* possible; This is of interest when peripherals consume 50% of all power, as for instance
* in sleep mode @ 36 MHz, HSI with all peripherals enabled, i = 7 mA, on 24 Mhz 4.8 mA and
- * on 16 MHz 3.2 mA only.
- *
+ * on 16 MHz 3.2 mA only.
+ *
* \return Nothing, operation is always successful.
*/
void sysclock_select_hsi(void)
@@ -70,18 +70,18 @@ void sysclock_select_hsi(void)
// 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 &= ~FLASH_ACR_LATENCY_MASK;
regval |= (FLASH_ACR_LATENCY_1|FLASH_ACR_PRTFBE);
putreg32(regval, STM32_FLASH_ACR);
-
+
// Set the HCLK source/divider
regval = getreg32(STM32_RCC_CFGR);
regval &= ~RCC_CFGR_HPRE_MASK;
@@ -93,34 +93,34 @@ void sysclock_select_hsi(void)
regval &= ~RCC_CFGR_PPRE2_MASK;
regval |= STM32_RCC_CFGR_PPRE2;
putreg32(regval, STM32_RCC_CFGR);
-
+
// Set the PCLK1 divider
regval = getreg32(STM32_RCC_CFGR);
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
+#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);
-
+
// Enable the PLL
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);
-
+
// Select the system clock source (probably the PLL)
regval = getreg32(STM32_RCC_CFGR);
regval &= ~RCC_CFGR_SW_MASK;
@@ -129,7 +129,7 @@ void sysclock_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;
@@ -139,11 +139,11 @@ void sysclock_select_hsi(void)
/** Selects external HSE Clock, SYSCLK = 72 MHz, HCLK = 36/72 MHz
* - HSE at 9 MHz, DPLL * 8, to get 72 MHz
- * - Suitable for maximum performance and USB
+ * - Suitable for maximum performance and USB
* - Sleep power consumption at HSE and at 72 MHz is 5.5 mA (3.1 @ 36 MHz)
* - Option AHB prescaler is set to :2 to be compatible with HSI to remain on HCLK = 36 MHz
* - Flash memory running on 72 MHz needs two wait states
- *
+ *
* \return Clock selection status
* \retval 0 Successful
* \retval -1 External clock is not provided
@@ -160,17 +160,17 @@ int sysclock_select_hse(void)
// 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, Callbacks
- ****************************************************************************/
+ ****************************************************************************/
-/** TODO: Interrupt on lost HSE clock, change it to HSI, ... restarting is
+/** TODO: Interrupt on lost HSE clock, change it to HSI, ... restarting is
* more complex as the step requires restart of CC1101 device driver;
* so spawn a task for that... once cc1101 is restarted signal an event
* to restart clock.
@@ -182,7 +182,7 @@ void sysclock_hse_lost(void)
/****************************************************************************
* Public Functions
- ****************************************************************************/
+ ****************************************************************************/
/** Setup system clock, enabled when:
* - CONFIG_ARCH_BOARD_STM32_CUSTOM_CLOCKCONFIG
diff --git a/nuttx/configs/vsn/src/usbmsc.c b/nuttx/configs/vsn/src/usbmsc.c
index df263afd3..63948b177 100644
--- a/nuttx/configs/vsn/src/usbmsc.c
+++ b/nuttx/configs/vsn/src/usbmsc.c
@@ -143,7 +143,7 @@ int usbmsc_archinitialize(void)
}
message("usbmsc_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.
diff --git a/nuttx/configs/vsn/src/vsn.h b/nuttx/configs/vsn/src/vsn.h
index f8414f36c..e84f0acb4 100644
--- a/nuttx/configs/vsn/src/vsn.h
+++ b/nuttx/configs/vsn/src/vsn.h
@@ -51,12 +51,12 @@
/************************************************************************************
* PIN Definitions
************************************************************************************/
-
+
/* Board Peripheral Assignment
- *
+ *
* RS232/Power connector:
* - USART1, is the default bootloader and console
- *
+ *
* Sensor Connector:
* Digital:
* - GPIOs: PB10, PB11 (or even TIM2 CH3 and CH4)
@@ -70,14 +70,14 @@
* - Filtered Out (TIM3_CH4)
* (TIM8 could run at lower frequency, while TIM3 must run at highest possible)
* - Gain selection muxed with SDcard I/Os.
- *
+ *
* Radio connector:
* - UART3 / UART4
* - SPI2
* - I2C1 (remapped pins vs. Expansion connector)
* - CAN
* - TIM4 CH[3:4]
- *
+ *
* Expansion connector:
* - WakeUp Pin
* - System Wide Reset
@@ -88,7 +88,7 @@
* - ADC2 on pins [0:7]
* - TIM2 Channels [1:4]
* - TIM5 Channels [1:4]
- *
+ *
* Onboard Components:
* - SPI3 has direct connection with FRAM
* - SDCard, conencts the microSD and shares the control lines with Sensor Interface
@@ -100,7 +100,7 @@
/* 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 )
@@ -148,7 +148,7 @@
#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_CH 4 /* TIM3.CH4 */
+#define GPIO_OUT_PWM_TIM3_CH 4 /* TIM3.CH4 */
#define GPIO_PGIA_A0_H (GPIO_OUTPUT|GPIO_CNF_OUTPP |GPIO_MODE_2MHz |GPIO_PORTC|GPIO_PIN8 |GPIO_OUTPUT_SET)
#define GPIO_PGIA_A0_L (GPIO_OUTPUT|GPIO_CNF_OUTPP |GPIO_MODE_2MHz |GPIO_PORTC|GPIO_PIN8 |GPIO_OUTPUT_CLEAR)