From fee72530476c5b9eed43fde792df9de367d56800 Mon Sep 17 00:00:00 2001 From: gdisirio Date: Thu, 13 May 2010 14:02:17 +0000 Subject: git-svn-id: svn://svn.code.sf.net/p/chibios/svn/trunk@1915 35acf78f-673a-0410-8e92-d51de3d6d3f4 --- boards/OLIMEX_STM32_P103/board.h | 6 + boards/ST_STM3210C_EVAL/board.c | 49 +++ boards/ST_STM3210C_EVAL/board.h | 113 +++++++ boards/ST_STM3210C_EVAL/board.mk | 5 + demos/ARMCM3-STM32F103-FATFS-GCC/Makefile | 2 +- demos/ARMCM3-STM32F103-FATFS-GCC/mcuconf.h | 6 +- demos/ARMCM3-STM32F103-FATFS-GCC/readme.txt | 2 +- demos/ARMCM3-STM32F103-GCC/Makefile | 2 +- demos/ARMCM3-STM32F103-GCC/mcuconf.h | 6 +- demos/ARMCM3-STM32F103-GCC/readme.txt | 2 +- demos/ARMCM3-STM32F107-GCC/Makefile | 205 ++++++++++++ demos/ARMCM3-STM32F107-GCC/ch.ld | 94 ++++++ demos/ARMCM3-STM32F107-GCC/chconf.h | 483 ++++++++++++++++++++++++++++ demos/ARMCM3-STM32F107-GCC/halconf.h | 152 +++++++++ demos/ARMCM3-STM32F107-GCC/main.c | 69 ++++ demos/ARMCM3-STM32F107-GCC/mcuconf.h | 102 ++++++ demos/ARMCM3-STM32F107-GCC/readme.txt | 25 ++ os/hal/platforms/STM32/hal_lld.c | 100 +++++- os/hal/platforms/STM32/hal_lld_F107.h | 161 +++++----- os/hal/platforms/STM32/hal_lld_F10x.h | 43 +-- readme.txt | 11 +- testhal/STM32/mcuconf.h | 12 +- 22 files changed, 1529 insertions(+), 121 deletions(-) create mode 100644 boards/ST_STM3210C_EVAL/board.c create mode 100644 boards/ST_STM3210C_EVAL/board.h create mode 100644 boards/ST_STM3210C_EVAL/board.mk create mode 100644 demos/ARMCM3-STM32F107-GCC/Makefile create mode 100644 demos/ARMCM3-STM32F107-GCC/ch.ld create mode 100644 demos/ARMCM3-STM32F107-GCC/chconf.h create mode 100644 demos/ARMCM3-STM32F107-GCC/halconf.h create mode 100644 demos/ARMCM3-STM32F107-GCC/main.c create mode 100644 demos/ARMCM3-STM32F107-GCC/mcuconf.h create mode 100644 demos/ARMCM3-STM32F107-GCC/readme.txt diff --git a/boards/OLIMEX_STM32_P103/board.h b/boards/OLIMEX_STM32_P103/board.h index 7ad0ffa7e..31fa3419c 100644 --- a/boards/OLIMEX_STM32_P103/board.h +++ b/boards/OLIMEX_STM32_P103/board.h @@ -36,6 +36,12 @@ #define STM32_LSECLK 32768 #define STM32_HSECLK 8000000 +/* + * MCU type, this macro is used by both the ST library and the ChibiOS/RT + * native STM32 HAL. + */ +#define STM32F10X_MD + /* * IO pins assignments. */ diff --git a/boards/ST_STM3210C_EVAL/board.c b/boards/ST_STM3210C_EVAL/board.c new file mode 100644 index 000000000..77f958101 --- /dev/null +++ b/boards/ST_STM3210C_EVAL/board.c @@ -0,0 +1,49 @@ +/* + ChibiOS/RT - Copyright (C) 2006,2007,2008,2009,2010 Giovanni Di Sirio. + + This file is part of ChibiOS/RT. + + ChibiOS/RT is free software; you can redistribute it and/or modify + it under the terms of the GNU General Public License as published by + the Free Software Foundation; either version 3 of the License, or + (at your option) any later version. + + ChibiOS/RT is distributed in the hope that it will be useful, + but WITHOUT ANY WARRANTY; without even the implied warranty of + MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + GNU General Public License for more details. + + You should have received a copy of the GNU General Public License + along with this program. If not, see . +*/ + +#include "ch.h" +#include "hal.h" + +/* + * Early initialization code. + * This initialization is performed just after reset before BSS and DATA + * segments initialization. + */ +void hwinit0(void) { + + stm32_clock_init(); +} + +/* + * Late initialization code. + * This initialization is performed after BSS and DATA segments initialization + * and before invoking the main() function. + */ +void hwinit1(void) { + + /* + * HAL initialization. + */ + halInit(); + + /* + * ChibiOS/RT initialization. + */ + chSysInit(); +} diff --git a/boards/ST_STM3210C_EVAL/board.h b/boards/ST_STM3210C_EVAL/board.h new file mode 100644 index 000000000..f6e623335 --- /dev/null +++ b/boards/ST_STM3210C_EVAL/board.h @@ -0,0 +1,113 @@ +/* + ChibiOS/RT - Copyright (C) 2006,2007,2008,2009,2010 Giovanni Di Sirio. + + This file is part of ChibiOS/RT. + + ChibiOS/RT is free software; you can redistribute it and/or modify + it under the terms of the GNU General Public License as published by + the Free Software Foundation; either version 3 of the License, or + (at your option) any later version. + + ChibiOS/RT is distributed in the hope that it will be useful, + but WITHOUT ANY WARRANTY; without even the implied warranty of + MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + GNU General Public License for more details. + + You should have received a copy of the GNU General Public License + along with this program. If not, see . +*/ + +#ifndef _BOARD_H_ +#define _BOARD_H_ + +/* + * Setup for the STMicroelectronics STM3210C-EVAL evaluation board. + */ + +/* + * Board identifier. + */ +#define BOARD_ST_STM3210C_EVAL +#define BOARD_NAME "ST STM3210C-EVAL" + +/* + * Board frequencies. + */ +#define STM32_LSECLK 32768 +#define STM32_HSECLK 25000000 + +/* + * MCU type, this macro is used by both the ST library and the ChibiOS/RT + * native STM32 HAL. + */ +#define STM32F10X_CL + +/* + * IO pins assignments. + * *********************TO BE COMPLETED********************* + */ + +/* + * I/O ports initial setup, this configuration is established soon after reset + * in the initialization code. + * + * The digits have the following meaning: + * 0 - Analog input. + * 1 - Push Pull output 10MHz. + * 2 - Push Pull output 2MHz. + * 3 - Push Pull output 50MHz. + * 4 - Digital input. + * 5 - Open Drain output 10MHz. + * 6 - Open Drain output 2MHz. + * 7 - Open Drain output 50MHz. + * 8 - Digital input with PullUp or PullDown resistor depending on ODR. + * 9 - Alternate Push Pull output 10MHz. + * A - Alternate Push Pull output 2MHz. + * B - Alternate Push Pull output 50MHz. + * C - Reserved. + * D - Alternate Open Drain output 10MHz. + * E - Alternate Open Drain output 2MHz. + * F - Alternate Open Drain output 50MHz. + * Please refer to the STM32 Reference Manual for details. + */ + +/* + * Port A setup. + * Everything input with pull-up except: + */ +#define VAL_GPIOACRL 0x88888888 /* PA7...PA0 */ +#define VAL_GPIOACRH 0x88888888 /* PA15...PA8 */ +#define VAL_GPIOAODR 0xFFFFFFFF + +/* + * Port B setup. + * Everything input with pull-up except: + */ +#define VAL_GPIOBCRL 0x88888888 /* PB7...PB0 */ +#define VAL_GPIOBCRH 0x88888888 /* PB15...PB8 */ +#define VAL_GPIOBODR 0xFFFFFFFF + +/* + * Port C setup. + * Everything input with pull-up except: + */ +#define VAL_GPIOCCRL 0x88888888 /* PC7...PC0 */ +#define VAL_GPIOCCRH 0x88888888 /* PC15...PC8 */ +#define VAL_GPIOCODR 0xFFFFFFFF + +/* + * Port D setup. + * Everything input with pull-up except: + */ +#define VAL_GPIODCRL 0x88888888 /* PD7...PD0 */ +#define VAL_GPIODCRH 0x88888888 /* PD15...PD8 */ +#define VAL_GPIODODR 0xFFFFFFFF + +/* + * Port E setup. + */ +#define VAL_GPIOECRL 0x88888888 /* PE7...PE0 */ +#define VAL_GPIOECRH 0x88888888 /* PE15...PE8 */ +#define VAL_GPIOEODR 0xFFFFFFFF + +#endif /* _BOARD_H_ */ diff --git a/boards/ST_STM3210C_EVAL/board.mk b/boards/ST_STM3210C_EVAL/board.mk new file mode 100644 index 000000000..eaa17162b --- /dev/null +++ b/boards/ST_STM3210C_EVAL/board.mk @@ -0,0 +1,5 @@ +# List of all the board related files. +BOARDSRC = ${CHIBIOS}/boards/ST_STM3210C_EVAL/board.c + +# Required include directories +BOARDINC = ${CHIBIOS}/boards/ST_STM3210C_EVAL diff --git a/demos/ARMCM3-STM32F103-FATFS-GCC/Makefile b/demos/ARMCM3-STM32F103-FATFS-GCC/Makefile index 22e059a39..a1c7a5668 100644 --- a/demos/ARMCM3-STM32F103-FATFS-GCC/Makefile +++ b/demos/ARMCM3-STM32F103-FATFS-GCC/Makefile @@ -157,7 +157,7 @@ CPPWARN = -Wall -Wextra # # List all default C defines here, like -D_DEBUG=1 -DDEFS = -DSTM32F10X_MD -DSTDOUT_SD=SD2 -DSTDIN_SD=SD2 +DDEFS = -DSTDOUT_SD=SD2 -DSTDIN_SD=SD2 # List all default ASM defines here, like -D_DEBUG=1 DADEFS = diff --git a/demos/ARMCM3-STM32F103-FATFS-GCC/mcuconf.h b/demos/ARMCM3-STM32F103-FATFS-GCC/mcuconf.h index b4b44dd33..511460ac4 100644 --- a/demos/ARMCM3-STM32F103-FATFS-GCC/mcuconf.h +++ b/demos/ARMCM3-STM32F103-FATFS-GCC/mcuconf.h @@ -37,7 +37,11 @@ #define STM32_SW STM32_SW_PLL #define STM32_PLLSRC STM32_PLLSRC_HSE #define STM32_PLLXTPRE STM32_PLLXTPRE_DIV1 -#define STM32_PLLCLKOUT 72000000 +#define STM32_PLLMUL_VALUE 9 +#define STM32_HPRE STM32_HPRE_DIV1 +#define STM32_PPRE1 STM32_PPRE1_DIV2 +#define STM32_PPRE2 STM32_PPRE2_DIV2 +#define STM32_ADCPRE STM32_ADCPRE_DIV4 /* * ADC driver system settings. diff --git a/demos/ARMCM3-STM32F103-FATFS-GCC/readme.txt b/demos/ARMCM3-STM32F103-FATFS-GCC/readme.txt index 619e89aa5..4178478bb 100644 --- a/demos/ARMCM3-STM32F103-FATFS-GCC/readme.txt +++ b/demos/ARMCM3-STM32F103-FATFS-GCC/readme.txt @@ -4,7 +4,7 @@ ** TARGET ** -The demo will on an Olimex STM32-P103 board. +The demo runs on an Olimex STM32-P103 board. ** The Demo ** diff --git a/demos/ARMCM3-STM32F103-GCC/Makefile b/demos/ARMCM3-STM32F103-GCC/Makefile index 59949cd15..623ddc8ee 100644 --- a/demos/ARMCM3-STM32F103-GCC/Makefile +++ b/demos/ARMCM3-STM32F103-GCC/Makefile @@ -154,7 +154,7 @@ CPPWARN = -Wall -Wextra # # List all default C defines here, like -D_DEBUG=1 -DDEFS = -DSTM32F10X_MD -DCORTEX_USE_BASEPRI=TRUE +DDEFS = -DCORTEX_USE_BASEPRI=TRUE # List all default ASM defines here, like -D_DEBUG=1 DADEFS = diff --git a/demos/ARMCM3-STM32F103-GCC/mcuconf.h b/demos/ARMCM3-STM32F103-GCC/mcuconf.h index b4b44dd33..511460ac4 100644 --- a/demos/ARMCM3-STM32F103-GCC/mcuconf.h +++ b/demos/ARMCM3-STM32F103-GCC/mcuconf.h @@ -37,7 +37,11 @@ #define STM32_SW STM32_SW_PLL #define STM32_PLLSRC STM32_PLLSRC_HSE #define STM32_PLLXTPRE STM32_PLLXTPRE_DIV1 -#define STM32_PLLCLKOUT 72000000 +#define STM32_PLLMUL_VALUE 9 +#define STM32_HPRE STM32_HPRE_DIV1 +#define STM32_PPRE1 STM32_PPRE1_DIV2 +#define STM32_PPRE2 STM32_PPRE2_DIV2 +#define STM32_ADCPRE STM32_ADCPRE_DIV4 /* * ADC driver system settings. diff --git a/demos/ARMCM3-STM32F103-GCC/readme.txt b/demos/ARMCM3-STM32F103-GCC/readme.txt index 353dd2658..5329bfb35 100644 --- a/demos/ARMCM3-STM32F103-GCC/readme.txt +++ b/demos/ARMCM3-STM32F103-GCC/readme.txt @@ -4,7 +4,7 @@ ** TARGET ** -The demo will on an Olimex STM32-P103 board. +The demo runs on an Olimex STM32-P103 board. ** The Demo ** diff --git a/demos/ARMCM3-STM32F107-GCC/Makefile b/demos/ARMCM3-STM32F107-GCC/Makefile new file mode 100644 index 000000000..f8767cfdf --- /dev/null +++ b/demos/ARMCM3-STM32F107-GCC/Makefile @@ -0,0 +1,205 @@ +############################################################################## +# Build global options +# NOTE: Can be overridden externally. +# + +# Compiler options here. +ifeq ($(USE_OPT),) + USE_OPT = -O2 -ggdb -fomit-frame-pointer -mabi=apcs-gnu -falign-functions=16 +endif + +# C++ specific options here (added to USE_OPT). +ifeq ($(USE_CPPOPT),) + USE_CPPOPT = -fno-rtti +endif + +# Enable this if you want the linker to remove unused code and data +ifeq ($(USE_LINK_GC),) + USE_LINK_GC = yes +endif + +# If enabled, this option allows to compile the application in THUMB mode. +ifeq ($(USE_THUMB),) + USE_THUMB = yes +endif + +# Enable register caching optimization (read documentation). +ifeq ($(USE_CURRP_CACHING),) + USE_CURRP_CACHING = no +endif + +# +# Build global options +############################################################################## + +############################################################################## +# Architecture or project specific options +# + +# Enable this if you really want to use the STM FWLib. +ifeq ($(USE_FWLIB),) + USE_FWLIB = no +endif + +# +# Architecture or project specific options +############################################################################## + +############################################################################## +# Project, sources and paths +# + +# Define project name here +PROJECT = ch + +# Define linker script file here +LDSCRIPT= ch.ld + +# Imported source files +CHIBIOS = ../.. +include $(CHIBIOS)/boards/ST_STM3210C_EVAL/board.mk +include $(CHIBIOS)/os/hal/platforms/STM32/platform.mk +include $(CHIBIOS)/os/hal/hal.mk +include $(CHIBIOS)/os/ports/GCC/ARMCMx/STM32F10x/port.mk +include $(CHIBIOS)/os/kernel/kernel.mk +include $(CHIBIOS)/test/test.mk + +# C sources that can be compiled in ARM or THUMB mode depending on the global +# setting. +CSRC = $(PORTSRC) \ + $(KERNSRC) \ + $(TESTSRC) \ + $(HALSRC) \ + $(PLATFORMSRC) \ + $(BOARDSRC) \ + $(CHIBIOS)/os/various/evtimer.c \ + $(CHIBIOS)/os/various/syscalls.c \ + main.c + +# C++ sources that can be compiled in ARM or THUMB mode depending on the global +# setting. +CPPSRC = + +# C sources to be compiled in ARM mode regardless of the global setting. +# NOTE: Mixing ARM and THUMB mode enables the -mthumb-interwork compiler +# option that results in lower performance and larger code size. +ACSRC = + +# C++ sources to be compiled in ARM mode regardless of the global setting. +# NOTE: Mixing ARM and THUMB mode enables the -mthumb-interwork compiler +# option that results in lower performance and larger code size. +ACPPSRC = + +# C sources to be compiled in THUMB mode regardless of the global setting. +# NOTE: Mixing ARM and THUMB mode enables the -mthumb-interwork compiler +# option that results in lower performance and larger code size. +TCSRC = + +# C sources to be compiled in THUMB mode regardless of the global setting. +# NOTE: Mixing ARM and THUMB mode enables the -mthumb-interwork compiler +# option that results in lower performance and larger code size. +TCPPSRC = + +# List ASM source files here +ASMSRC = $(PORTASM) \ + $(CHIBIOS)/os/ports/GCC/ARMCMx/STM32F10x/vectors.s + +INCDIR = $(PORTINC) $(KERNINC) $(TESTINC) \ + $(HALINC) $(PLATFORMINC) $(BOARDINC) \ + $(CHIBIOS)/os/various + +# +# Project, sources and paths +############################################################################## + +############################################################################## +# Compiler settings +# + +MCU = cortex-m3 + +#TRGT = arm-elf- +TRGT = arm-none-eabi- +CC = $(TRGT)gcc +CPPC = $(TRGT)g++ +# Enable loading with g++ only if you need C++ runtime support. +# NOTE: You can use C++ even without C++ support if you are careful. C++ +# runtime support makes code size explode. +LD = $(TRGT)gcc +#LD = $(TRGT)g++ +CP = $(TRGT)objcopy +AS = $(TRGT)gcc -x assembler-with-cpp +OD = $(TRGT)objdump +HEX = $(CP) -O ihex +BIN = $(CP) -O binary + +# ARM-specific options here +AOPT = + +# THUMB-specific options here +TOPT = -mthumb -DTHUMB + +# Define C warning options here +CWARN = -Wall -Wextra -Wstrict-prototypes + +# Define C++ warning options here +CPPWARN = -Wall -Wextra + +# +# Compiler settings +############################################################################## + +############################################################################## +# Start of default section +# + +# List all default C defines here, like -D_DEBUG=1 +DDEFS = -DCORTEX_USE_BASEPRI=TRUE + +# List all default ASM defines here, like -D_DEBUG=1 +DADEFS = + +# List all default directories to look for include files here +DINCDIR = + +# List the default directory to look for the libraries here +DLIBDIR = + +# List all default libraries here +DLIBS = + +# +# End of default section +############################################################################## + +############################################################################## +# Start of user section +# + +# List all user C define here, like -D_DEBUG=1 +UDEFS = + +# Define ASM defines here +UADEFS = + +# List all user directories here +UINCDIR = + +# List the user directory to look for the libraries here +ULIBDIR = + +# List all user libraries here +ULIBS = + +# +# End of user defines +############################################################################## + +ifeq ($(USE_FWLIB),yes) + include $(CHIBIOS)/ext/stm32lib/stm32lib.mk + CSRC += $(STM32SRC) + INCDIR += $(STM32INC) + USE_OPT += -DUSE_STDPERIPH_DRIVER +endif + +include $(CHIBIOS)/os/ports/GCC/ARM/rules.mk diff --git a/demos/ARMCM3-STM32F107-GCC/ch.ld b/demos/ARMCM3-STM32F107-GCC/ch.ld new file mode 100644 index 000000000..c0aa83278 --- /dev/null +++ b/demos/ARMCM3-STM32F107-GCC/ch.ld @@ -0,0 +1,94 @@ +/* + ChibiOS/RT - Copyright (C) 2006,2007,2008,2009,2010 Giovanni Di Sirio. + + This file is part of ChibiOS/RT. + + ChibiOS/RT is free software; you can redistribute it and/or modify + it under the terms of the GNU General Public License as published by + the Free Software Foundation; either version 3 of the License, or + (at your option) any later version. + + ChibiOS/RT is distributed in the hope that it will be useful, + but WITHOUT ANY WARRANTY; without even the implied warranty of + MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + GNU General Public License for more details. + + You should have received a copy of the GNU General Public License + along with this program. If not, see . +*/ + +/* + * ST32F107 memory setup. + */ +__main_stack_size__ = 0x0200; +__process_stack_size__ = 0x0400; +__stacks_total_size__ = __main_stack_size__ + __process_stack_size__; + +MEMORY +{ + flash : org = 0x08000000, len = 256k + ram : org = 0x20000000, len = 64k +} + +__ram_start__ = ORIGIN(ram); +__ram_size__ = LENGTH(ram); +__ram_end__ = __ram_start__ + __ram_size__; + +SECTIONS +{ + . = 0; + + .text : ALIGN(16) SUBALIGN(16) + { + _text = .; + KEEP(*(vectors)); + *(.text) + *(.text.*); + *(.rodata); + *(.rodata.*); + *(.glue_7t); + *(.glue_7); + *(.gcc*); + *(.ctors); + *(.dtors); + . = ALIGN(4); + _etext = .; + } > flash + + _textdata = _etext; + + .data : + { + _data = .; + *(.data) + . = ALIGN(4); + *(.data.*) + . = ALIGN(4); + *(.ramtext) + . = ALIGN(4); + _edata = .; + } > ram AT > flash + + .bss : + { + _bss_start = .; + *(.bss) + . = ALIGN(4); + *(.bss.*) + . = ALIGN(4); + *(COMMON) + . = ALIGN(4); + _bss_end = .; + } > ram + + /DISCARD/ : + { + *(.eh_*) + } +} + +PROVIDE(end = .); +_end = .; + +__heap_base__ = _end; +__heap_end__ = __ram_end__ - __stacks_total_size__; diff --git a/demos/ARMCM3-STM32F107-GCC/chconf.h b/demos/ARMCM3-STM32F107-GCC/chconf.h new file mode 100644 index 000000000..046d28300 --- /dev/null +++ b/demos/ARMCM3-STM32F107-GCC/chconf.h @@ -0,0 +1,483 @@ +/* + ChibiOS/RT - Copyright (C) 2006,2007,2008,2009,2010 Giovanni Di Sirio. + + This file is part of ChibiOS/RT. + + ChibiOS/RT is free software; you can redistribute it and/or modify + it under the terms of the GNU General Public License as published by + the Free Software Foundation; either version 3 of the License, or + (at your option) any later version. + + ChibiOS/RT is distributed in the hope that it will be useful, + but WITHOUT ANY WARRANTY; without even the implied warranty of + MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + GNU General Public License for more details. + + You should have received a copy of the GNU General Public License + along with this program. If not, see . +*/ + +/** + * @file templates/chconf.h + * @brief Configuration file template. + * @details A copy of this file must be placed in each project directory, it + * contains the application specific kernel settings. + * + * @addtogroup config + * @details Kernel related settings and hooks. + * @{ + */ + +#ifndef _CHCONF_H_ +#define _CHCONF_H_ + +/*===========================================================================*/ +/* Kernel parameters. */ +/*===========================================================================*/ + +/** + * @brief System tick frequency. + * @details Frequency of the system timer that drives the system ticks. This + * setting also defines the system tick time unit. + */ +#if !defined(CH_FREQUENCY) || defined(__DOXYGEN__) +#define CH_FREQUENCY 1000 +#endif + +/** + * @brief Round robin interval. + * @details This constant is the number of system ticks allowed for the + * threads before preemption occurs. Setting this value to zero + * disables the preemption for threads with equal priority and the + * round robin becomes cooperative. Note that higher priority + * threads can still preempt, the kernel is always preemptive. + * + * @note Disabling the round robin preemption makes the kernel more compact + * and generally faster. + */ +#if !defined(CH_TIME_QUANTUM) || defined(__DOXYGEN__) +#define CH_TIME_QUANTUM 20 +#endif + +/** + * @brief Nested locks. + * @details If enabled then the use of nested @p chSysLock() / @p chSysUnlock() + * operations is allowed.
+ * For performance and code size reasons the recommended setting + * is to leave this option disabled.
+ * You may use this option if you need to merge ChibiOS/RT with + * external libraries that require nested lock/unlock operations. + * + * @note T he default is @p FALSE. + */ +#if !defined(CH_USE_NESTED_LOCKS) || defined(__DOXYGEN__) +#define CH_USE_NESTED_LOCKS FALSE +#endif + +/** + * @brief Managed RAM size. + * @details Size of the RAM area to be managed by the OS. If set to zero + * then the whole available RAM is used. The core memory is made + * available to the heap allocator and/or can be used directly through + * the simplified core memory allocator. + * + * @note In order to let the OS manage the whole RAM the linker script must + * provide the @p __heap_base__ and @p __heap_end__ symbols. + * @note Requires @p CH_USE_COREMEM. + */ +#if !defined(CH_MEMCORE_SIZE) || defined(__DOXYGEN__) +#define CH_MEMCORE_SIZE 0 +#endif + +/*===========================================================================*/ +/* Performance options. */ +/*===========================================================================*/ + +/** + * @brief OS optimization. + * @details If enabled then time efficient rather than space efficient code + * is used when two possible implementations exist. + * + * @note This is not related to the compiler optimization options. + * @note The default is @p TRUE. + */ +#if !defined(CH_OPTIMIZE_SPEED) || defined(__DOXYGEN__) +#define CH_OPTIMIZE_SPEED TRUE +#endif + +/** + * @brief Exotic optimization. + * @details If defined then a CPU register is used as storage for the global + * @p currp variable. Caching this variable in a register greatly + * improves both space and time OS efficiency. A side effect is that + * one less register has to be saved during the context switch + * resulting in lower RAM usage and faster context switch. + * + * @note This option is only usable with the GCC compiler and is only useful + * on processors with many registers like ARM cores. + * @note If this option is enabled then ALL the libraries linked to the + * ChibiOS/RT code must be recompiled with the GCC option @p + * -ffixed-@. + * @note This option must be enabled in the Makefile, it is listed here for + * documentation only. + */ +#if defined(__DOXYGEN__) +#define CH_CURRP_REGISTER_CACHE "reg" +#endif + +/*===========================================================================*/ +/* Subsystem options. */ +/*===========================================================================*/ + +/** + * @brief Threads registry APIs. + * @details If enabled then the registry APIs are included in the kernel. + * + * @note The default is @p TRUE. + */ +#if !defined(CH_USE_REGISTRY) || defined(__DOXYGEN__) +#define CH_USE_REGISTRY TRUE +#endif + +/** + * @brief Threads synchronization APIs. + * @details If enabled then the @p chThdWait() function is included in + * the kernel. + * + * @note The default is @p TRUE. + */ +#if !defined(CH_USE_WAITEXIT) || defined(__DOXYGEN__) +#define CH_USE_WAITEXIT TRUE +#endif + +/** + * @brief Semaphores APIs. + * @details If enabled then the Semaphores APIs are included in the kernel. + * + * @note The default is @p TRUE. + */ +#if !defined(CH_USE_SEMAPHORES) || defined(__DOXYGEN__) +#define CH_USE_SEMAPHORES TRUE +#endif + +/** + * @brief Semaphores queuing mode. + * @details If enabled then the threads are enqueued on semaphores by + * priority rather than in FIFO order. + * + * @note The default is @p FALSE. Enable this if you have special requirements. + * @note Requires @p CH_USE_SEMAPHORES. + */ +#if !defined(CH_USE_SEMAPHORES_PRIORITY) || defined(__DOXYGEN__) +#define CH_USE_SEMAPHORES_PRIORITY FALSE +#endif + +/** + * @brief Atomic semaphore API. + * @details If enabled then the semaphores the @p chSemSignalWait() API + * is included in the kernel. + * + * @note The default is @p TRUE. + * @note Requires @p CH_USE_SEMAPHORES. + */ +#if !defined(CH_USE_SEMSW) || defined(__DOXYGEN__) +#define CH_USE_SEMSW TRUE +#endif + +/** + * @brief Mutexes APIs. + * @details If enabled then the mutexes APIs are included in the kernel. + * + * @note The default is @p TRUE. + */ +#if !defined(CH_USE_MUTEXES) || defined(__DOXYGEN__) +#define CH_USE_MUTEXES TRUE +#endif + +/** + * @brief Conditional Variables APIs. + * @details If enabled then the conditional variables APIs are included + * in the kernel. + * + * @note The default is @p TRUE. + * @note Requires @p CH_USE_MUTEXES. + */ +#if !defined(CH_USE_CONDVARS) || defined(__DOXYGEN__) +#define CH_USE_CONDVARS TRUE +#endif + +/** + * @brief Conditional Variables APIs with timeout. + * @details If enabled then the conditional variables APIs with timeout + * specification are included in the kernel. + * + * @note The default is @p TRUE. + * @note Requires @p CH_USE_CONDVARS. + */ +#if !defined(CH_USE_CONDVARS_TIMEOUT) || defined(__DOXYGEN__) +#define CH_USE_CONDVARS_TIMEOUT TRUE +#endif + +/** + * @brief Events Flags APIs. + * @details If enabled then the event flags APIs are included in the kernel. + * + * @note The default is @p TRUE. + */ +#if !defined(CH_USE_EVENTS) || defined(__DOXYGEN__) +#define CH_USE_EVENTS TRUE +#endif + +/** + * @brief Events Flags APIs with timeout. + * @details If enabled then the events APIs with timeout specification + * are included in the kernel. + * + * @note The default is @p TRUE. + * @note Requires @p CH_USE_EVENTS. + */ +#if !defined(CH_USE_EVENTS_TIMEOUT) || defined(__DOXYGEN__) +#define CH_USE_EVENTS_TIMEOUT TRUE +#endif + +/** + * @brief Synchronous Messages APIs. + * @details If enabled then the synchronous messages APIs are included + * in the kernel. + * + * @note The default is @p TRUE. + */ +#if !defined(CH_USE_MESSAGES) || defined(__DOXYGEN__) +#define CH_USE_MESSAGES TRUE +#endif + +/** + * @brief Synchronous Messages queuing mode. + * @details If enabled then messages are served by priority rather than in + * FIFO order. + * + * @note The default is @p FALSE. Enable this if you have special requirements. + * @note Requires @p CH_USE_MESSAGES. + */ +#if !defined(CH_USE_MESSAGES_PRIORITY) || defined(__DOXYGEN__) +#define CH_USE_MESSAGES_PRIORITY FALSE +#endif + +/** + * @brief Mailboxes APIs. + * @details If enabled then the asynchronous messages (mailboxes) APIs are + * included in the kernel. + * + * @note The default is @p TRUE. + * @note Requires @p CH_USE_SEMAPHORES. + */ +#if !defined(CH_USE_MAILBOXES) || defined(__DOXYGEN__) +#define CH_USE_MAILBOXES TRUE +#endif + +/** + * @brief I/O Queues APIs. + * @details If enabled then the I/O queues APIs are included in the kernel. + * + * @note The default is @p TRUE. + * @note Requires @p CH_USE_SEMAPHORES. + */ +#if !defined(CH_USE_QUEUES) || defined(__DOXYGEN__) +#define CH_USE_QUEUES TRUE +#endif + +/** + * @brief Core Memory Manager APIs. + * @details If enabled then the core memory manager APIs are included + * in the kernel. + * + * @note The default is @p TRUE. + */ +#if !defined(CH_USE_MEMCORE) || defined(__DOXYGEN__) +#define CH_USE_MEMCORE TRUE +#endif + +/** + * @brief Heap Allocator APIs. + * @details If enabled then the memory heap allocator APIs are included + * in the kernel. + * + * @note The default is @p TRUE. + * @note Requires @p CH_USE_COREMEM and either @p CH_USE_MUTEXES or + * @p CH_USE_SEMAPHORES. + * @note Mutexes are recommended. + */ +#if !defined(CH_USE_HEAP) || defined(__DOXYGEN__) +#define CH_USE_HEAP TRUE +#endif + +/** + * @brief C-runtime allocator. + * @details If enabled the the heap allocator APIs just wrap the C-runtime + * @p malloc() and @p free() functions. + * + * @note The default is @p FALSE. + * @note Requires @p CH_USE_HEAP. + * @note The C-runtime may or may not require @p CH_USE_COREMEM, see the + * appropriate documentation. + */ +#if !defined(CH_USE_MALLOC_HEAP) || defined(__DOXYGEN__) +#define CH_USE_MALLOC_HEAP FALSE +#endif + +/** + * @brief Memory Pools Allocator APIs. + * @details If enabled then the memory pools allocator APIs are included + * in the kernel. + * + * @note The default is @p TRUE. + */ +#if !defined(CH_USE_MEMPOOLS) || defined(__DOXYGEN__) +#define CH_USE_MEMPOOLS TRUE +#endif + +/** + * @brief Dynamic Threads APIs. + * @details If enabled then the dynamic threads creation APIs are included + * in the kernel. + * + * @note The default is @p TRUE. + * @note Requires @p CH_USE_WAITEXIT. + * @note Requires @p CH_USE_HEAP and/or @p CH_USE_MEMPOOLS. + */ +#if !defined(CH_USE_DYNAMIC) || defined(__DOXYGEN__) +#define CH_USE_DYNAMIC TRUE +#endif + +/*===========================================================================*/ +/* Debug options. */ +/*===========================================================================*/ + +/** + * @brief Debug option, parameters checks. + * @details If enabled then the checks on the API functions input + * parameters are activated. + * + * @note The default is @p FALSE. + */ +#if !defined(CH_DBG_ENABLE_CHECKS) || defined(__DOXYGEN__) +#define CH_DBG_ENABLE_CHECKS FALSE +#endif + +/** + * @brief Debug option, consistency checks. + * @details If enabled then all the assertions in the kernel code are + * activated. This includes consistency checks inside the kernel, + * runtime anomalies and port-defined checks. + * + * @note The default is @p FALSE. + */ +#if !defined(CH_DBG_ENABLE_ASSERTS) || defined(__DOXYGEN__) +#define CH_DBG_ENABLE_ASSERTS FALSE +#endif + +/** + * @brief Debug option, trace buffer. + * @details If enabled then the context switch circular trace buffer is + * activated. + * + * @note The default is @p FALSE. + */ +#if !defined(CH_DBG_ENABLE_TRACE) || defined(__DOXYGEN__) +#define CH_DBG_ENABLE_TRACE FALSE +#endif + +/** + * @brief Debug option, stack checks. + * @details If enabled then a runtime stack check is performed. + * + * @note The default is @p FALSE. + * @note The stack check is performed in a architecture/port dependent way. + * It may not be implemented or some ports. + * @note The default failure mode is to halt the system with the global + * @p panic_msg variable set to @p NULL. + */ +#if !defined(CH_DBG_ENABLE_STACK_CHECK) || defined(__DOXYGEN__) +#define CH_DBG_ENABLE_STACK_CHECK FALSE +#endif + +/** + * @brief Debug option, stacks initialization. + * @details If enabled then the threads working area is filled with a byte + * value when a thread is created. This can be useful for the + * runtime measurement of the used stack. + * + * @note The default is @p FALSE. + */ +#if !defined(CH_DBG_FILL_THREADS) || defined(__DOXYGEN__) +#define CH_DBG_FILL_THREADS FALSE +#endif + +/** + * @brief Debug option, threads profiling. + * @details If enabled then a field is added to the @p Thread structure that + * counts the system ticks occurred while executing the thread. + * + * @note The default is @p TRUE. + * @note This debug option is defaulted to TRUE because it is required by + * some test cases into the test suite. + */ +#if !defined(CH_DBG_THREADS_PROFILING) || defined(__DOXYGEN__) +#define CH_DBG_THREADS_PROFILING TRUE +#endif + +/*===========================================================================*/ +/* Kernel hooks. */ +/*===========================================================================*/ + +/** + * @brief Threads descriptor structure hook. + * @details User fields added to the end of the @p Thread structure. + */ +#if !defined(THREAD_EXT_FIELDS) || defined(__DOXYGEN__) +#define THREAD_EXT_FIELDS \ +struct { \ + /* Add threads custom fields here.*/ \ +}; +#endif + +/** + * @brief Threads initialization hook. + * @details User initialization code added to the @p chThdInit() API. + * + * @note It is invoked from within @p chThdInit() and implicitily from all + * the threads creation APIs. + */ +#if !defined(THREAD_EXT_INIT) || defined(__DOXYGEN__) +#define THREAD_EXT_INIT(tp) { \ + /* Add threads initialization code here.*/ \ +} +#endif + +/** + * @brief Threads finalization hook. + * @details User finalization code added to the @p chThdExit() API. + * + * @note It is inserted into lock zone. + * @note It is also invoked when the threads simply return in order to + * terminate. + */ +#if !defined(THREAD_EXT_EXIT) || defined(__DOXYGEN__) +#define THREAD_EXT_EXIT(tp) { \ + /* Add threads finalization code here.*/ \ +} +#endif + +/** + * @brief Idle Loop hook. + * @details This hook is continuously invoked by the idle thread loop. + */ +#if !defined(IDLE_LOOP_HOOK) || defined(__DOXYGEN__) +#define IDLE_LOOP_HOOK() { \ + /* Idle loop code here.*/ \ +} +#endif + +#endif /* _CHCONF_H_ */ + +/** @} */ diff --git a/demos/ARMCM3-STM32F107-GCC/halconf.h b/demos/ARMCM3-STM32F107-GCC/halconf.h new file mode 100644 index 000000000..763b0019a --- /dev/null +++ b/demos/ARMCM3-STM32F107-GCC/halconf.h @@ -0,0 +1,152 @@ +/* + ChibiOS/RT - Copyright (C) 2006,2007,2008,2009,2010 Giovanni Di Sirio. + + This file is part of ChibiOS/RT. + + ChibiOS/RT is free software; you can redistribute it and/or modify + it under the terms of the GNU General Public License as published by + the Free Software Foundation; either version 3 of the License, or + (at your option) any later version. + + ChibiOS/RT is distributed in the hope that it will be useful, + but WITHOUT ANY WARRANTY; without even the implied warranty of + MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + GNU General Public License for more details. + + You should have received a copy of the GNU General Public License + along with this program. If not, see . +*/ + +/** + * @file templates/halconf.h + * @brief HAL configuration header. + * @addtogroup HAL_CONF + * @{ + */ + +/* + * HAL configuration file, this file allows to enable or disable the various + * device drivers from your application. You may also use this file in order + * to override the device drivers default settings. + */ + +#ifndef _HALCONF_H_ +#define _HALCONF_H_ + +/* + * Uncomment the following line in order to include a mcu-related + * settings file. This file can be used to include platform specific + * header files or to override the low level drivers settings. + */ +#include "mcuconf.h" + +/*===========================================================================*/ +/* PAL driver related settings. */ +/*===========================================================================*/ + +/** + * @brief Enables the PAL subsystem. + */ +#if !defined(CH_HAL_USE_PAL) || defined(__DOXYGEN__) +#define CH_HAL_USE_PAL TRUE +#endif + +/*===========================================================================*/ +/* ADC driver related settings. */ +/*===========================================================================*/ + +/** + * @brief Enables the ADC subsystem. + */ +#if !defined(CH_HAL_USE_ADC) || defined(__DOXYGEN__) +#define CH_HAL_USE_ADC FALSE +#endif + +/*===========================================================================*/ +/* CAN driver related settings. */ +/*===========================================================================*/ + +/** + * @brief Enables the CAN subsystem. + */ +#if !defined(CH_HAL_USE_CAN) || defined(__DOXYGEN__) +#define CH_HAL_USE_CAN FALSE +#endif + +/*===========================================================================*/ +/* MAC driver related settings. */ +/*===========================================================================*/ + +/** + * @brief Enables the MAC subsystem. + */ +#if !defined(CH_HAL_USE_MAC) || defined(__DOXYGEN__) +#define CH_HAL_USE_MAC FALSE +#endif + +/*===========================================================================*/ +/* PWM driver related settings. */ +/*===========================================================================*/ + +/** + * @brief Enables the PWM subsystem. + */ +#if !defined(CH_HAL_USE_PWM) || defined(__DOXYGEN__) +#define CH_HAL_USE_PWM FALSE +#endif + +/*===========================================================================*/ +/* SERIAL driver related settings. */ +/*===========================================================================*/ + +/** + * @brief Enables the SERIAL subsystem. + */ +#if !defined(CH_HAL_USE_SERIAL) || defined(__DOXYGEN__) +#define CH_HAL_USE_SERIAL TRUE +#endif + +/* + * Default SERIAL settings overrides (uncomment to override). + */ +/*#define SERIAL_DEFAULT_BITRATE 38400*/ +/*#define SERIAL_BUFFERS_SIZE 64*/ + +/*===========================================================================*/ +/* SPI driver related settings. */ +/*===========================================================================*/ + +/** + * @brief Enables the SPI subsystem. + */ +#if !defined(CH_HAL_USE_SPI) || defined(__DOXYGEN__) +#define CH_HAL_USE_SPI FALSE +#endif + +/* + * Default SPI settings overrides (uncomment to override). + */ +/*#define SPI_USE_MUTUAL_EXCLUSION TRUE*/ + +/*===========================================================================*/ +/* MMC_SPI driver related settings. */ +/*===========================================================================*/ + +/** + * @brief Enables the MMC_SPI subsystem. + */ +#if !defined(CH_HAL_USE_MMC_SPI) || defined(__DOXYGEN__) +#define CH_HAL_USE_MMC_SPI FALSE +#endif + +/* + * Default MMC_SPI settings overrides (uncomment to override). + */ +/*#define MMC_SECTOR_SIZE 512*/ +/*#define MMC_NICE_WAITING TRUE*/ +/*#define MMC_POLLING_INTERVAL 10*/ +/*#define MMC_POLLING_DELAY 10*/ + +#endif /* _HALCONF_H_ */ + +/** @} */ diff --git a/demos/ARMCM3-STM32F107-GCC/main.c b/demos/ARMCM3-STM32F107-GCC/main.c new file mode 100644 index 000000000..b831d2c37 --- /dev/null +++ b/demos/ARMCM3-STM32F107-GCC/main.c @@ -0,0 +1,69 @@ +/* + ChibiOS/RT - Copyright (C) 2006,2007,2008,2009,2010 Giovanni Di Sirio. + + This file is part of ChibiOS/RT. + + ChibiOS/RT is free software; you can redistribute it and/or modify + it under the terms of the GNU General Public License as published by + the Free Software Foundation; either version 3 of the License, or + (at your option) any later version. + + ChibiOS/RT is distributed in the hope that it will be useful, + but WITHOUT ANY WARRANTY; without even the implied warranty of + MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + GNU General Public License for more details. + + You should have received a copy of the GNU General Public License + along with this program. If not, see . +*/ + +#include "ch.h" +#include "hal.h" +#include "test.h" + +/* + * Red LEDs blinker thread, times are in milliseconds. + */ +static WORKING_AREA(waThread1, 128); +static msg_t Thread1(void *arg) { + + (void)arg; + while (TRUE) { +// palClearPad(IOPORT3, GPIOC_LED); + chThdSleepMilliseconds(500); +// palSetPad(IOPORT3, GPIOC_LED); + chThdSleepMilliseconds(500); + } + return 0; +} + +/* + * Entry point, note, the main() function is already a thread in the system + * on entry. + */ +int main(int argc, char **argv) { + + (void)argc; + (void)argv; + + /* + * Activates the serial driver 2 using the driver default configuration. + */ + sdStart(&SD2, NULL); + + /* + * Creates the blinker thread. + */ + chThdCreateStatic(waThread1, sizeof(waThread1), NORMALPRIO, Thread1, NULL); + + /* + * Normal main() thread activity, in this demo it does nothing except + * sleeping in a loop and check the button state. + */ + while (TRUE) { +// if (palReadPad(IOPORT1, GPIOA_BUTTON)) +// TestThread(&SD2); + chThdSleepMilliseconds(500); + } + return 0; +} diff --git a/demos/ARMCM3-STM32F107-GCC/mcuconf.h b/demos/ARMCM3-STM32F107-GCC/mcuconf.h new file mode 100644 index 000000000..2591523ed --- /dev/null +++ b/demos/ARMCM3-STM32F107-GCC/mcuconf.h @@ -0,0 +1,102 @@ +/* + ChibiOS/RT - Copyright (C) 2006,2007,2008,2009,2010 Giovanni Di Sirio. + + This file is part of ChibiOS/RT. + + ChibiOS/RT is free software; you can redistribute it and/or modify + it under the terms of the GNU General Public License as published by + the Free Software Foundation; either version 3 of the License, or + (at your option) any later version. + + ChibiOS/RT is distributed in the hope that it will be useful, + but WITHOUT ANY WARRANTY; without even the implied warranty of + MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + GNU General Public License for more details. + + You should have received a copy of the GNU General Public License + along with this program. If not, see . +*/ + +/* + * STM32 drivers configuration. + * The following settings override the default settings present in + * the various device driver implementation headers. + * Note that the settings for each driver only have effect if the driver + * is enabled in halconf.h. + * + * IRQ priorities: + * 15...0 Lowest...Highest. + * + * DMA priorities: + * 0...3 Lowest...Highest. + */ + +/* + * HAL driver system settings. + */ +#define STM32_SW STM32_SW_PLL +#define STM32_PLLSRC STM32_PLLSRC_PREDIV1 +#define STM32_PREDIV1SRC STM32_PREDIV1SRC_PLL2 +#define STM32_PREDIV1_VALUE 5 +#define STM32_PLLMUL_VALUE 9 +#define STM32_PREDIV2_VALUE 5 +#define STM32_PLL2MUL_VALUE 8 +#define STM32_HPRE STM32_HPRE_DIV1 +#define STM32_PPRE1 STM32_PPRE1_DIV2 +#define STM32_PPRE2 STM32_PPRE2_DIV2 +#define STM32_ADCPRE STM32_ADCPRE_DIV4 + +/* + * ADC driver system settings. + */ +#define USE_STM32_ADC1 TRUE +#define STM32_ADC1_DMA_PRIORITY 3 +#define STM32_ADC1_IRQ_PRIORITY 5 +#define STM32_ADC1_DMA_ERROR_HOOK() chSysHalt() + +/* + * CAN driver system settings. + */ +#define USE_STM32_CAN1 TRUE +#define STM32_CAN1_IRQ_PRIORITY 11 + +/* + * PWM driver system settings. + */ +#define USE_STM32_PWM1 TRUE +#define USE_STM32_PWM2 FALSE +#define USE_STM32_PWM3 FALSE +#define USE_STM32_PWM4 FALSE +#define STM32_PWM1_IRQ_PRIORITY 7 +#define STM32_PWM2_IRQ_PRIORITY 7 +#define STM32_PWM3_IRQ_PRIORITY 7 +#define STM32_PWM4_IRQ_PRIORITY 7 + +/* + * SERIAL driver system settings. + */ +#define USE_STM32_USART1 FALSE +#define USE_STM32_USART2 TRUE +#define USE_STM32_USART3 FALSE +#if defined(STM32F10X_HD) || defined(STM32F10X_CL) +#define USE_STM32_UART4 FALSE +#define USE_STM32_UART5 FALSE +#endif +#define STM32_USART1_PRIORITY 12 +#define STM32_USART2_PRIORITY 12 +#define STM32_USART3_PRIORITY 12 +#if defined(STM32F10X_HD) || defined(STM32F10X_CL) +#define STM32_UART4_PRIORITY 12 +#define STM32_UART5_PRIORITY 12 +#endif + +/* + * SPI driver system settings. + */ +#define USE_STM32_SPI1 TRUE +#define USE_STM32_SPI2 TRUE +#define STM32_SPI1_DMA_PRIORITY 2 +#define STM32_SPI2_DMA_PRIORITY 2 +#define STM32_SPI1_IRQ_PRIORITY 10 +#define STM32_SPI2_IRQ_PRIORITY 10 +#define STM32_SPI1_DMA_ERROR_HOOK() chSysHalt() diff --git a/demos/ARMCM3-STM32F107-GCC/readme.txt b/demos/ARMCM3-STM32F107-GCC/readme.txt new file mode 100644 index 000000000..959a23363 --- /dev/null +++ b/demos/ARMCM3-STM32F107-GCC/readme.txt @@ -0,0 +1,25 @@ +***************************************************************************** +** ChibiOS/RT port for ARM-Cortex-M3 STM32F107. ** +***************************************************************************** + +** TARGET ** + +The demo runs on an ST STM3210C-EVAL board. + +** The Demo ** + + +** Build Procedure ** + +The demo has been tested by using the free Codesourcery GCC-based toolchain, +YAGARTO and an experimental WinARM build including GCC 4.3.0. +Just modify the TRGT line in the makefile in order to use different GCC ports. + +** Notes ** + +Some files used by the demo are not part of ChibiOS/RT but are copyright of +ST Microelectronics and are licensed under a different license. +Also note that not all the files present in the ST library are distribited +with ChibiOS/RT, you can find the whole library on the ST web site: + + http://www.st.com diff --git a/os/hal/platforms/STM32/hal_lld.c b/os/hal/platforms/STM32/hal_lld.c index b56e6bbbb..9dc66a3f0 100644 --- a/os/hal/platforms/STM32/hal_lld.c +++ b/os/hal/platforms/STM32/hal_lld.c @@ -90,33 +90,109 @@ void hal_lld_init(void) { * @brief STM32 clocks and PLL initialization. * @note All the involved constants come from the file @p board.h. */ +#if defined(STM32F10X_LD) || defined(STM32F10X_MD) || \ + defined(STM32F10X_HD) || defined(__DOXYGEN__) +/* + * Clocks initialization for the LD, MD and HD sub-families. + */ void stm32_clock_init(void) { - /* HSI setup.*/ - RCC->CR = 0x00000083; /* Reset value, HSI ON. */ + /* HSI setup, it enforces the reset situation in order to handle possible + problems with JTAG probes and re-initializations.*/ + RCC->CR |= RCC_CR_HSION; /* Make sure HSI is ON. */ while (!(RCC->CR & RCC_CR_HSIRDY)) - ; /* Waits until HSI stable. */ - /* HSE setup.*/ + ; /* Wait until HSI is stable. */ + RCC->CR &= RCC_CR_HSITRIM | RCC_CR_HSION; /* CR Reset value. */ + RCC->CFGR = 0; /* CFGR reset value. */ + while ((RCC->CFGR & RCC_CFGR_SWS) != RCC_CFGR_SWS_HSI) + ; /* Wait until HSI is the source.*/ + + /* HSE setup, it is only performed if the HSE clock is selected as source + of the system clock (directly or through the PLL).*/ +#if (STM32_SW == STM32_SW_HSE) || \ + ((STM32_SW == STM32_SW_PLL) && (STM32_PLLSRC == STM32_PLLSRC_HSE)) RCC->CR |= RCC_CR_HSEON; while (!(RCC->CR & RCC_CR_HSERDY)) - ; /* Waits until HSE stable. */ + ; /* Waits until HSE is stable. */ +#endif + + /* PLL setup, it is only performed if the PLL is the selected source of + the system clock else it is left disabled.*/ #if STM32_SW == STM32_SW_PLL - /* PLL setup, only if the PLL is the selected source of the system clock - else it is left disabled.*/ - RCC->CFGR = ((STM32_PLLMUL - 2) << 18) | STM32_PLLXTPRE | STM32_PLLSRC; - RCC->CR |= RCC_CR_PLLON; + RCC->CFGR |= STM32_PLLMUL | STM32_PLLXTPRE | STM32_PLLSRC; + RCC->CR |= RCC_CR_PLLON; while (!(RCC->CR & RCC_CR_PLLRDY)) - ; /* Waits until PLL stable. */ + ; /* Waits until PLL is stable. */ #endif + /* Clock settings.*/ - RCC->CFGR = ((STM32_PLLMUL - 2) << 18) | STM32_PLLXTPRE | STM32_PLLSRC | + RCC->CFGR = STM32_PLLMUL | STM32_PLLXTPRE | STM32_PLLSRC | STM32_ADCPRE | STM32_PPRE2 | STM32_PPRE1 | STM32_HPRE; /* Flash setup and final clock selection. */ FLASH->ACR = STM32_FLASHBITS; /* Flash wait states depending on clock. */ - RCC->CFGR |= STM32_SW; /* Switches on the clock sources. */ + + /* Switching on the configured clock source if it is different from HSI.*/ +#if (STM32_SW != STM32_SW_HSI) + RCC->CFGR |= STM32_SW; /* Switches on the selected clock source. */ while ((RCC->CFGR & RCC_CFGR_SWS) != (STM32_SW << 2)) ; +#endif } +#elif defined(STM32F10X_CL) +/* + * Clocks initialization for the CL sub-family. + */ +void stm32_clock_init(void) { + + /* HSI setup, it enforces the reset situation in order to handle possible + problems with JTAG probes and re-initializations.*/ + RCC->CR |= RCC_CR_HSION; /* Make sure HSI is ON. */ + while (!(RCC->CR & RCC_CR_HSIRDY)) + ; /* Wait until HSI is stable. */ + RCC->CR &= RCC_CR_HSITRIM | RCC_CR_HSION; /* CR Reset value. */ + RCC->CFGR = 0; /* CFGR reset value. */ + while ((RCC->CFGR & RCC_CFGR_SWS) != RCC_CFGR_SWS_HSI) + ; /* Wait until HSI is the source.*/ + RCC->CFGR2 = 0; + + /* HSE setup, it is only performed if the HSE clock is selected as source + of the system clock (directly or through the PLLs).*/ +#if (STM32_SW == STM32_SW_HSE) || \ + ((STM32_SW == STM32_SW_PLL) && (STM32_PLLSRC == STM32_PLLSRC_PREDIV1)) + RCC->CR |= RCC_CR_HSEON; + while (!(RCC->CR & RCC_CR_HSERDY)) + ; /* Waits until HSE is stable. */ +#endif + + /* PLL2 setup, it is only performed if the PLL2 clock is selected as source + for the PLL clock else it is left disabled.*/ +#if STM32_PREDIV1SRC == STM32_PREDIV1SRC_PLL2 + RCC->CFGR2 |= STM32_PREDIV2 | STM32_PLL2MUL; + RCC->CR |= RCC_CR_PLL2ON; + while (!(RCC->CR & RCC_CR_PLLRDY)) + ; /* Waits until PLL is stable. */ +#endif + + /* PLL setup, it is only performed if the PLL is the selected source of + the system clock else it is left disabled.*/ +#if STM32_SW == STM32_SW_PLL + RCC->CFGR2 |= STM32_PREDIV1 | STM32_PREDIV1SRC; + RCC->CFGR |= STM32_PLLMUL | STM32_PLLSRC; + RCC->CR |= RCC_CR_PLLON; + while (!(RCC->CR & RCC_CR_PLL2RDY)) + ; /* Waits until PLL2 is stable. */ +#endif + + /* Switching on the configured clock source if it is different from HSI.*/ +#if (STM32_SW != STM32_SW_HSI) + RCC->CFGR |= STM32_SW; /* Switches on the selected clock source. */ + while ((RCC->CFGR & RCC_CFGR_SWS) != (STM32_SW << 2)) + ; +#endif +} +#else +void stm32_clock_init(void) {} +#endif /** @} */ diff --git a/os/hal/platforms/STM32/hal_lld_F107.h b/os/hal/platforms/STM32/hal_lld_F107.h index 1fe31a5dd..193beda68 100644 --- a/os/hal/platforms/STM32/hal_lld_F107.h +++ b/os/hal/platforms/STM32/hal_lld_F107.h @@ -67,70 +67,49 @@ #define STM32_ADCPRE_DIV6 (2 << 14) /**< HCLK divided by 6. */ #define STM32_ADCPRE_DIV8 (3 << 14) /**< HCLK divided by 8. */ -#define STM32_PLL1SRC_HSI (0 << 16) /**< PLL1 clock source is HSI. */ -#define STM32_PLL1SRC_PREDIV1 (1 << 16) /**< PLL1 clock source is +#define STM32_PLLSRC_HSI (0 << 16) /**< PLL clock source is HSI. */ +#define STM32_PLLSRC_PREDIV1 (1 << 16) /**< PLL clock source is PREDIV1. */ -#define STM32_PLL1MUL_MUL4 (2 << 18) /**< PLL2CLK multiplied by 4. */ -#define STM32_PLL1MUL_MUL5 (3 << 18) /**< PLL2CLK multiplied by 5. */ -#define STM32_PLL1MUL_MUL6 (4 << 18) /**< PLL2CLK multiplied by 6. */ -#define STM32_PLL1MUL_MUL7 (5 << 18) /**< PLL2CLK multiplied by 7. */ -#define STM32_PLL1MUL_MUL8 (6 << 18) /**< PLL2CLK multiplied by 8. */ -#define STM32_PLL1MUL_MUL9 (7 << 18) /**< PLL2CLK multiplied by 9. */ -#define STM32_PLL1MUL_MUL6P5 (13 << 18) /**< PLL2CLK multiplied by 6.5. */ - #define STM32_OTGFSPRE_DIV2 (1 << 22) /**< HCLK*2 divided by 2. */ #define STM32_OTGFSPRE_DIV3 (0 << 22) /**< HCLK*2 divided by 3. */ /* RCC_CFGR2 register bits definitions.*/ -#define STM32_PREDIV1_DIV(n) ((n) << 0) /**< PREDIV1 divided by n. */ -#define STM32_PREDIV2_DIV(n) ((n) << 4) /**< PREDIV2 divided by n. */ - #define STM32_PREDIV1SRC_HSE (0 << 16) /**< PREDIV1 source is HSE. */ #define STM32_PREDIV1SRC_PLL2 (1 << 16) /**< PREDIV1 source is PLL2. */ -#define STM32_PLL2MUL_MUL8 (6 << 8) /**< PLL2CLK multiplied by 8. */ -#define STM32_PLL2MUL_MUL9 (7 << 8) /**< PLL2CLK multiplied by 9. */ -#define STM32_PLL2MUL_MUL10 (8 << 8) /**< PLL2CLK multiplied by 10. */ -#define STM32_PLL2MUL_MUL11 (9 << 8) /**< PLL2CLK multiplied by 11. */ -#define STM32_PLL2MUL_MUL12 (10 << 8) /**< PLL2CLK multiplied by 12. */ -#define STM32_PLL2MUL_MUL13 (11 << 8) /**< PLL2CLK multiplied by 13. */ -#define STM32_PLL2MUL_MUL14 (12 << 8) /**< PLL2CLK multiplied by 14. */ -#define STM32_PLL2MUL_MUL16 (14 << 8) /**< PLL2CLK multiplied by 16. */ -#define STM32_PLL2MUL_MUL20 (15 << 8) /**< PLL2CLK multiplied by 20. */ - /*===========================================================================*/ /* Driver pre-compile time settings. */ /*===========================================================================*/ /** * @brief Main clock source selection. - * @note If the selected clock source is not the PLL1 then the PLL1 is not + * @note If the selected clock source is not the PLL then the PLL is not * initialized and started. * @note The default value is calculated for a 72MHz system clock from - * a 25MHz crystal using both PLL1 and PLL2. + * a 25MHz crystal using both PLL and PLL2. */ #if !defined(STM32_SW) || defined(__DOXYGEN__) #define STM32_SW STM32_SW_PLL #endif /** - * @brief Clock source for the PLL1. - * @note This setting has only effect if the PLL1 is selected as the + * @brief Clock source for the PLL. + * @note This setting has only effect if the PLL is selected as the * system clock source. * @note The default value is calculated for a 72MHz system clock from - * a 25MHz crystal using both PLL1 and PLL2. + * a 25MHz crystal using both PLL and PLL2. */ -#if !defined(STM32_PLL1SRC) || defined(__DOXYGEN__) -#define STM32_PLL1SRC STM32_PLL1SRC_PREDIV1 +#if !defined(STM32_PLLSRC) || defined(__DOXYGEN__) +#define STM32_PLLSRC STM32_PLLSRC_PREDIV1 #endif /** * @brief PREDIV1 clock source. - * @note This setting has only effect if the PLL1 is selected as the + * @note This setting has only effect if the PLL is selected as the * system clock source. * @note The default value is calculated for a 72MHz system clock from - * a 25MHz crystal using both PLL1 and PLL2. + * a 25MHz crystal using both PLL and PLL2. */ #if !defined(STM32_PREDIV1SCR) || defined(__DOXYGEN__) #define STM32_PREDIV1SRC STM32_PREDIV1SRC_PLL2 @@ -138,50 +117,51 @@ /** * @brief PREDIV1 division factor. - * @note This setting has only effect if the PLL1 is selected as the + * @note This setting has only effect if the PLL is selected as the * system clock source. * @note The allowed range is 1...16. * @note The default value is calculated for a 72MHz system clock from - * a 25MHz crystal using both PLL1 and PLL2. + * a 25MHz crystal using both PLL and PLL2. */ -#if !defined(STM32_PREDIV1) || defined(__DOXYGEN__) -#define STM32_PREDIV1 5 +#if !defined(STM32_PREDIV1_VALUE) || defined(__DOXYGEN__) +#define STM32_PREDIV1_VALUE 5 #endif /** - * @brief PLL1 multiplier value. + * @brief PLL multiplier value. + * @note The allowed range is 4...9. * @note The default value is calculated for a 72MHz system clock from - * a 25MHz crystal using both PLL1 and PLL2. + * a 25MHz crystal using both PLL and PLL2. */ -#if !defined(STM32_PLL1MUL) || defined(__DOXYGEN__) -#define STM32_PLL1MUL STM32_PLL1MUL_MUL9 +#if !defined(STM32_PLLMUL_VALUE) || defined(__DOXYGEN__) +#define STM32_PLLMUL_VALUE 9 #endif /** * @brief PREDIV2 division factor. * @note This setting has only effect if the PLL2 is selected as the - * clock source for the PLL1. + * clock source for the PLL. * @note The allowed range is 1...16. * @note The default value is calculated for a 72MHz system clock from - * a 25MHz crystal using both PLL1 and PLL2. + * a 25MHz crystal using both PLL and PLL2. */ -#if !defined(STM32_PREDIV2) || defined(__DOXYGEN__) -#define STM32_PREDIV2 5 +#if !defined(STM32_PREDIV2_VALUE) || defined(__DOXYGEN__) +#define STM32_PREDIV2_VALUE 5 #endif /** * @brief PLL2 multiplier value. * @note The default value is calculated for a 72MHz system clock from - * a 25MHz crystal using both PLL1 and PLL2. + * a 25MHz crystal using both PLL and PLL2. */ #if !defined(STM32_PLL2MUL) || defined(__DOXYGEN__) -#define STM32_PLL2MUL STM32_PLL2MUL_MUL8 +#define STM32_PLL2MUL_VALUE 8 #endif /** * @brief AHB prescaler value. * @note The default value is calculated for a 72MHz system clock from - * a 8MHz crystal using the PLL. + * a 25MHz crystal using both PLL and PLL2. */ #if !defined(STM32_HPRE) || defined(__DOXYGEN__) #define STM32_HPRE STM32_HPRE_DIV1 @@ -205,27 +185,61 @@ * @brief ADC prescaler value. */ #if !defined(STM32_ADCPRE) || defined(__DOXYGEN__) -#define STM32_ADCPRE STM32_ADCPRE_DIV4 +#define STM32_ADCPRE STM32_ADCPRE_DIV4 #endif /*===========================================================================*/ /* Derived constants and error checks. */ /*===========================================================================*/ -/* PREDIV1 prescaler setting check.*/ -#if (STM32_PREDIV1 < 1) || (STM32_PREDIV1 > 16) -#error "invalid STM32_PREDIV1 value specified" +/** + * @brief PREDIV1 field. + */ +#if (STM32_PREDIV1_VALUE >= 1) && (STM32_PREDIV1_VALUE <= 16) || \ + defined(__DOXYGEN__) +#define STM32_PREDIV1 (STM32_PREDIV1_VALUE << 0) +#else +#error "invalid STM32_PREDIV1_VALUE value specified" #endif -/* PREDIV2 prescaler setting check.*/ -#if (STM32_PREDIV2 < 1) || (STM32_PREDIV2 > 16) -#error "invalid STM32_PREDIV2 value specified" +/** + * @brief PREDIV2 field. + */ +#if (STM32_PREDIV2_VALUE >= 1) && (STM32_PREDIV2_VALUE <= 16) || \ + defined(__DOXYGEN__) +#define STM32_PREDIV2 (STM32_PREDIV2_VALUE << 4) +#else +#error "invalid STM32_PREDIV2_VALUE value specified" +#endif + +/** + * @brief PLLMUL field. + */ +#if ((STM32_PLLMUL_VALUE >= 4) && (STM32_PLLMUL_VALUE <= 9)) || \ + defined(__DOXYGEN__) +#define STM32_PLLMUL ((STM32_PLLMUL_VALUE - 2) << 18) +#else +#error "invalid STM32_PLLMUL_VALUE value specified" +#endif + +/** + * @brief PLL2MUL field. + */ +#if ((STM32_PLL2MUL_VALUE >= 8) && (STM32_PLL2MUL_VALUE <= 14)) || \ + defined(__DOXYGEN__) +#define STM32_PLL2MUL ((STM32_PLLMUL_VALUE - 2) << 8) +#elif (STM32_PLL2MUL_VALUE == 16) +#define STM32_PLL2MUL (14 << 8) +#elif (STM32_PLL2MUL_VALUE == 20) +#define STM32_PLL2MUL (15 << 8) +#else +#error "invalid STM32_PLL2MUL_VALUE value specified" #endif /** * @brief PLL2 input frequency. */ -#define STM32_PLL2CLKIN (STM32_HSECLK / STM32_PREDIV2) +#define STM32_PLL2CLKIN (STM32_HSECLK / STM32_PREDIV2_VALUE) /* PLL2 input frequency range check.*/ #if (STM32_PLL2CLKIN < 3000000) || (STM32_PLL2CLKIN > 5000000) @@ -235,7 +249,7 @@ /** * @brief PLL2 output clock frequency. */ -#define STM32_PLL2CLKOUT (STM32_PLL2CLKIN * STM32_PLL2MUL) +#define STM32_PLL2CLKOUT (STM32_PLL2CLKIN * STM32_PLL2MUL_VALUE) /* PLL2 output frequency range check.*/ #if (STM32_PLL2CLKOUT < 40000000) || (STM32_PLL2CLKOUT > 74000000) @@ -246,43 +260,44 @@ * @brief PREDIV1 input frequency. */ #if (STM32_PREDIV1SRC == STM32_PREDIV1SRC_PLL2) || defined(__DOXYGEN__) -#define STM32_PREDIV1CLK STM32_HSECLK -#elif STM32_PREDIV1SRC == STM32_PREDIV1SRC_HSE #define STM32_PREDIV1CLK STM32_PLL2CLKOUT +#elif STM32_PREDIV1SRC == STM32_PREDIV1SRC_HSE +#define STM32_PREDIV1CLK STM32_HSECLK #else +#error "invalid STM32_PREDIV1SRC value specified" #endif /** - * @brief PLL1 input clock frequency. + * @brief PLL input clock frequency. */ -#if (STM32_PLL1SRC == STM32_PLL1SRC_PREDIV1) || defined(__DOXYGEN__) -#define STM32_PLL1CLKIN (STM32_PREDIV1CLK / STM32_PREDIV1) +#if (STM32_PLLSRC == STM32_PLLSRC_PREDIV1) || defined(__DOXYGEN__) +#define STM32_PLLCLKIN (STM32_PREDIV1CLK / STM32_PREDIV1) #elif STM32_PLLSRC == STM32_PLLSRC_HSI -#define STM32_PLL1CLKIN (STM32_HSICLK / 2) +#define STM32_PLLCLKIN (STM32_HSICLK / 2) #else -#error "invalid STM32_PLL1SRC value specified" +#error "invalid STM32_PLLSRC value specified" #endif -/* PLL1 input frequency range check.*/ -#if (STM32_PLL1CLKIN < 3000000) || (STM32_PLL1CLKIN > 12000000) -#error "STM32_PLL1CLKIN outside acceptable range (3...12MHz)" +/* PLL input frequency range check.*/ +#if (STM32_PLLCLKIN < 3000000) || (STM32_PLLCLKIN > 12000000) +#error "STM32_PLLCLKIN outside acceptable range (3...12MHz)" #endif /** - * @brief PLL1 output clock frequency. + * @brief PLL output clock frequency. */ -#define STM32_PLL1CLKOUT (STM32_PLL1CLKIN * STM32_PLL1MUL) +#define STM32_PLLCLKOUT (STM32_PLLCLKIN * STM32_PLLMUL_VALUE) -/* PLL1 output frequency range check.*/ -#if (STM32_PLL1CLKOUT < 18000000) || (STM32_PLL1CLKOUT > 72000000) -#error "STM32_PLL1CLKOUT outside acceptable range (18...72MHz)" +/* PLL output frequency range check.*/ +#if (STM32_PLLCLKOUT < 18000000) || (STM32_PLLCLKOUT > 72000000) +#error "STM32_PLLCLKOUT outside acceptable range (18...72MHz)" #endif /** * @brief System clock source. */ #if (STM32_SW == STM32_SW_PLL) || defined(__DOXYGEN__) -#define STM32_SYSCLK STM32_PLL1CLKOUT +#define STM32_SYSCLK STM32_PLLCLKOUT #elif (STM32_SW == STM32_SW_HSI) #define STM32_SYSCLK STM32_HSICLK #elif (STM32_SW == STM32_SW_HSE) @@ -327,7 +342,7 @@ #endif /** - * @brief APB1 frequency. + * @brief APB1 frequency. */ #if (STM32_PPRE1 == STM32_PPRE1_DIV1) || defined(__DOXYGEN__) #define STM32_PCLK1 (STM32_HCLK / 1) diff --git a/os/hal/platforms/STM32/hal_lld_F10x.h b/os/hal/platforms/STM32/hal_lld_F10x.h index 518d96fdf..67876e6b2 100644 --- a/os/hal/platforms/STM32/hal_lld_F10x.h +++ b/os/hal/platforms/STM32/hal_lld_F10x.h @@ -84,7 +84,9 @@ * @note The default value is calculated for a 72MHz system clock from * a 8MHz crystal using the PLL. */ +#if !defined(STM32_SW) || defined(__DOXYGEN__) #define STM32_SW STM32_SW_PLL +#endif /** * @brief Clock source for the PLL. @@ -109,16 +111,13 @@ #endif /** - * @brief Desired PLL output frequency. - * @note The PLL multiplier is calculated from the input clock and this - * value. - * @note This setting has only effect if the PLL is selected as the - * system clock source. + * @brief PLL multiplier value. + * @note The allowed range is 2...16. * @note The default value is calculated for a 72MHz system clock from * a 8MHz crystal using the PLL. */ -#if !defined(STM32_PLLCLKOUT) || defined(__DOXYGEN__) -#define STM32_PLLCLKOUT 72000000 +#if !defined(STM32_PLLMUL_VALUE) || defined(__DOXYGEN__) +#define STM32_PLLMUL_VALUE 9 #endif /** @@ -148,7 +147,7 @@ * @brief ADC prescaler value. */ #if !defined(STM32_ADCPRE) || defined(__DOXYGEN__) -#define STM32_ADCPRE STM32_ADCPRE_DIV4 +#define STM32_ADCPRE STM32_ADCPRE_DIV4 #endif /*===========================================================================*/ @@ -160,6 +159,15 @@ (STM32_PLLXTPRE != STM32_PLLXTPRE_DIV2) #error "invalid STM32_PLLXTPRE value specified" #endif +/** + * @brief PLLMUL field. + */ +#if ((STM32_PLLMUL_VALUE >= 2) && (STM32_PLLMUL_VALUE <= 16)) || \ + defined(__DOXYGEN__) +#define STM32_PLLMUL ((STM32_PLLMUL_VALUE - 2) << 18) +#else +#error "invalid STM32_PLLMUL_VALUE value specified" +#endif /** * @brief PLL input clock frequency. @@ -181,22 +189,16 @@ #error "STM32_PLLCLKIN outside acceptable range (3...12MHz)" #endif +/** + * @brief PLL output clock frequency. + */ +#define STM32_PLLCLKOUT (STM32_PLLCLKIN * STM32_PLLMUL_VALUE) + /* PLL output frequency range check.*/ #if (STM32_PLLCLKOUT < 16000000) || (STM32_PLLCLKOUT > 72000000) #error "STM32_PLLCLKOUT outside acceptable range (16...72MHz)" #endif -/** - * @brief PLL multiplier. - */ -#define STM32_PLLMUL (STM32_PLLCLKOUT / STM32_PLLCLKIN) -#if (STM32_PLLMUL % 1) != 0 -#error "the requested PLL output frequency is not a multiple of the input frequency" -#endif -#if (STM32_PLLMUL < 2) || (STM32_PLLMUL > 16) -#error "the calculated PLL multiplier is out of the allowed range (2...16)" -#endif - /** * @brief System clock source. */ @@ -210,6 +212,7 @@ #error "invalid STM32_SYSCLK_SW value specified" #endif +/* Check on the system clock.*/ #if STM32_SYSCLK > 72000000 #error "STM32_SYSCLK above maximum rated frequency (72MHz)" #endif @@ -289,7 +292,7 @@ #endif /** - * @brief ADC frequency. + * @brief ADC frequency. */ #if (STM32_ADCPRE == STM32_ADCPRE_DIV2) || defined(__DOXYGEN__) #define STM32_ADCCLK (STM32_PCLK2 / 2) diff --git a/readme.txt b/readme.txt index 5c220096c..e7e33c00c 100644 --- a/readme.txt +++ b/readme.txt @@ -61,10 +61,13 @@ *** 1.5.7 *** - NEW: Improved clock initialization for the STM32, now it is possible to configure the clock using any clock source and any HSE frequency. - The clock tree parameters and checks are now calculated into a separate - file in order to support multiple clock trees for different sub-families - of the STM32 platform. Added separated clock trees for the LD/MD/HD - sub-family and the CL sub-family. +- NEW: The STM32 clock tree parameters and checks are now calculated into + a separate file in order to support multiple clock trees for different + sub-families of the STM32 platform. +- NEW: Added separated clock trees for the STM32 LD/MD/HD sub-family and + the CL sub-family (untested). Now the selection of the sub-family is done + in the board.h file, there is no more the need to put -DSTM32F10X_xx into + the makefile. *** 1.5.6 *** - FIX: Fixed centralized ARM makefile (bug 2992747)(backported in 1.4.3). diff --git a/testhal/STM32/mcuconf.h b/testhal/STM32/mcuconf.h index ed863801d..511460ac4 100644 --- a/testhal/STM32/mcuconf.h +++ b/testhal/STM32/mcuconf.h @@ -25,11 +25,7 @@ * is enabled in halconf.h. * * IRQ priorities: - * 15 Lowest, priority level reserved for PENDSV. - * 14...4 Normal IRQs priority levels (0x80 used by SYSTICK). - * 3 Used by SVCALL, do not share. - * 2...0 Fast interrupts, can preempt the kernel but cannot use it - * directly. + * 15...0 Lowest...Highest. * * DMA priorities: * 0...3 Lowest...Highest. @@ -41,7 +37,11 @@ #define STM32_SW STM32_SW_PLL #define STM32_PLLSRC STM32_PLLSRC_HSE #define STM32_PLLXTPRE STM32_PLLXTPRE_DIV1 -#define STM32_PLLCLKOUT 72000000 +#define STM32_PLLMUL_VALUE 9 +#define STM32_HPRE STM32_HPRE_DIV1 +#define STM32_PPRE1 STM32_PPRE1_DIV2 +#define STM32_PPRE2 STM32_PPRE2_DIV2 +#define STM32_ADCPRE STM32_ADCPRE_DIV4 /* * ADC driver system settings. -- cgit v1.2.3