AP_HAL_ChibiOS: support for STM32H730xx MCUs

correct calculation of advanced timers
add support for linker script configuration in mcu config script
use linker script configuration for H750 and H730
add single OTG_HS support on H730 via OTG2
make sure complimentary channels get advanced timers
complemntary timers do not require advanced mode
allow custom clockspeeds of 550Mhz
correct debug pins on H730
support custom clockrate of 520Mhz on H730
correct H730 USB end point pins
restructure linker script for STM32H730
allow chibios_hwdef.py to set advanced timer on L431
don't define RAMFUNC on STM32H730
clock tree for STM32H730
create non-cacheable memory area for SDMMC DMA
don't look for RAM_MAP in bootloader with external flash
This commit is contained in:
Andy Piper 2022-08-14 16:27:11 +02:00 committed by Andrew Tridgell
parent 09ee6b8651
commit cc086ab8d4
9 changed files with 1896 additions and 41 deletions

View File

@ -0,0 +1,357 @@
/*
ChibiOS - Copyright (C) 2006..2015 Giovanni Di Sirio
Licensed under the Apache License, Version 2.0 (the "License");
you may not use this file except in compliance with the License.
You may obtain a copy of the License at
http://www.apache.org/licenses/LICENSE-2.0
Unless required by applicable law or agreed to in writing, software
distributed under the License is distributed on an "AS IS" BASIS,
WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
See the License for the specific language governing permissions and
limitations under the License.
*/
/*
this file is included by the board specific ldscript.ld which is
generated from hwdef.dat
*/
/* RAM region to be used for fast code. */
REGION_ALIAS("FASTCODE_RAM", ram1)
/* stack areas are configured to be in AXI RAM (ram0) to ensure the SSBL will load the image */
/* RAM region to be used for Main stack. This stack accommodates the processing
of all exceptions and interrupts*/
REGION_ALIAS("MAIN_STACK_RAM", ram0);
/* RAM region to be used for the process stack. This is the stack used by
the main() function.*/
REGION_ALIAS("PROCESS_STACK_RAM", ram0);
/* RAM region to be used for data segment.*/
REGION_ALIAS("DATA_RAM", ram0);
/* RAM region to be used for BSS segment.*/
REGION_ALIAS("BSS_RAM", ram0);
/* RAM region to be used for the default heap.*/
REGION_ALIAS("HEAP_RAM", ram0);
/* AXI */
__ram0_start__ = ORIGIN(ram0);
__ram0_size__ = LENGTH(ram0);
__ram0_end__ = __ram0_start__ + __ram0_size__;
/* AXI */
__ram1_start__ = ORIGIN(ram1);
__ram1_size__ = LENGTH(ram1);
__ram1_end__ = __ram1_start__ + __ram1_size__;
/* DTCM */
__ram2_start__ = ORIGIN(ram2);
__ram2_size__ = LENGTH(ram2);
__ram2_end__ = __ram2_start__ + __ram2_size__;
/* ITCM */
__instram_start__ = ORIGIN(instram);
__instram_size__ = LENGTH(instram);
__instram_end__ = __instram_start__ + __instram_size__;
ENTRY(Reset_Handler)
SECTIONS
{
. = 0;
_text = .;
startup : ALIGN(16) SUBALIGN(16)
{
KEEP(*(.vectors))
} > default_flash
constructors : ALIGN(4) SUBALIGN(4)
{
__init_array_base__ = .;
KEEP(*(SORT(.init_array.*)))
KEEP(*(.init_array))
__init_array_end__ = .;
} > default_flash
destructors : ALIGN(4) SUBALIGN(4)
{
__fini_array_base__ = .;
KEEP(*(.fini_array))
KEEP(*(SORT(.fini_array.*)))
__fini_array_end__ = .;
} > default_flash
/* INSTRUCTION_RAM area is fast-access ITCM used for RAM-based code, 64k on H7 */
.fastramfunc : ALIGN(4) SUBALIGN(4)
{
. = ALIGN(4);
__instram_init_text__ = LOADADDR(.fastramfunc);
__instram_init__ = .;
/* ChibiOS won't boot unless these are excluded */
EXCLUDE_FILE (*vectors.o *crt0_v7m.o *crt1.o)
/* performance critical sections of ChibiOS */
*libch.a:ch*.*(.text*)
*libch.a:nvic.*(.text*)
*libch.a:bouncebuffer.*(.text*)
*libch.a:stm32_util.*(.text*)
*libch.a:stm32_dma.*(.text*)
*libch.a:memstreams.*(.text*)
*libch.a:malloc.*(.text*)
*libch.a:hrt.*(.text*)
*libch.a:hal*.*(.text*)
/* a selection of performance critical functions driven CPUInfo results */
lib/lib*.a:Semaphores.*(.text*)
lib/lib*.a:AP_Math.*(.text*)
lib/lib*.a:vector3.*(.text*)
lib/lib*.a:matrix3.*(.text*)
/* only used on debug builds */
/**libg_nano.a:*memset*(.text*)
*libg_nano.a:*memcpy*(.text*)*/
*libm.a:*(.text*)
/* For some reason boards won't boot if libc is in RAM, but will with debug on */
/**libc_nano.a:*(.text* .rodata*)
*libstdc++_nano.a:(.text* .rodata*)*/
*(.fastramfunc)
. = ALIGN(4);
__instram_end__ = .;
} > instram AT > default_flash
/* FLASH_RAM area is primarily used for RAM-based code and data, 256k allocation on H7 */
.ramfunc : ALIGN(4) SUBALIGN(4)
{
. = ALIGN(4);
__ram1_init_text__ = LOADADDR(.ramfunc);
__ram1_init__ = .;
/* ChibiOS won't boot unless these are excluded */
EXCLUDE_FILE (*vectors.o *crt0_v7m.o *crt1.o)
/*libch.a:*(.text* .rodata* .glue_7t .glue_7 .gcc*)*/
/* a selection of larger performance critical functions */
lib/lib*.a:*Filter.*(.text* .rodata*)
lib/lib*.a:*Filter2p.*(.text* .rodata*)
/*
lib/lib*.a:SPIDevice.*(.text* .rodata*)
lib/lib*.a:I2CDevice.*(.text* .rodata*)
*/
/*lib/lib*.a:Util.*(.text* .rodata*)
lib/lib*.a:Device.*(.text* .rodata*)
lib/lib*.a:Scheduler.*(.text* .rodata*)
lib/lib*.a:RingBuffer.*(.text* .rodata*)
lib/lib*.a:shared_dma.*(.text* .rodata*)
lib/lib*.a:crc.*(.text* .rodata*)*/
lib/lib*.a:matrixN.*(.text* .rodata*)
lib/lib*.a:matrix_alg.*(.text* .rodata*)
/*
lib/lib*.a:AP_NavEKF3*.*(.text* .rodata*)
lib/lib*.a:AP_NavEKF_*.*(.text* .rodata*)
lib/lib*.a:EKF*.*(.text* .rodata*)
lib/lib*.a:AP_Compass_Backend.*(.text* .rodata*)
lib/lib*.a:AP_RCProtocol_Backend.*(.text* .rodata*)
lib/lib*.a:AP_RCProtocol.*(.text* .rodata*)
lib/lib*.a:AP_RCProtocol_CRSF.*(.text* .rodata*)
lib/lib*.a:AP_RCTelemetry.*(.text* .rodata*)
lib/lib*.a:AP_CRSF_Telem.*(.text* .rodata*)
*/
lib/lib*.a:vector2.*(.text* .rodata*)
lib/lib*.a:quaternion.*(.text* .rodata*)
lib/lib*.a:polygon.*(.text* .rodata*)
lib/lib*.a:flash.*(.text* .rodata*) /* flash ops in RAM so that both banks can be erased */
/* uncomment these to test CPUInfo in FLASH_RAM */
/*Tools/CPUInfo/CPUInfo.*(.text* .rodata*)
Tools/CPUInfo/EKF_Maths.*(.text* .rodata*)*/
*(.ramfunc*)
. = ALIGN(4);
} > ram1 AT > default_flash
.ram1 (NOLOAD) : ALIGN(4)
{
. = ALIGN(4);
__ram1_clear__ = .;
. = ALIGN(4);
__ram1_noinit__ = .;
*(.ram1*)
. = ALIGN(4);
__ram1_free__ = .;
} > ram1
/* DATA_RAM area is DTCM primarily used for RAM-based data, e.g. vtables */
.ramdata : ALIGN(4)
{
. = ALIGN(4);
__ram2_init_text__ = LOADADDR(.ramdata);
__ram2_init__ = .;
/* ChibiOS won't boot unless these are excluded */
EXCLUDE_FILE (*vectors.o *crt0_v7m.o *crt1.o)
/* performance critical sections of ChibiOS */
*libch.a:ch*.*(.rodata*)
*libch.a:nvic.*(.rodata*)
*libch.a:bouncebuffer.*(.rodata*)
*libch.a:stm32_util.*(.rodata*)
*libch.a:stm32_dma.*(.rodata*)
*libch.a:memstreams.*(.rodata*)
*libch.a:malloc.*(.rodata*)
*libch.a:hrt.*(.rodata*)
*libch.a:hal*.*(.rodata*)
/* a selection of performance critical functions driven CPUInfo results */
lib/lib*.a:Semaphores.*(.rodata*)
lib/lib*.a:AP_Math.*(.rodata*)
lib/lib*.a:vector3.*(.rodata*)
lib/lib*.a:matrix3.*(.rodata*)
*libm.a:*(.rodata*)
*(.ramdata*)
. = ALIGN(4);
} > ram2 AT > default_flash
.ram2 (NOLOAD) : ALIGN(4)
{
. = ALIGN(4);
__ram2_clear__ = .;
. = ALIGN(4);
__ram2_noinit__ = .;
*(.ram2*)
. = ALIGN(4);
__ram2_free__ = .;
} > ram2
.text : ALIGN(4) SUBALIGN(4)
{
/* we want app_descriptor near the start of flash so a false
positive isn't found by the bootloader (eg. ROMFS) */
KEEP(*libch.a:vectors.o);
KEEP(*libch.a:crt0_v7m.o);
KEEP(*(.app_descriptor));
*(.text)
*(.text.*)
*(.rodata)
*(.rodata.*)
*(.glue_7t)
*(.glue_7)
*(.gcc*)
} > default_flash
.ARM.extab :
{
*(.ARM.extab* .gnu.linkonce.armextab.*)
} > default_flash
.ARM.exidx : {
__exidx_start = .;
*(.ARM.exidx* .gnu.linkonce.armexidx.*)
__exidx_end = .;
} > default_flash
.eh_frame_hdr :
{
*(.eh_frame_hdr)
} > default_flash
.eh_frame : ONLY_IF_RO
{
*(.eh_frame)
} > default_flash
.textalign : ONLY_IF_RO
{
. = ALIGN(8);
} > default_flash
/* Legacy symbol, not used anywhere.*/
. = ALIGN(4);
PROVIDE(_etext = .);
/* Special section for exceptions stack.*/
.mstack :
{
. = ALIGN(8);
__main_stack_base__ = .;
. += __main_stack_size__;
. = ALIGN(8);
__main_stack_end__ = .;
} > MAIN_STACK_RAM
/* Special section for process stack.*/
.pstack :
{
__process_stack_base__ = .;
__main_thread_stack_base__ = .;
. += __process_stack_size__;
. = ALIGN(8);
__process_stack_end__ = .;
__main_thread_stack_end__ = .;
} > PROCESS_STACK_RAM
.data : ALIGN(4)
{
. = ALIGN(4);
PROVIDE(_textdata = LOADADDR(.data));
PROVIDE(_data = .);
__textdata_base__ = LOADADDR(.data);
__data_base__ = .;
*(.data)
*(.data.*)
*(.ramtext)
. = ALIGN(4);
PROVIDE(_edata = .);
__data_end__ = .;
} > DATA_RAM AT > default_flash
.bss (NOLOAD) : ALIGN(4)
{
. = ALIGN(4);
__bss_base__ = .;
*(.bss)
*(.bss.*)
*(COMMON)
. = ALIGN(4);
__bss_end__ = .;
PROVIDE(end = .);
} > BSS_RAM
.ram0_init : ALIGN(4)
{
. = ALIGN(4);
__ram0_init_text__ = LOADADDR(.ram0_init);
__ram0_init__ = .;
*(.ram0_init)
*(.ram0_init.*)
. = ALIGN(4);
} > ram0 AT > default_flash
.ram0 (NOLOAD) : ALIGN(4)
{
. = ALIGN(4);
__ram0_clear__ = .;
*(.ram0_clear)
*(.ram0_clear.*)
. = ALIGN(4);
__ram0_noinit__ = .;
*(.ram0)
*(.ram0.*)
. = ALIGN(4);
__ram0_free__ = .;
} > ram0
/* The default heap uses the (statically) unused part of a RAM section.*/
.heap (NOLOAD) :
{
. = ALIGN(8);
__heap_base__ = .;
. = ORIGIN(HEAP_RAM) + LENGTH(HEAP_RAM);
__heap_end__ = .;
} > HEAP_RAM
/* The crash log uses the unused part of a flash section.*/
.crash_log (NOLOAD) :
{
. = ALIGN(32);
__crash_log_base__ = .;
. = ORIGIN(default_flash) + LENGTH(default_flash);
__crash_log_end__ = .;
} > default_flash
}

View File

@ -206,8 +206,11 @@ static void stm32_flash_wait_idle(void)
{
__DSB();
#if defined(STM32H7)
while ((FLASH->SR1 & (FLASH_SR_BSY|FLASH_SR_QW|FLASH_SR_WBNE)) ||
(FLASH->SR2 & (FLASH_SR_BSY|FLASH_SR_QW|FLASH_SR_WBNE))) {
while ((FLASH->SR1 & (FLASH_SR_BSY|FLASH_SR_QW|FLASH_SR_WBNE))
#if !defined(STM32H730xx) && !defined(STM32H750xx)
|| (FLASH->SR2 & (FLASH_SR_BSY|FLASH_SR_QW|FLASH_SR_WBNE))
#endif
) {
// nop
}
#else
@ -221,7 +224,9 @@ static void stm32_flash_clear_errors(void)
{
#if defined(STM32H7)
FLASH->CCR1 = ~0;
#if !defined(STM32H730xx) && !defined(STM32H750xx)
FLASH->CCR2 = ~0;
#endif
#else
FLASH->SR = 0xF3;
#endif
@ -240,11 +245,13 @@ static void stm32_flash_unlock(void)
FLASH->KEYR1 = FLASH_KEY1;
FLASH->KEYR1 = FLASH_KEY2;
}
#if !defined(STM32H730xx) && !defined(STM32H750xx)
if (FLASH->CR2 & FLASH_CR_LOCK) {
/* Unlock sequence */
FLASH->KEYR2 = FLASH_KEY1;
FLASH->KEYR2 = FLASH_KEY2;
}
#endif
#else
if (FLASH->CR & FLASH_CR_LOCK) {
/* Unlock sequence */
@ -268,12 +275,16 @@ void stm32_flash_lock(void)
if (FLASH->SR1 & FLASH_SR_QW) {
FLASH->CR1 |= FLASH_CR_FW;
}
#if !defined(STM32H730xx) && !defined(STM32H750xx)
if (FLASH->SR2 & FLASH_SR_QW) {
FLASH->CR2 |= FLASH_CR_FW;
}
#endif
stm32_flash_wait_idle();
FLASH->CR1 |= FLASH_CR_LOCK;
#if !defined(STM32H730xx) && !defined(STM32H750xx)
FLASH->CR2 |= FLASH_CR_LOCK;
#endif
#else
stm32_flash_wait_idle();
FLASH->CR |= FLASH_CR_LOCK;
@ -436,7 +447,9 @@ bool stm32_flash_erasepage(uint32_t page)
FLASH->CR1 = FLASH_CR_PSIZE_1 | snb | FLASH_CR_SER;
FLASH->CR1 |= FLASH_CR_START;
while (FLASH->SR1 & FLASH_SR_QW) ;
} else {
}
#if !defined(STM32H730xx) && !defined(STM32H750xx)
else {
// second bank
FLASH->SR2 = ~0;
@ -449,6 +462,7 @@ bool stm32_flash_erasepage(uint32_t page)
FLASH->CR2 |= FLASH_CR_START;
while (FLASH->SR2 & FLASH_SR_QW) ;
}
#endif
#elif defined(STM32F1) || defined(STM32F3)
FLASH->CR = FLASH_CR_PER;
FLASH->AR = stm32_flash_getpageaddr(page);
@ -520,16 +534,16 @@ static bool stm32h7_check_all_ones(uint32_t addr, uint32_t words)
*/
static bool stm32h7_flash_write32(uint32_t addr, const void *buf)
{
volatile uint32_t *CR, *CCR, *SR;
if (addr - STM32_FLASH_BASE < 8 * STM32_FLASH_FIXED_PAGE_SIZE * 1024) {
CR = &FLASH->CR1;
CCR = &FLASH->CCR1;
SR = &FLASH->SR1;
} else {
volatile uint32_t *CR = &FLASH->CR1;
volatile uint32_t *CCR = &FLASH->CCR1;
volatile uint32_t *SR = &FLASH->SR1;
#if !defined(STM32H730xx) && !defined(STM32H750xx)
if (addr - STM32_FLASH_BASE >= 8 * STM32_FLASH_FIXED_PAGE_SIZE * 1024) {
CR = &FLASH->CR2;
CCR = &FLASH->CCR2;
SR = &FLASH->SR2;
}
#endif
stm32_flash_wait_idle();
*CCR = ~0;
@ -877,7 +891,9 @@ void stm32_flash_protect_flash(bool bootloader, bool protect)
(void)protect;
#if defined(STM32H7) && HAL_FLASH_PROTECTION
uint32_t prg1 = FLASH->WPSN_CUR1;
#if !defined(STM32H730xx) && !defined(STM32H750xx)
uint32_t prg2 = FLASH->WPSN_CUR2;
#endif
#ifndef STORAGE_FLASH_PAGE
const uint32_t storage_page = 0xFF;
#else
@ -901,7 +917,7 @@ void stm32_flash_protect_flash(bool bootloader, bool protect)
prg1 |= 1U<<i;
}
}
#if !defined(STM32H730xx) && !defined(STM32H750xx)
for (uint32_t i = 0; i < 8; i++) {
if (i+8 != storage_page && i+8 != storage_page+1 && protect) {
prg2 &= ~(1U<<i);
@ -909,10 +925,15 @@ void stm32_flash_protect_flash(bool bootloader, bool protect)
prg2 |= 1U<<i;
}
}
#endif
}
// check if any changes to be made
if (prg1 == FLASH->WPSN_CUR1 && prg2 == FLASH->WPSN_CUR2) {
if (prg1 == FLASH->WPSN_CUR1
#if !defined(STM32H730xx) && !defined(STM32H750xx)
&& prg2 == FLASH->WPSN_CUR2
#endif
) {
return;
}
@ -921,7 +942,9 @@ void stm32_flash_protect_flash(bool bootloader, bool protect)
if (stm32_flash_unlock_options()) {
FLASH->WPSN_PRG1 = prg1;
#if !defined(STM32H730xx) && !defined(STM32H750xx)
FLASH->WPSN_PRG2 = prg2;
#endif
FLASH->OPTCR |= FLASH_OPTCR_OPTSTART;
stm32_flash_wait_opt_idle();
@ -941,6 +964,7 @@ void stm32_flash_unprotect_flash()
stm32_flash_opt_clear_errors();
stm32_flash_clear_errors();
#if !defined(STM32H730xx) && !defined(STM32H750xx)
if ((FLASH->PRAR_CUR2 & 0xFFF) <= ((FLASH->PRAR_CUR2 >> 16) & 0xFFF)
|| (FLASH->SCAR_CUR2 & 0xFFF) <= ((FLASH->SCAR_CUR2 >> 16) & 0xFFF)) {
@ -963,7 +987,7 @@ void stm32_flash_unprotect_flash()
stm32_flash_lock();
}
}
#endif
if ((FLASH->PRAR_CUR1 & 0xFFF) <= ((FLASH->PRAR_CUR1 >> 16) & 0xFFF)
|| (FLASH->SCAR_CUR1 & 0xFFF) <= ((FLASH->SCAR_CUR1 >> 16) & 0xFFF)) {
@ -987,11 +1011,16 @@ void stm32_flash_unprotect_flash()
}
}
// remove write protection from banks 1&2
if ((FLASH->WPSN_CUR2 & 0xFF) != 0xFF
|| (FLASH->WPSN_CUR1 & 0xFF) != 0xFF) {
if ((FLASH->WPSN_CUR1 & 0xFF) != 0xFF
#if !defined(STM32H730xx) && !defined(STM32H750xx)
|| (FLASH->WPSN_CUR2 & 0xFF) != 0xFF
#endif
) {
if (stm32_flash_unlock_options()) {
FLASH->WPSN_PRG1 = 0xFF;
#if !defined(STM32H730xx) && !defined(STM32H750xx)
FLASH->WPSN_PRG2 = 0xFF;
#endif
FLASH->OPTCR |= FLASH_OPTCR_OPTSTART;
stm32_flash_wait_opt_idle();

View File

@ -584,5 +584,4 @@
#define WSPI_USE_MUTUAL_EXCLUSION TRUE
#endif
/** @} */

View File

@ -45,6 +45,7 @@
*/
#define STM32H7xx_MCUCONF
#define STM32H730_MCUCONF
#define STM32H742_MCUCONF
#define STM32H743_MCUCONF
#define STM32H753_MCUCONF
@ -74,7 +75,6 @@
* very critical.
* Register constants are taken from the ST header.
*/
#define STM32_VOS STM32_VOS_SCALE1
#define STM32_PWR_CR1 (PWR_CR1_SVOS_1 | PWR_CR1_SVOS_0)
#define STM32_PWR_CR2 (PWR_CR2_BREN)
#ifdef SMPS_PWR
@ -94,6 +94,178 @@
#define STM32_LSE_ENABLED FALSE
#define STM32_HSIDIV STM32_HSIDIV_DIV1
/*
* Setup clocks for the STM32H70 which vary quite significantly from other H7 variants
*/
#if defined(STM32H730xx)
#define STM32_VOS STM32_VOS_SCALE0
/*
setup PLLs based on HSE clock
*/
#if STM32_HSECLK == 0U
// no crystal, this gives 400MHz system clock
#define STM32_HSE_ENABLED FALSE
#define STM32_HSI_ENABLED TRUE
#define STM32_PLL1_DIVM_VALUE 32
#define STM32_PLL2_DIVM_VALUE 32
#define STM32_PLL3_DIVM_VALUE 32
#define STM32_PLLSRC STM32_PLLSRC_HSI_CK
#define STM32_MCO1SEL STM32_MCO1SEL_HSI_CK
#define STM32_CKPERSEL STM32_CKPERSEL_HSI_CK
#elif STM32_HSECLK == 8000000U
// this gives 520MHz system clock
#define STM32_HSE_ENABLED TRUE
#define STM32_HSI_ENABLED FALSE
#define STM32_PLL1_DIVM_VALUE 4
#define STM32_PLL2_DIVM_VALUE 8
#define STM32_PLL3_DIVM_VALUE 8
#elif STM32_HSECLK == 16000000U
// this gives 520MHz system clock
#define STM32_HSE_ENABLED TRUE
#define STM32_HSI_ENABLED FALSE
#define STM32_PLL1_DIVM_VALUE 8
#define STM32_PLL2_DIVM_VALUE 16
#define STM32_PLL3_DIVM_VALUE 16
#else
#error "Unsupported HSE clock"
#endif
#if STM32_HSECLK == 0U
// no crystal
#define STM32_PLL1_DIVN_VALUE 260
#define STM32_PLL1_DIVP_VALUE 1
#define STM32_PLL1_DIVQ_VALUE 6
#define STM32_PLL1_DIVR_VALUE 4
#define STM32_PLL2_DIVN_VALUE 200
#define STM32_PLL2_DIVP_VALUE 3
#define STM32_PLL2_DIVQ_VALUE 3
#define STM32_PLL2_DIVR_VALUE 2
#define STM32_PLL3_DIVN_VALUE 96
#define STM32_PLL3_DIVP_VALUE 1
#define STM32_PLL3_DIVQ_VALUE 2
#define STM32_PLL3_DIVR_VALUE 4
#elif (STM32_HSECLK == 8000000U) || (STM32_HSECLK == 16000000U)
// common clock tree for multiples of 8MHz crystals
#ifdef HAL_CUSTOM_MCU_CLOCKRATE
#if HAL_CUSTOM_MCU_CLOCKRATE == 520000000
#define STM32_PLL1_DIVN_VALUE 260
#define STM32_PLL1_DIVP_VALUE 1
#define STM32_PLL1_DIVQ_VALUE 6
#define STM32_PLL3_DIVP_VALUE 1
#else
#error "Unable to configure custom clockrate"
#endif
#else // these downclock to a system clock of 400Mhz
#define STM32_PLL1_DIVN_VALUE 200
#define STM32_PLL1_DIVP_VALUE 1
#define STM32_PLL1_DIVQ_VALUE 6
#define STM32_PLL3_DIVP_VALUE 2
#endif
#define STM32_PLL1_DIVR_VALUE 4
#define STM32_PLL2_DIVN_VALUE 400
#define STM32_PLL2_DIVP_VALUE 3
#define STM32_PLL2_DIVQ_VALUE 3
#define STM32_PLL2_DIVR_VALUE 2
#define STM32_PLL3_DIVN_VALUE 192
#define STM32_PLL3_DIVQ_VALUE 2
#define STM32_PLL3_DIVR_VALUE 4
#endif // clock selection
/*
* PLLs static settings.
* Reading STM32 Reference Manual is required.
*/
#define STM32_PLLSRC STM32_PLLSRC_HSE_CK
#define STM32_PLLCFGR_MASK ~0
#define STM32_PLL1_ENABLED TRUE
#define STM32_PLL1_P_ENABLED TRUE
#define STM32_PLL1_Q_ENABLED TRUE
#define STM32_PLL1_R_ENABLED TRUE
#define STM32_PLL1_FRACN_VALUE 0
#define STM32_PLL2_ENABLED TRUE
#define STM32_PLL2_P_ENABLED TRUE
#define STM32_PLL2_Q_ENABLED TRUE
#define STM32_PLL2_R_ENABLED TRUE
#define STM32_PLL2_FRACN_VALUE 0
#define STM32_PLL3_ENABLED TRUE
#define STM32_PLL3_P_ENABLED TRUE
#define STM32_PLL3_Q_ENABLED TRUE
#define STM32_PLL3_R_ENABLED TRUE
#define STM32_PLL3_FRACN_VALUE 0
/*
* Core clocks dynamic settings (can be changed at runtime).
* Reading STM32 Reference Manual is required.
*/
#define STM32_SW STM32_SW_PLL1_P_CK
#define STM32_RTCSEL STM32_RTCSEL_LSI_CK
#define STM32_D1CPRE STM32_D1CPRE_DIV1
#define STM32_D1HPRE STM32_D1HPRE_DIV2
#define STM32_D1PPRE3 STM32_D1PPRE3_DIV2
#define STM32_D2PPRE1 STM32_D2PPRE1_DIV2
#define STM32_D2PPRE2 STM32_D2PPRE2_DIV2
#define STM32_D3PPRE4 STM32_D3PPRE4_DIV2
/*
* Peripherals clocks static settings.
* Reading STM32 Reference Manual is required.
*/
#define STM32_MCO1SEL STM32_MCO1SEL_HSE_CK
#define STM32_MCO1PRE_VALUE 1
#define STM32_MCO2SEL STM32_MCO2SEL_SYS_CK
#define STM32_MCO2PRE_VALUE 1
#define STM32_TIMPRE_ENABLE TRUE
#define STM32_HRTIMSEL 0
#define STM32_STOPKERWUCK 0
#define STM32_STOPWUCK 0
#define STM32_RTCPRE_VALUE 2
#define STM32_CKPERSEL STM32_CKPERSEL_HSE_CK
#define STM32_SDMMCSEL STM32_SDMMCSEL_PLL1_Q_CK
#define STM32_OCTOSPISEL STM32_OCTOSPISEL_HCLK
#define STM32_FMCSEL STM32_OCTOSPISEL_HCLK
#define STM32_SWPSEL STM32_SWPSEL_PCLK1
#define STM32_FDCANSEL STM32_FDCANSEL_PLL1_Q_CK
#define STM32_DFSDM1SEL STM32_DFSDM1SEL_PCLK2
#define STM32_SPDIFSEL STM32_SPDIFSEL_PLL1_Q_CK
#define STM32_SPI45SEL STM32_SPI45SEL_PCLK2
#define STM32_SPI123SEL STM32_SPI123SEL_PLL3_P_CK
#define STM32_SAI1SEL STM32_SAI1SEL_PLL1_Q_CK
#define STM32_LPTIM1SEL STM32_LPTIM1SEL_PCLK1
#define STM32_CECSEL STM32_CECSEL_DISABLE
#define STM32_USBSEL STM32_USBSEL_HSI48_CK
#define STM32_I2C123SEL STM32_I2C123SEL_PLL3_R_CK
#define STM32_RNGSEL STM32_RNGSEL_HSI48_CK
#define STM32_USART16SEL STM32_USART16SEL_PCLK2
#define STM32_USART234578SEL STM32_USART234578SEL_PCLK1
#define STM32_SPI6SEL STM32_SPI6SEL_PLL3_Q_CK
#define STM32_SAI4BSEL STM32_SAI4BSEL_PLL1_Q_CK
#define STM32_SAI4ASEL STM32_SAI4ASEL_PLL1_Q_CK
#define STM32_ADCSEL STM32_ADCSEL_PLL3_R_CK
#define STM32_LPTIM345SEL STM32_LPTIM345SEL_PCLK4
#define STM32_LPTIM2SEL STM32_LPTIM2SEL_PCLK4
#define STM32_I2C4SEL STM32_I2C4SEL_PLL3_R_CK
#define STM32_LPUART1SEL STM32_LPUART1SEL_PCLK4 // really PCLK3
/*
* Clock setup for all other H7 variants including H743, H753, H750 and H757
*/
#else
#define STM32_VOS STM32_VOS_SCALE1
/*
setup PLLs based on HSE clock
*/
@ -286,15 +458,23 @@
#define STM32_CKPERSEL STM32_CKPERSEL_HSE_CK
#endif
#define STM32_SDMMCSEL STM32_SDMMCSEL_PLL1_Q_CK
#ifndef STM32H730xx
#define STM32_QSPISEL STM32_QSPISEL_PLL2_R_CK
#define STM32_FMCSEL STM32_QSPISEL_HCLK
#else
#define STM32_OSPISEL STM32_OSPISEL_HCLK
#define STM32_FMCSEL STM32_OSPISEL_HCLK
#endif
#define STM32_SWPSEL STM32_SWPSEL_PCLK1
#define STM32_FDCANSEL STM32_FDCANSEL_PLL1_Q_CK
#define STM32_DFSDM1SEL STM32_DFSDM1SEL_PCLK2
#define STM32_SPDIFSEL STM32_SPDIFSEL_PLL1_Q_CK
#define STM32_SPI45SEL STM32_SPI45SEL_PLL2_Q_CK
#define STM32_SPI123SEL STM32_SPI123SEL_PLL1_Q_CK
#ifdef STM32_SAI23SEL_PLL1_Q_CK
#define STM32_SAI23SEL STM32_SAI23SEL_PLL1_Q_CK
#endif
#define STM32_SAI1SEL STM32_SAI1SEL_PLL1_Q_CK
#define STM32_LPTIM1SEL STM32_LPTIM1SEL_PCLK1
#define STM32_CECSEL STM32_CECSEL_DISABLE
@ -311,6 +491,7 @@
#define STM32_LPTIM2SEL STM32_LPTIM2SEL_PCLK4
#define STM32_I2C4SEL STM32_I2C4SEL_PLL3_R_CK
#define STM32_LPUART1SEL STM32_LPUART1SEL_PCLK4
#endif
/*
* IRQ system settings.
@ -333,6 +514,9 @@
#define STM32_IRQ_MDMA_PRIORITY 9
#define STM32_IRQ_QUADSPI1_PRIORITY 10
#define STM32_IRQ_QUADSPI2_PRIORITY 10
#define STM32_IRQ_OCTOSPI1_PRIORITY 10
#define STM32_IRQ_OCTOSPI2_PRIORITY 10
#define STM32_IRQ_SDMMC1_PRIORITY 9
#define STM32_IRQ_SDMMC2_PRIORITY 9
@ -361,6 +545,8 @@
#define STM32_IRQ_USART6_PRIORITY 12
#define STM32_IRQ_UART7_PRIORITY 12
#define STM32_IRQ_UART8_PRIORITY 12
#define STM32_IRQ_UART9_PRIORITY 12
#define STM32_IRQ_USART10_PRIORITY 12
/*
* ADC driver system settings.
@ -373,7 +559,7 @@
#endif
#define STM32_ADC_COMPACT_SAMPLES FALSE
#define STM32_ADC_USE_ADC12 TRUE
#ifndef STM32H750xx
#if !defined(STM32H750xx) && !defined(STM32H730xx)
#ifndef STM32_ADC_USE_ADC3
#define STM32_ADC_USE_ADC3 TRUE
#endif
@ -587,7 +773,6 @@
/*
* USB driver system settings.
*/
#define STM32_USB_USE_OTG1 TRUE
#define STM32_USB_USE_OTG2 TRUE
#define STM32_USB_OTG1_IRQ_PRIORITY 14
#define STM32_USB_OTG2_IRQ_PRIORITY 14
@ -621,6 +806,16 @@
#define STM32_WSPI_QUADSPI1_PRESCALER_VALUE (STM32_QSPICLK / HAL_QSPI1_CLK)
#endif
#ifndef STM32_WSPI_USE_OCTOSPI1
#define STM32_WSPI_USE_OCTOSPI1 FALSE
#endif
#if STM32_WSPI_USE_OCTOSPI1
#define STM32_WSPI_OCTOSPI1_MDMA_CHANNEL STM32_MDMA_CHANNEL_ID_ANY
#define STM32_WSPI_OCTOSPI1_MDMA_PRIORITY 1
#define STM32_WSPI_OCTOSPI1_PRESCALER_VALUE (STM32_OCTOSPICLK / HAL_OSPI1_CLK)
#endif
/*
we use a fixed allocation of BDMA streams. We previously dynamically
allocated these, but bugs in the chip make that unreliable. This is

View File

@ -223,11 +223,6 @@
#define STM32_I2C_I2C4_DMA_PRIORITY 3
#define STM32_I2C_DMA_ERROR_HOOK(i2cp) STM32_DMA_ERROR_HOOK(i2cp)
/*
* PWM driver system settings.
*/
#define STM32_PWM_USE_ADVANCED FALSE
/*
* RTC driver system settings.
*/

View File

@ -401,7 +401,11 @@ const USBConfig usbcfg = {
* Serial over USB driver configuration.
*/
const SerialUSBConfig serusbcfg1 = {
#if STM32_USB_USE_OTG1
&USBD1,
#else
&USBD2,
#endif
USBD1_DATA_REQUEST_EP,
USBD1_DATA_AVAILABLE_EP,
USBD1_INTERRUPT_REQUEST_EP

File diff suppressed because it is too large Load Diff

View File

@ -77,7 +77,9 @@ mcu = {
'DEFINES' : {
'HAL_HAVE_HARDWARE_DOUBLE' : '1',
'STM32H7' : '1',
}
},
'LINKER_CONFIG' : 'common_extf.ld'
}
pincount = {

View File

@ -749,8 +749,8 @@ def get_ram_map():
if args.bootloader:
ram_map = get_mcu_config('RAM_MAP_BOOTLOADER', False)
if ram_map is not None:
app_ram_map = get_mcu_config('RAM_MAP', True)
if app_ram_map[0][0] != ram_map[0][0]:
app_ram_map = get_mcu_config('RAM_MAP', False)
if app_ram_map is not None and app_ram_map[0][0] != ram_map[0][0]:
# we need to find the location of app_ram_map[0] in ram_map
for i in range(len(ram_map)):
if app_ram_map[0][0] == ram_map[i][0]:
@ -921,7 +921,10 @@ def write_mcu_config(f):
build_flags.append('USE_FATFS=no')
env_vars['DISABLE_SCRIPTING'] = True
if 'OTG1' in bytype:
f.write('#define STM32_USB_USE_OTG1 TRUE\n')
if mcu_type.startswith('STM32H730'):
f.write('#define STM32_USB_USE_OTG2 TRUE\n')
else:
f.write('#define STM32_USB_USE_OTG1 TRUE\n')
f.write('#define HAL_USE_USB TRUE\n')
f.write('#define HAL_USE_SERIAL_USB TRUE\n')
if 'OTG2' in bytype:
@ -1005,7 +1008,8 @@ def write_mcu_config(f):
f.write('#define CRT0_AREAS_NUMBER 3\n')
f.write('#define CRT1_RAMFUNC_ENABLE TRUE\n') # this will enable loading program sections to RAM
f.write('#define __FASTRAMFUNC__ __attribute__ ((__section__(".fastramfunc")))\n')
f.write('#define __RAMFUNC__ __attribute__ ((__section__(".ramfunc")))\n')
if not mcu_type.startswith('STM32H730'):
f.write('#define __RAMFUNC__ __attribute__ ((__section__(".ramfunc")))\n')
f.write('#define PORT_IRQ_ATTRIBUTES __FASTRAMFUNC__\n')
else:
f.write('#define CRT0_AREAS_NUMBER 1\n')
@ -1372,7 +1376,7 @@ MEMORY
ram2 : org = 0x%08x, len = %u
}
INCLUDE common_extf.ld
INCLUDE common.ld
''' % (ext_flash_base, ext_flash_length,
instruction_ram_base, instruction_ram_length,
ram0_start, ram0_len,
@ -1381,15 +1385,20 @@ INCLUDE common_extf.ld
def copy_common_linkerscript(outdir):
dirpath = os.path.dirname(os.path.realpath(__file__))
if not get_config('EXT_FLASH_SIZE_MB', default=0, type=int) or args.bootloader:
shutil.copy(os.path.join(dirpath, "../common/common.ld"),
os.path.join(outdir, "common.ld"))
elif get_config('INT_FLASH_PRIMARY', default=False, type=int):
shutil.copy(os.path.join(dirpath, "../common/common_mixf.ld"),
os.path.join(outdir, "common_mixf.ld"))
if args.bootloader:
linker = 'common.ld'
else:
shutil.copy(os.path.join(dirpath, "../common/common_extf.ld"),
os.path.join(outdir, "common_extf.ld"))
linker = get_mcu_config('LINKER_CONFIG')
if linker is None:
if not get_config('EXT_FLASH_SIZE_MB', default=0, type=int):
linker = 'common.ld'
elif get_config('INT_FLASH_PRIMARY', default=False, type=int):
linker = 'common_mixf.ld'
else:
linker = 'common_extf.ld'
shutil.copy(os.path.join(dirpath, "../common", linker),
os.path.join(outdir, "common.ld"))
def get_USB_IDs():
'''return tuple of USB VID/PID'''
@ -2128,7 +2137,9 @@ def write_PWM_config(f, ordered_timers):
f.write('\n')
f.write('// PWM output config\n')
groups = []
have_complementary = False
# complementary channels require advanced features
# which are only available on timers 1 and 8
need_advanced = False
for t in pwm_timers:
group = len(groups) + 1
@ -2148,7 +2159,6 @@ def write_PWM_config(f, ordered_timers):
chan_list[chan - 1] = pwm - 1
if compl:
chan_mode[chan - 1] = 'PWM_COMPLEMENTARY_OUTPUT_ACTIVE_HIGH'
have_complementary = True
else:
chan_mode[chan - 1] = 'PWM_OUTPUT_ACTIVE_HIGH'
alt_functions[chan - 1] = p.af
@ -2156,6 +2166,7 @@ def write_PWM_config(f, ordered_timers):
groups.append('HAL_PWM_GROUP%u' % group)
if n in [1, 8]:
# only the advanced timers do 8MHz clocks
need_advanced = True
advanced_timer = 'true'
else:
advanced_timer = 'false'
@ -2207,7 +2218,7 @@ def write_PWM_config(f, ordered_timers):
alt_functions[0], alt_functions[1], alt_functions[2], alt_functions[3],
pal_lines[0], pal_lines[1], pal_lines[2], pal_lines[3]))
f.write('#define HAL_PWM_GROUPS %s\n\n' % ','.join(groups))
if have_complementary:
if need_advanced:
f.write('#define STM32_PWM_USE_ADVANCED TRUE\n')
@ -2428,11 +2439,16 @@ def write_peripheral_enable(f):
if type.startswith('SPI'):
f.write('#define STM32_SPI_USE_%s TRUE\n' % type)
if type.startswith('OTG'):
f.write('#define STM32_USB_USE_%s TRUE\n' % type)
if mcu_type.startswith('STM32H730'):
f.write('#define STM32_USB_USE_OTG2 TRUE\n')
else:
f.write('#define STM32_USB_USE_%s TRUE\n' % type)
if type.startswith('I2C'):
f.write('#define STM32_I2C_USE_%s TRUE\n' % type)
if type.startswith('QUADSPI'):
f.write('#define STM32_WSPI_USE_%s TRUE\n' % type)
if type.startswith('OCTOSPI'):
f.write('#define STM32_WSPI_USE_%s TRUE\n' % type)
def get_dma_exclude(periph_list):