summaryrefslogtreecommitdiff
path: root/nuttx/configs/stm32ldiscovery
diff options
context:
space:
mode:
authorGregory Nutt <gnutt@nuttx.org>2013-05-20 12:17:34 -0600
committerGregory Nutt <gnutt@nuttx.org>2013-05-20 12:17:34 -0600
commit27045911445a07fe3a39962ce2b428d133971a85 (patch)
tree416d7ca161a7a3dec752f70b87393646f7f968c6 /nuttx/configs/stm32ldiscovery
parent33ab4ed94393e3c95d1155394789ee6aabfd42a9 (diff)
downloadpx4-nuttx-27045911445a07fe3a39962ce2b428d133971a85.tar.gz
px4-nuttx-27045911445a07fe3a39962ce2b428d133971a85.tar.bz2
px4-nuttx-27045911445a07fe3a39962ce2b428d133971a85.zip
Fix STM32L-Discovery clock setup - The X3 crystal is not fitted on the board
Diffstat (limited to 'nuttx/configs/stm32ldiscovery')
-rw-r--r--nuttx/configs/stm32ldiscovery/README.txt7
-rw-r--r--nuttx/configs/stm32ldiscovery/include/board.h31
-rw-r--r--nuttx/configs/stm32ldiscovery/nsh/defconfig2
-rw-r--r--nuttx/configs/stm32ldiscovery/src/stm32_userleds.c2
-rw-r--r--nuttx/configs/stm32ldiscovery/src/stm32ldiscovery.h18
5 files changed, 33 insertions, 27 deletions
diff --git a/nuttx/configs/stm32ldiscovery/README.txt b/nuttx/configs/stm32ldiscovery/README.txt
index 5c8eae418..860e220b1 100644
--- a/nuttx/configs/stm32ldiscovery/README.txt
+++ b/nuttx/configs/stm32ldiscovery/README.txt
@@ -444,6 +444,11 @@ GND and (external) 5V are available on both P1 and P2. Note: These signals
may be at lower voltage levels and, hence, may not properly drive an external
RS-232 transceiver.
+NOTE: The crystal X3 is not installed on the STM32L3-Discovery. As a
+result, the HSE clock is not availabled and the less acurate HSI must be
+used. This may limit the accuracy of the computed baud, especially at
+higher BAUD.
+
A USB serial console is another option.
Debugging
@@ -707,6 +712,8 @@ Where <subdir> is one of the following:
USB converter. The UART1 TX and RX pins should be available on
PA9 and PA10, respectively.
+ The serial console is configured for 57600 8N1
+
3. Support for NSH built-in applications is *not* enabled.
4. By default, this configuration uses the CodeSourcery toolchain
diff --git a/nuttx/configs/stm32ldiscovery/include/board.h b/nuttx/configs/stm32ldiscovery/include/board.h
index 951b38b63..d6f57492f 100644
--- a/nuttx/configs/stm32ldiscovery/include/board.h
+++ b/nuttx/configs/stm32ldiscovery/include/board.h
@@ -60,7 +60,8 @@
* - HSI high-speed internal oscillator clock
* Generated from an internal 16 MHz RC oscillator
* - HSE high-speed external oscillator clock
- * Driven by the 8MHz crystal (X1) on the OSC_IN and OSC_OUT pins
+ * Normally driven by an external crystal (X3). However, this crystal is not fitted
+ * on the STM32L-Discovery board.
* - PLL clock
* - MSI multispeed internal oscillator clock
* The MSI clock signal is generated from an internal RC oscillator. Seven frequency
@@ -74,7 +75,7 @@
* Driven by 32.768KHz crystal (X2) on the OSC32_IN and OSC32_OUT pins.
*/
-#define STM32_BOARD_XTAL 8000000ul /* X1 on board */
+#define STM32_BOARD_XTAL 8000000ul /* X3 on board (not fitted)*/
#define STM32_HSI_FREQUENCY 16000000ul /* Approximately 16MHz */
#define STM32_HSE_FREQUENCY STM32_BOARD_XTAL
@@ -84,11 +85,11 @@
/* PLL Configuration
*
- * - PLL source is HSE/1 -> 8MHz input
- * - PLL multipler is 8 -> 64MHz PLL VCO clock output
+ * - PLL source is HSI -> 16MHz input (nominal)
+ * - PLL multipler is 4 -> 64MHz PLL VCO clock output
* - PLL output divider 2 -> 32MHz divided down PLL VCO clock output
*
- * Resulting SYSCLK frequency is 8MHz (XTAL) x 8 / 2 = 32MHz
+ * Resulting SYSCLK frequency is 16MHz x 4 / 2 = 32MHz
*
* USB/SDIO:
* If the USB or SDIO interface is used in the application, the PLL VCO
@@ -105,10 +106,10 @@
* The minimum input clock frequency for PLL is 2 MHz (when using HSE as PLL source).
*/
-#define STM32_CFGR_PLLSRC RCC_CFGR_PLLSRC /* Source is 8MHz HSE */
-#define STM32_CFGR_PLLMUL RCC_CFGR_PLLMUL_CLKx8 /* PLLMUL = 8 */
+#define STM32_CFGR_PLLSRC 0 /* Source is 16MHz HSI */
+#define STM32_CFGR_PLLMUL RCC_CFGR_PLLMUL_CLKx4 /* PLLMUL = 4 */
#define STM32_CFGR_PLLDIV RCC_CFGR_PLLDIV_2 /* PLLDIV = 2 */
-#define STM32_PLL_FREQUENCY (8*STM32_BOARD_XTAL) /* PLL VCO Frequency is 64MHz */
+#define STM32_PLL_FREQUENCY (4*STM32_HSE_FREQUENCY) /* PLL VCO Frequency is 64MHz */
/* Use the PLL and set the SYSCLK source to be the diveded down PLL VCO output
* frequency (STM32_PLL_FREQUENCY divided by the PLLDIV value).
@@ -292,7 +293,7 @@ extern "C" {
*
************************************************************************************/
-EXTERN void stm32_boardinitialize(void);
+void stm32_boardinitialize(void);
/************************************************************************************
* Name: stm32_ledinit, stm32_setled, and stm32_setleds
@@ -305,9 +306,9 @@ EXTERN void stm32_boardinitialize(void);
************************************************************************************/
#ifndef CONFIG_ARCH_LEDS
-EXTERN void stm32_ledinit(void);
-EXTERN void stm32_setled(int led, bool ledon);
-EXTERN void stm32_setleds(uint8_t ledset);
+void stm32_ledinit(void);
+void stm32_setled(int led, bool ledon);
+void stm32_setleds(uint8_t ledset);
#endif
/************************************************************************************
@@ -334,10 +335,10 @@ EXTERN void stm32_setleds(uint8_t ledset);
************************************************************************************/
#ifdef CONFIG_ARCH_BUTTONS
-EXTERN void up_buttoninit(void);
-EXTERN uint8_t up_buttons(void);
+void up_buttoninit(void);
+uint8_t up_buttons(void);
#ifdef CONFIG_ARCH_IRQBUTTONS
-EXTERN xcpt_t up_irqbutton(int id, xcpt_t irqhandler);
+xcpt_t up_irqbutton(int id, xcpt_t irqhandler);
#endif
#endif
diff --git a/nuttx/configs/stm32ldiscovery/nsh/defconfig b/nuttx/configs/stm32ldiscovery/nsh/defconfig
index 957962c48..97fdf010b 100644
--- a/nuttx/configs/stm32ldiscovery/nsh/defconfig
+++ b/nuttx/configs/stm32ldiscovery/nsh/defconfig
@@ -406,7 +406,7 @@ CONFIG_USART1_SERIAL_CONSOLE=y
#
CONFIG_USART1_RXBUFSIZE=64
CONFIG_USART1_TXBUFSIZE=64
-CONFIG_USART1_BAUD=115200
+CONFIG_USART1_BAUD=57600
CONFIG_USART1_BITS=8
CONFIG_USART1_PARITY=0
CONFIG_USART1_2STOP=0
diff --git a/nuttx/configs/stm32ldiscovery/src/stm32_userleds.c b/nuttx/configs/stm32ldiscovery/src/stm32_userleds.c
index 710b3f0fc..e556f4f23 100644
--- a/nuttx/configs/stm32ldiscovery/src/stm32_userleds.c
+++ b/nuttx/configs/stm32ldiscovery/src/stm32_userleds.c
@@ -112,7 +112,7 @@ void stm32_setled(int led, bool ledon)
{
ledcfg = GPIO_LED1;
}
- else if (led == BOARD_LED1)
+ else if (led == BOARD_LED2)
{
ledcfg = GPIO_LED2;
}
diff --git a/nuttx/configs/stm32ldiscovery/src/stm32ldiscovery.h b/nuttx/configs/stm32ldiscovery/src/stm32ldiscovery.h
index af0ce96b5..c012b9a08 100644
--- a/nuttx/configs/stm32ldiscovery/src/stm32ldiscovery.h
+++ b/nuttx/configs/stm32ldiscovery/src/stm32ldiscovery.h
@@ -63,20 +63,19 @@
#endif
/* STM32L-Discovery GPIOs ***************************************************************************/
-/* The STM32L-Discovery board has four LEDs. Two of these are controlled by
- * logic on the board and are not available for software control:
+/* The STM32L-Discovery board has four LEDs. Two of these are controlled by logic on the board and
+ * are not available for software control:
*
- * LD1 COM: LD2 default status is red. LD2 turns to green to indicate that
- * communications are in progress between the PC and the ST-LINK/V2.
+ * LD1 COM: LD2 default status is red. LD2 turns to green to indicate that communications are in
+ * progress between the PC and the ST-LINK/V2.
* LD2 PWR: Red LED indicates that the board is powered.
*
* And two LEDs can be controlled by software:
*
- * User LD3: Green LED is a user LED connected to the I/O PB7 of the STM32L152
- * MCU.
- * User LD4: Blue LED is a user LED connected to the I/O PB6 of the STM32L152
- * MCU.
+ * User LD3: Green LED is a user LED connected to the I/O PB7 of the STM32L152 MCU.
+ * User LD4: Blue LED is a user LED connected to the I/O PB6 of the STM32L152 MCU.
*
+ * The other side of the LED connects to ground so high value will illuminate the LED.
*/
#define GPIO_LED1 (GPIO_OUTPUT | GPIO_PUSHPULL | GPIO_SPEED_10MHz | \
@@ -85,8 +84,7 @@
GPIO_OUTPUT_CLEAR | GPIO_PORTB | GPIO_PIN6)
/* Button definitions *******************************************************************************/
-/* The STM32L-Discovery supports two buttons; only one button is controllable by
- * software:
+/* The STM32L-Discovery supports two buttons; only one button is controllable by software:
*
* B1 USER: user and wake-up button connected to the I/O PA0 of the STM32F303VCT6.
* B2 RESET: pushbutton connected to NRST is used to RESET the STM32F303VCT6.