Finish code for basic STM3240 port

git-svn-id: svn://svn.code.sf.net/p/nuttx/code/trunk@4124 42af7a65-404d-4744-a932-0658087f49c3
This commit is contained in:
patacongo 2011-11-24 01:34:10 +00:00
parent 76bb54a502
commit 79b13e12e6
10 changed files with 323 additions and 68 deletions

View File

@ -170,6 +170,8 @@
#define NVIC_IRQ232_235_PRIORITY_OFFSET 0x04e8 /* IRQ 232-235 priority register */
#define NVIC_IRQ236_239_PRIORITY_OFFSET 0x04ec /* IRQ 236-239 priority register */
/* System Control Block (SCB) */
#define NVIC_CPUID_BASE_OFFSET 0x0d00 /* CPUID base register */
#define NVIC_INTCTRL_OFFSET 0x0d04 /* Interrupt control state register */
#define NVIC_VECTAB_OFFSET 0x0d08 /* Vector table offset register */
@ -200,6 +202,7 @@
#define NVIC_ISAR2_OFFSET 0x0d68 /* ISA feature register 2 */
#define NVIC_ISAR3_OFFSET 0x0d6c /* ISA feature register 3 */
#define NVIC_ISAR4_OFFSET 0x0d70 /* ISA feature register 4 */
#define NVIC_CPACR_OFFSET 0x0d88 /* Coprocessor Access Control Register */
#define NVIC_STIR_OFFSET 0x0f00 /* Software trigger interrupt register */
#define NVIC_PID4_OFFSET 0x0fd0 /* Peripheral identification register (PID4) */
#define NVIC_PID5_OFFSET 0x0fd4 /* Peripheral identification register (PID5) */
@ -363,6 +366,7 @@
#define NVIC_ISAR2 (ARMV7M_NVIC_BASE + NVIC_ISAR2_OFFSET)
#define NVIC_ISAR3 (ARMV7M_NVIC_BASE + NVIC_ISAR3_OFFSET)
#define NVIC_ISAR4 (ARMV7M_NVIC_BASE + NVIC_ISAR4_OFFSET)
#define NVIC_CPACR (ARMV7M_NVIC_BASE + NVIC_CPACR_OFFSET)
#define NVIC_STIR (ARMV7M_NVIC_BASE + NVIC_STIR_OFFSET)
#define NVIC_PID4 (ARMV7M_NVIC_BASE + NVIC_PID4_OFFSET)
#define NVIC_PID5 (ARMV7M_NVIC_BASE + NVIC_PID5_OFFSET)

View File

@ -36,7 +36,7 @@
HEAD_ASRC = stm32_vectors.S
CMN_ASRCS = up_saveusercontext.S up_fullcontextrestore.S up_switchcontext.S
CMN_CSRCS = up_allocateheap.c up_assert.c up_blocktask.c up_copystate.c \
CMN_CSRCS = up_assert.c up_blocktask.c up_copystate.c \
up_createstack.c up_mdelay.c up_udelay.c up_exit.c \
up_initialize.c up_initialstate.c up_interruptcontext.c \
up_memfault.c up_modifyreg8.c up_modifyreg16.c up_modifyreg32.c \
@ -49,10 +49,11 @@ CMN_CSRCS += up_checkstack.c
endif
CHIP_ASRCS =
CHIP_CSRCS = stm32_start.c stm32_rcc.c stm32_gpio.c stm32_exti.c stm32_flash.c \
stm32_irq.c stm32_timerisr.c stm32_dma.c stm32_lowputc.c \
stm32_serial.c stm32_spi.c stm32_usbdev.c stm32_sdio.c \
stm32_tim.c stm32_i2c.c stm32_pwr.c stm32_idle.c stm32_waste.c
CHIP_CSRCS = stm32_allocateheap.c stm32_start.c stm32_rcc.c stm32_lse.c \
stm32_gpio.c stm32_exti.c stm32_flash.c stm32_irq.c \
stm32_timerisr.c stm32_dma.c stm32_lowputc.c stm32_serial.c \
stm32_spi.c stm32_usbdev.c stm32_sdio.c stm32_tim.c stm32_i2c.c \
stm32_pwr.c stm32_idle.c stm32_waste.c
ifeq ($(CONFIG_STM32_RCCLOCK),y)
CHIP_CSRCS += stm32_rcclock.c

View File

@ -512,10 +512,10 @@
#define GPIO_USART1_CK (GPIO_ALT|GPIO_AF7|GPIO_PORTA|GPIO_PIN8)
#define GPIO_USART1_CTS (GPIO_ALT|GPIO_AF7|GPIO_PORTA|GPIO_PIN11)
#define GPIO_USART1_RTS (GPIO_ALT|GPIO_AF7|GPIO_PORTA|GPIO_PIN12)
#define GPIO_USART1_RX_1 (GPIO_ALT|GPIO_AF7|GPIO_PORTA|GPIO_PIN10)
#define GPIO_USART1_RX_2 (GPIO_ALT|GPIO_AF7|GPIO_PORTB|GPIO_PIN7)
#define GPIO_USART1_TX_1 (GPIO_ALT|GPIO_AF7|GPIO_PORTA|GPIO_PIN9)
#define GPIO_USART1_TX_2 (GPIO_ALT|GPIO_AF7|GPIO_PORTB|GPIO_PIN6)
#define GPIO_USART1_RX_1 (GPIO_ALT|GPIO_AF7|GPIO_PULLUP|GPIO_SPEED_100MHz|GPIO_PUSHPULL|GPIO_PORTA|GPIO_PIN10)
#define GPIO_USART1_RX_2 (GPIO_ALT|GPIO_AF7|GPIO_PULLUP|GPIO_SPEED_100MHz|GPIO_PUSHPULL|GPIO_PORTB|GPIO_PIN7)
#define GPIO_USART1_TX_1 (GPIO_ALT|GPIO_AF7|GPIO_PULLUP|GPIO_SPEED_100MHz|GPIO_PUSHPULL|GPIO_PORTA|GPIO_PIN9)
#define GPIO_USART1_TX_2 (GPIO_ALT|GPIO_AF7|GPIO_PULLUP|GPIO_SPEED_100MHz|GPIO_PUSHPULL|GPIO_PORTB|GPIO_PIN6)
#define GPIO_USART2_CK_1 (GPIO_ALT|GPIO_AF7|GPIO_PORTA|GPIO_PIN4)
#define GPIO_USART2_CK_2 (GPIO_ALT|GPIO_AF7|GPIO_PORTD|GPIO_PIN7)
@ -523,10 +523,10 @@
#define GPIO_USART2_CTS_2 (GPIO_ALT|GPIO_AF7|GPIO_PORTD|GPIO_PIN3)
#define GPIO_USART2_RTS_1 (GPIO_ALT|GPIO_AF7|GPIO_PORTA|GPIO_PIN1)
#define GPIO_USART2_RTS_2 (GPIO_ALT|GPIO_AF7|GPIO_PORTD|GPIO_PIN4)
#define GPIO_USART2_RX_1 (GPIO_ALT|GPIO_AF7|GPIO_PORTA|GPIO_PIN3)
#define GPIO_USART2_RX_2 (GPIO_ALT|GPIO_AF7|GPIO_PORTD|GPIO_PIN6)
#define GPIO_USART2_TX_1 (GPIO_ALT|GPIO_AF7|GPIO_PORTA|GPIO_PIN2)
#define GPIO_USART2_TX_2 (GPIO_ALT|GPIO_AF7|GPIO_PORTD|GPIO_PIN5)
#define GPIO_USART2_RX_1 (GPIO_ALT|GPIO_AF7|GPIO_PULLUP|GPIO_SPEED_100MHz|GPIO_PUSHPULL|GPIO_PORTA|GPIO_PIN3)
#define GPIO_USART2_RX_2 (GPIO_ALT|GPIO_AF7|GPIO_PULLUP|GPIO_SPEED_100MHz|GPIO_PUSHPULL|GPIO_PORTD|GPIO_PIN6)
#define GPIO_USART2_TX_1 (GPIO_ALT|GPIO_AF7|GPIO_PULLUP|GPIO_SPEED_100MHz|GPIO_PUSHPULL|GPIO_PORTA|GPIO_PIN2)
#define GPIO_USART2_TX_2 (GPIO_ALT|GPIO_AF7|GPIO_PULLUP|GPIO_SPEED_100MHz|GPIO_PUSHPULL|GPIO_PORTD|GPIO_PIN5)
#define GPIO_USART3_CK_1 (GPIO_ALT|GPIO_AF7|GPIO_PORTB|GPIO_PIN12)
#define GPIO_USART3_CK_2 (GPIO_ALT|GPIO_AF7|GPIO_PORTC|GPIO_PIN12)
@ -535,20 +535,20 @@
#define GPIO_USART3_CTS_2 (GPIO_ALT|GPIO_AF7|GPIO_PORTD|GPIO_PIN11)
#define GPIO_USART3_RTS_1 (GPIO_ALT|GPIO_AF7|GPIO_PORTB|GPIO_PIN14)
#define GPIO_USART3_RTS_2 (GPIO_ALT|GPIO_AF7|GPIO_PORTD|GPIO_PIN12)
#define GPIO_USART3_RX_1 (GPIO_ALT|GPIO_AF7|GPIO_PORTB|GPIO_PIN11)
#define GPIO_USART3_RX_2 (GPIO_ALT|GPIO_AF7|GPIO_PORTC|GPIO_PIN11)
#define GPIO_USART3_RX_3 (GPIO_ALT|GPIO_AF7|GPIO_PORTD|GPIO_PIN9)
#define GPIO_USART3_TX_1 (GPIO_ALT|GPIO_AF7|GPIO_PORTB|GPIO_PIN10)
#define GPIO_USART3_TX_2 (GPIO_ALT|GPIO_AF7|GPIO_PORTC|GPIO_PIN10)
#define GPIO_USART3_TX_3 (GPIO_ALT|GPIO_AF7|GPIO_PORTD|GPIO_PIN8)
#define GPIO_USART3_RX_1 (GPIO_ALT|GPIO_AF7|GPIO_PULLUP|GPIO_SPEED_100MHz|GPIO_PUSHPULL|GPIO_PORTB|GPIO_PIN11)
#define GPIO_USART3_RX_2 (GPIO_ALT|GPIO_AF7|GPIO_PULLUP|GPIO_SPEED_100MHz|GPIO_PUSHPULL|GPIO_PORTC|GPIO_PIN11)
#define GPIO_USART3_RX_3 (GPIO_ALT|GPIO_AF7|GPIO_PULLUP|GPIO_SPEED_100MHz|GPIO_PUSHPULL|GPIO_PORTD|GPIO_PIN9)
#define GPIO_USART3_TX_1 (GPIO_ALT|GPIO_AF7|GPIO_PULLUP|GPIO_SPEED_100MHz|GPIO_PUSHPULL|GPIO_PORTB|GPIO_PIN10)
#define GPIO_USART3_TX_2 (GPIO_ALT|GPIO_AF7|GPIO_PULLUP|GPIO_SPEED_100MHz|GPIO_PUSHPULL|GPIO_PORTC|GPIO_PIN10)
#define GPIO_USART3_TX_3 (GPIO_ALT|GPIO_AF7|GPIO_PULLUP|GPIO_SPEED_100MHz|GPIO_PUSHPULL|GPIO_PORTD|GPIO_PIN8)
#define GPIO_UART4_RX_1 (GPIO_ALT|GPIO_AF8|GPIO_PORTA|GPIO_PIN1)
#define GPIO_UART4_RX_2 (GPIO_ALT|GPIO_AF8|GPIO_PORTC|GPIO_PIN11)
#define GPIO_UART4_TX_1 (GPIO_ALT|GPIO_AF8|GPIO_PORTA|GPIO_PIN0)
#define GPIO_UART4_TX_2 (GPIO_ALT|GPIO_AF8|GPIO_PORTC|GPIO_PIN10)
#define GPIO_UART4_RX_1 (GPIO_ALT|GPIO_AF8|GPIO_PULLUP|GPIO_SPEED_100MHz|GPIO_PUSHPULL|GPIO_PORTA|GPIO_PIN1)
#define GPIO_UART4_RX_2 (GPIO_ALT|GPIO_AF8|GPIO_PULLUP|GPIO_SPEED_100MHz|GPIO_PUSHPULL|GPIO_PORTC|GPIO_PIN11)
#define GPIO_UART4_TX_1 (GPIO_ALT|GPIO_AF8|GPIO_PULLUP|GPIO_SPEED_100MHz|GPIO_PUSHPULL|GPIO_PORTA|GPIO_PIN0)
#define GPIO_UART4_TX_2 (GPIO_ALT|GPIO_AF8|GPIO_PULLUP|GPIO_SPEED_100MHz|GPIO_PUSHPULL|GPIO_PORTC|GPIO_PIN10)
#define GPIO_UART5_RX (GPIO_ALT|GPIO_AF8|GPIO_PORTD|GPIO_PIN2)
#define GPIO_UART5_TX (GPIO_ALT|GPIO_AF8|GPIO_PORTC|GPIO_PIN12)
#define GPIO_UART5_RX (GPIO_ALT|GPIO_AF8|GPIO_PULLUP|GPIO_SPEED_100MHz|GPIO_PUSHPULL|GPIO_PORTD|GPIO_PIN2)
#define GPIO_UART5_TX (GPIO_ALT|GPIO_AF8|GPIO_PULLUP|GPIO_SPEED_100MHz|GPIO_PUSHPULL|GPIO_PORTC|GPIO_PIN12)
#define GPIO_USART6_CK_1 (GPIO_ALT|GPIO_AF8|GPIO_PORTC|GPIO_PIN8)
#define GPIO_USART6_CK_2 (GPIO_ALT|GPIO_AF8|GPIO_PORTG|GPIO_PIN7)
@ -556,10 +556,10 @@
#define GPIO_USART6_CTS_2 (GPIO_ALT|GPIO_AF8|GPIO_PORTG|GPIO_PIN15)
#define GPIO_USART6_RTS_1 (GPIO_ALT|GPIO_AF8|GPIO_PORTG|GPIO_PIN12)
#define GPIO_USART6_RTS_2 (GPIO_ALT|GPIO_AF8|GPIO_PORTG|GPIO_PIN8)
#define GPIO_USART6_RX_1 (GPIO_ALT|GPIO_AF8|GPIO_PORTC|GPIO_PIN7)
#define GPIO_USART6_RX_2 (GPIO_ALT|GPIO_AF8|GPIO_PORTG|GPIO_PIN9)
#define GPIO_USART6_TX_1 (GPIO_ALT|GPIO_AF8|GPIO_PORTC|GPIO_PIN6)
#define GPIO_USART6_TX_2 (GPIO_ALT|GPIO_AF8|GPIO_PORTG|GPIO_PIN14)
#define GPIO_USART6_RX_1 (GPIO_ALT|GPIO_AF8|GPIO_PULLUP|GPIO_SPEED_100MHz|GPIO_PUSHPULL|GPIO_PORTC|GPIO_PIN7)
#define GPIO_USART6_RX_2 (GPIO_ALT|GPIO_AF8|GPIO_PULLUP|GPIO_SPEED_100MHz|GPIO_PUSHPULL|GPIO_PORTG|GPIO_PIN9)
#define GPIO_USART6_TX_1 (GPIO_ALT|GPIO_AF8|GPIO_PULLUP|GPIO_SPEED_100MHz|GPIO_PUSHPULL|GPIO_PORTC|GPIO_PIN6)
#define GPIO_USART6_TX_2 (GPIO_ALT|GPIO_AF8|GPIO_PULLUP|GPIO_SPEED_100MHz|GPIO_PUSHPULL|GPIO_PORTG|GPIO_PIN14)
#endif /* __ARCH_ARM_SRC_STM32_CHIP_STM32F40XXX_PINMAP_H */

View File

@ -0,0 +1,161 @@
/****************************************************************************
* arch/arm/src/stm32/up_allocateheap.c
*
* Copyright (C) 2011 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <gnutt@nuttx.org>
*
* 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 <sys/types.h>
#include <debug.h>
#include <nuttx/arch.h>
#include <arch/board/board.h>
#include "chip.h"
#include "up_arch.h"
#include "up_internal.h"
/****************************************************************************
* Private Definitions
****************************************************************************/
/* For the STM312F10xxx family, all SRAM is in a contiguous block starting
* at g_heapbase and extending through CONFIG_DRAM_END (my apologies for
* the bad naming).
*/
#if defined(CONFIG_STM32_STM32F10XX)
# define SRAM1_END CONFIG_DRAM_END
/* All members of the STM32F40xxx family have 192Kb in three banks:
*
* 1) 112Kb of SRAM beginning at address 0x2000:0000
* 2) 16Kb of SRAM beginning at address 0x2001:c000
* 3) 64Kb of TCM SRAM beginning at address 0x1000:0000
*
* As determined by ld.script, g_heapbase lies in the 112Kb memory
* region and that extends to 0x2001:0000. But the first and second memory
* regions are contiguous and treated as one in this logic that extends to
* 0x2002:0000.
*/
#elif defined(CONFIG_STM32_STM32F40XX)
# define SRAM1_END 0x20020000
# define SRAM2_START 0x10000000
# define SRAM2_END 0x10010000
#else
# error "Unsupported STM32 chip"
#endif
/****************************************************************************
* Private Data
****************************************************************************/
/****************************************************************************
* Private Functions
****************************************************************************/
/****************************************************************************
* Public Functions
****************************************************************************/
/****************************************************************************
* Name: up_allocate_heap
*
* Description:
* The heap may be statically allocated by
* defining CONFIG_HEAP_BASE and CONFIG_HEAP_SIZE. If these
* are not defined, then this function will be called to
* dynamically set aside the heap region.
*
****************************************************************************/
void up_allocate_heap(FAR void **heap_start, size_t *heap_size)
{
up_ledon(LED_HEAPALLOCATE);
*heap_start = (FAR void*)g_heapbase;
*heap_size = SRAM1_END - g_heapbase;
}
/****************************************************************************
* Name: up_addregion
*
* Description:
* Memory may be added in non-contiguous chunks. Additional chunks are
* added by calling this function.
*
****************************************************************************/
#if CONFIG_MM_REGIONS > 1
# if defined(CONFIG_STM32_STM32F40XX)
# if defined(CONFIG_HEAP2_BASE) && defined(CONFIG_HEAP2_END)
# if CONFIG_MM_REGIONS > 3
# error "CONFIG_MM_REGIONS > 3 but I don't know what all of the regions are"
# endif
# elif CONFIG_MM_REGIONS > 2
# error "CONFIG_MM_REGIONS > 2 but I don't know what all of the regions are"
# endif
void up_addregion(void)
{
/* Add the STM32F40xxx TCM SRAM heap region. */
mm_addregion((FAR void*)SRAM2_START, SRAM2_END-SRAM2_START);
/* Add the user specified heap region. */
# if CONFIG_MM_REGIONS > 2 && defined(CONFIG_HEAP2_BASE) && defined(CONFIG_HEAP2_END)
mm_addregion((FAR void*)CONFIG_HEAP2_BASE, CONFIG_HEAP2_END - CONFIG_HEAP2_BASE);
# endif
}
# elif defined(CONFIG_HEAP2_BASE) && defined(CONFIG_HEAP2_END)
# if CONFIG_MM_REGIONS > 2
# error "CONFIG_MM_REGIONS > 2 but I don't know what all of the regions are"
# endif
void up_addregion(void)
{
/* Add the user specified heap region. */
mm_addregion((FAR void*)CONFIG_HEAP2_BASE, CONFIG_HEAP2_END - CONFIG_HEAP2_BASE);
}
# else
# error "CONFIG_MM_REGIONS > 1 but I don't know what any of the region(s) are"
# endif
#endif

View File

@ -500,7 +500,7 @@ int stm32_configgpio(uint32_t cfgset)
setting = GPIO_OSPEED_25MHz;
break;
case GPIO_SPEED_20MHz: /* 50 MHz Fast speed output */
case GPIO_SPEED_50MHz: /* 50 MHz Fast speed output */
setting = GPIO_OSPEED_50MHz;
break;

View File

@ -296,7 +296,7 @@ extern "C" {
#define GPIO_SPEED_MASK (3 << GPIO_SPEED_SHIFT)
# define GPIO_SPEED_2MHz (0 << GPIO_SPEED_SHIFT) /* 2 MHz Low speed output */
# define GPIO_SPEED_25MHz (1 << GPIO_SPEED_SHIFT) /* 25 MHz Medium speed output */
# define GPIO_SPEED_20MHz (2 << GPIO_SPEED_SHIFT) /* 50 MHz Fast speed output */
# define GPIO_SPEED_50MHz (2 << GPIO_SPEED_SHIFT) /* 50 MHz Fast speed output */
# define GPIO_SPEED_100MHz (3 << GPIO_SPEED_SHIFT) /* 100 MHz High speed output */
/* Output/Alt function type selection:

View File

@ -0,0 +1,93 @@
/****************************************************************************
* arch/arm/src/stm32/stm32_lse.c
*
* Copyright (C) 2009, 2011 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <spudmonkey@racsa.co.cr>
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
* are met:
*
* 1. Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright
* notice, this list of conditions and the following disclaimer in
* the documentation and/or other materials provided with the
* distribution.
* 3. Neither the name NuttX nor the names of its contributors may be
* used to endorse or promote products derived from this software
* without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
* POSSIBILITY OF SUCH DAMAGE.
*
****************************************************************************/
/****************************************************************************
* Included Files
****************************************************************************/
#include <nuttx/config.h>
#include "up_arch.h"
#include "stm32_rcc.h"
#include "stm32_waste.h"
/****************************************************************************
* Definitions
****************************************************************************/
/****************************************************************************
* Private Data
****************************************************************************/
/****************************************************************************
* Private Functions
****************************************************************************/
/****************************************************************************
* Public Functions
****************************************************************************/
/****************************************************************************
* Name: stm32_rcc_enablelse
*
* Todo:
* Check for LSE good timeout and return with -1,
* possible ISR optimization? or at least ISR should be cough in case of\
* failure
*
****************************************************************************/
void stm32_rcc_enablelse(void)
{
/* Enable LSE */
modifyreg16(STM32_RCC_BDCR, 0, RCC_BDCR_LSEON);
/* We could wait for ISR here ... */
while ((getreg16(STM32_RCC_BDCR) & RCC_BDCR_LSERDY) == 0)
{
up_waste();
}
/* Select LSE as RTC Clock Source */
modifyreg16(STM32_RCC_BDCR, RCC_BDCR_RTCSEL_MASK, RCC_BDCR_RTCSEL_LSE);
/* Enable Clock */
modifyreg16(STM32_RCC_BDCR, 0, RCC_BDCR_RTCEN);
}

View File

@ -49,6 +49,9 @@
#include "stm32_internal.h"
#include "stm32_gpio.h"
#ifdef CONFIG_ARCH_FPU
# include "nvic.h"
#endif
/****************************************************************************
* Name: showprogress
@ -64,6 +67,33 @@
# define showprogress(c)
#endif
/****************************************************************************
* Public Functions
****************************************************************************/
/****************************************************************************
* Name: stm32_fpuconfig
*
* Description:
* Configure the FPU. The the MCU has an FPU, then enable full access
* to coprocessors CP10 and CP11.
*
* This is implemented as a macro because the stack has not yet been
* initialized.
*
****************************************************************************/
#ifdef CONFIG_ARCH_FPU
# define stm32_fpuconfig() \
{ \
uint32_t regval = getreg32(NVIC_CPACR); \
regval |= ((3 << (2*10)) | (3 << (2*11))); \
putreg32(regval, NVIC_CPACR); \
}
#else
# define stm32_fpuconfig()
#endif
/****************************************************************************
* Public Functions
****************************************************************************/
@ -84,6 +114,7 @@ void __start(void)
/* Configure the uart so that we can get debug output as soon as possible */
stm32_clockconfig();
stm32_fpuconfig();
stm32_lowsetup();
stm32_gpioinit();
showprogress('A');

View File

@ -36,13 +36,7 @@
#ifndef __ARCH_ARM_SRC_STM32_STM32_WASTE_H
#define __ARCH_ARM_SRC_STM32_STM32_WASTE_H
/** \file
* \author Uros Platise
* \brief Waste CPU Time
*
* \addtogroup STM32_WASTE
* \{
*/
/* Waste CPU Time */
/****************************************************************************
* Pre-processor Definitions
@ -58,7 +52,6 @@ extern "C" {
#define EXTERN extern
#endif
/****************************************************************************
* Public Functions
****************************************************************************/
@ -76,10 +69,10 @@ extern "C" {
EXTERN void up_waste(void);
#undef EXTERN
#if defined(__cplusplus)
}
#endif
#endif /* __ASSEMBLY__ */
#endif /* __ARCH_ARM_SRC_STM32_STM32_RRC_H */

View File

@ -512,31 +512,3 @@ static inline void rcc_enableperipherals(void)
/****************************************************************************
* Public Functions
****************************************************************************/
/****************************************************************************
* Name: stm32_rcc_enablelse
*
* Todo:
* Check for LSE good timeout and return with -1,
* possible ISR optimization? or at least ISR should be cough in case of failure
*
****************************************************************************/
void stm32_rcc_enablelse(void)
{
/* Enable LSE */
modifyreg16(STM32_RCC_BDCR, 0, RCC_BDCR_LSEON);
/* We could wait for ISR here ... */
while( !(getreg16(STM32_RCC_BDCR) & RCC_BDCR_LSERDY) ) up_waste();
/* Select LSE as RTC Clock Source */
modifyreg16(STM32_RCC_BDCR, RCC_BDCR_RTCSEL_MASK, RCC_BDCR_RTCSEL_LSE);
/* Enable Clock */
modifyreg16(STM32_RCC_BDCR, 0, RCC_BDCR_RTCEN);
}