/* * This file is part of Cleanflight and Betaflight. * * Cleanflight and Betaflight are free software. You can redistribute * this software and/or modify this software 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. * * Cleanflight and Betaflight are distributed in the hope that they * 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 software. * * If not, see . */ #include #include #include #include "platform.h" #include "build/atomic.h" #include "drivers/io.h" #include "drivers/light_led.h" #include "drivers/nvic.h" #include "drivers/resource.h" #include "drivers/sound_beeper.h" #include "drivers/time.h" #include "drivers/system.h" #if defined(STM32F4) || defined(STM32F7) || defined(STM32H7) || defined(AT32F4) || defined(APM32F4) || defined(GD32F4) // See "RM CoreSight Architecture Specification" // B2.3.10 "LSR and LAR, Software Lock Status Register and Software Lock Access Register" // "E1.2.11 LAR, Lock Access Register" #define DWT_LAR_UNLOCK_VALUE 0xC5ACCE55 #endif // cycles per microsecond static uint32_t usTicks = 0; static float usTicksInv = 0.0f; // current uptime for 1kHz systick timer. will rollover after 49 days. hopefully we won't care. static volatile uint32_t sysTickUptime = 0; static volatile uint32_t sysTickValStamp = 0; // cached value of RCC->CSR uint32_t cachedRccCsrValue; static uint32_t cpuClockFrequency = 0; void cycleCounterInit(void) { #if defined(USE_HAL_DRIVER) cpuClockFrequency = HAL_RCC_GetSysClockFreq(); #elif defined(USE_ATBSP_DRIVER) crm_clocks_freq_type clocks; crm_clocks_freq_get(&clocks); cpuClockFrequency = clocks.sclk_freq; #elif defined(USE_GDBSP_DRIVER) cpuClockFrequency = rcu_clock_freq_get(CK_SYS); #else RCC_ClocksTypeDef clocks; RCC_GetClocksFreq(&clocks); cpuClockFrequency = clocks.SYSCLK_Frequency; #endif usTicks = cpuClockFrequency / 1000000; usTicksInv = 1e6f / cpuClockFrequency; CoreDebug->DEMCR |= CoreDebug_DEMCR_TRCENA_Msk; #if defined(DWT_LAR_UNLOCK_VALUE) #if defined(STM32H7) || defined(AT32F4) || defined(GD32F4) ITM->LAR = DWT_LAR_UNLOCK_VALUE; #elif defined(STM32F7) DWT->LAR = DWT_LAR_UNLOCK_VALUE; #elif defined(STM32F4) || defined(APM32F4) // Note: DWT_Type does not contain LAR member. #define DWT_LAR __O uint32_t *DWTLAR = (uint32_t *)(DWT_BASE + 0x0FB0); *(DWTLAR) = DWT_LAR_UNLOCK_VALUE; #endif #endif DWT->CYCCNT = 0; DWT->CTRL |= DWT_CTRL_CYCCNTENA_Msk; } // SysTick static volatile int sysTickPending = 0; void SysTick_Handler(void) { ATOMIC_BLOCK(NVIC_PRIO_MAX) { sysTickUptime++; sysTickValStamp = SysTick->VAL; sysTickPending = 0; (void)(SysTick->CTRL); } #ifdef USE_HAL_DRIVER // used by the HAL for some timekeeping and timeouts, should always be 1ms HAL_IncTick(); #endif } // Return system uptime in microseconds (rollover in 70minutes) MMFLASH_CODE_NOINLINE uint32_t microsISR(void) { register uint32_t ms, pending, cycle_cnt; ATOMIC_BLOCK(NVIC_PRIO_MAX) { cycle_cnt = SysTick->VAL; if (SysTick->CTRL & SysTick_CTRL_COUNTFLAG_Msk) { // Update pending. // Record it for multiple calls within the same rollover period // (Will be cleared when serviced). // Note that multiple rollovers are not considered. sysTickPending = 1; // Read VAL again to ensure the value is read after the rollover. cycle_cnt = SysTick->VAL; } ms = sysTickUptime; pending = sysTickPending; } return ((ms + pending) * 1000) + (usTicks * 1000 - cycle_cnt) / usTicks; } uint32_t micros(void) { register uint32_t ms, cycle_cnt; // Call microsISR() in interrupt and elevated (non-zero) BASEPRI context if ((SCB->ICSR & SCB_ICSR_VECTACTIVE_Msk) || (__get_BASEPRI())) { return microsISR(); } do { ms = sysTickUptime; cycle_cnt = SysTick->VAL; } while (ms != sysTickUptime || cycle_cnt > sysTickValStamp); return (ms * 1000) + (usTicks * 1000 - cycle_cnt) / usTicks; } uint32_t getCycleCounter(void) { return DWT->CYCCNT; } int32_t clockCyclesToMicros(int32_t clockCycles) { return clockCycles / usTicks; } float clockCyclesToMicrosf(int32_t clockCycles) { return clockCycles * usTicksInv; } // Note that this conversion is signed as this is used for periods rather than absolute timestamps int32_t clockCyclesTo10thMicros(int32_t clockCycles) { return 10 * clockCycles / (int32_t)usTicks; } // Note that this conversion is signed as this is used for periods rather than absolute timestamps int32_t clockCyclesTo100thMicros(int32_t clockCycles) { return 100 * clockCycles / (int32_t)usTicks; } uint32_t clockMicrosToCycles(uint32_t micros) { return micros * usTicks; } // Return system uptime in milliseconds (rollover in 49 days) uint32_t millis(void) { return sysTickUptime; } #if 1 void delayMicroseconds(uint32_t us) { uint32_t now = micros(); while (micros() - now < us); } #else void delayMicroseconds(uint32_t us) { uint32_t elapsed = 0; uint32_t lastCount = SysTick->VAL; for (;;) { register uint32_t current_count = SysTick->VAL; uint32_t elapsed_us; // measure the time elapsed since the last time we checked elapsed += current_count - lastCount; lastCount = current_count; // convert to microseconds elapsed_us = elapsed / usTicks; if (elapsed_us >= us) break; // reduce the delay by the elapsed time us -= elapsed_us; // keep fractional microseconds for the next iteration elapsed %= usTicks; } } #endif void delay(uint32_t ms) { while (ms--) delayMicroseconds(1000); } static void indicate(uint8_t count, uint16_t duration) { if (count) { LED1_ON; LED0_OFF; while (count--) { LED1_TOGGLE; LED0_TOGGLE; BEEP_ON; delay(duration); LED1_TOGGLE; LED0_TOGGLE; BEEP_OFF; delay(duration); } } } void indicateFailure(failureMode_e mode, int codeRepeatsRemaining) { while (codeRepeatsRemaining--) { indicate(WARNING_FLASH_COUNT, WARNING_FLASH_DURATION_MS); delay(WARNING_PAUSE_DURATION_MS); indicate(mode + 1, WARNING_CODE_DURATION_LONG_MS); delay(1000); } } void failureMode(failureMode_e mode) { indicateFailure(mode, 10); #ifdef DEBUG systemReset(); #else systemResetToBootloader(BOOTLOADER_REQUEST_ROM); #endif } void initialiseMemorySections(void) { #ifdef USE_ITCM_RAM /* Load fast-functions into ITCM RAM */ extern uint8_t tcm_code_start; extern uint8_t tcm_code_end; extern uint8_t tcm_code; memcpy(&tcm_code_start, &tcm_code, (size_t) (&tcm_code_end - &tcm_code_start)); #endif #ifdef USE_CCM_CODE /* Load functions into RAM */ extern uint8_t ccm_code_start; extern uint8_t ccm_code_end; extern uint8_t ccm_code; memcpy(&ccm_code_start, &ccm_code, (size_t) (&ccm_code_end - &ccm_code_start)); #endif #ifdef USE_FAST_DATA /* Load FAST_DATA variable initializers into DTCM RAM */ extern uint8_t _sfastram_data; extern uint8_t _efastram_data; extern uint8_t _sfastram_idata; memcpy(&_sfastram_data, &_sfastram_idata, (size_t) (&_efastram_data - &_sfastram_data)); #endif #ifdef USE_RAM_CODE /* Load slow-functions into ITCM RAM */ extern uint8_t ram_code_start; extern uint8_t ram_code_end; extern uint8_t ram_code; memcpy(&ram_code_start, &ram_code, (size_t) (&ram_code_end - &ram_code_start)); #endif } static void unusedPinInit(IO_t io) { if (IOGetOwner(io) == OWNER_FREE) { IOConfigGPIO(io, IOCFG_IPU); } } void unusedPinsInit(void) { IOTraversePins(unusedPinInit); } const mcuTypeInfo_t *getMcuTypeInfo(void) { static const mcuTypeInfo_t info[] = { #if defined(STM32H743xx) { .id = MCU_TYPE_H743_REV_UNKNOWN, .name = "STM32H743 (Rev Unknown)" }, { .id = MCU_TYPE_H743_REV_Y, .name = "STM32H743 (Rev.Y)" }, { .id = MCU_TYPE_H743_REV_X, .name = "STM32H743 (Rev.X)" }, { .id = MCU_TYPE_H743_REV_V, .name = "STM32H743 (Rev.V)" }, #elif defined(STM32F40_41xxx) { .id = MCU_TYPE_F40X, .name = "STM32F40X" }, #elif defined(STM32F411xE) { .id = MCU_TYPE_F411, .name = "STM32F411" }, #elif defined(STM32F446xx) { .id = MCU_TYPE_F446, .name = "STM32F446" }, #elif defined(STM32F722xx) { .id = MCU_TYPE_F722, .name = "STM32F722" }, #elif defined(STM32F745xx) { .id = MCU_TYPE_F745, .name = "STM32F745" }, #elif defined(STM32F746xx) { .id = MCU_TYPE_F746, .name = "STM32F746" }, #elif defined(STM32F765xx) { .id = MCU_TYPE_F765, .name = "STM32F765" }, #elif defined(STM32H563xx) { .id = MCU_TYPE_H563, .name = "STM32H563" }, #elif defined(STM32H750xx) { .id = MCU_TYPE_H750, .name = "STM32H750" }, #elif defined(STM32H730xx) { .id = MCU_TYPE_H730, .name = "STM32H730" }, #elif defined(STM32H7A3xx) || defined(STM32H7A3xxQ) { .id = MCU_TYPE_H7A3, .name = "STM32H7A3" }, #elif defined(STM32H723xx) || defined(STM32H725xx) { .id = MCU_TYPE_H723_725, .name = "STM32H723/H725" }, #elif defined(STM32G474xx) { .id = MCU_TYPE_G474, .name = "STM32G474" }, #elif defined(AT32F435G) { .id = MCU_TYPE_AT32F435G, .name = "AT32F435G" }, #elif defined(AT32F435M) { .id = MCU_TYPE_AT32F435M, .name = "AT32F435M" }, #elif defined(APM32F405) { .id = MCU_TYPE_APM32F405, .name = "APM32F405" }, #elif defined(APM32F407) { .id = MCU_TYPE_APM32F407, .name = "APM32F407" }, #elif defined(GD32F460) { .id = MCU_TYPE_GD32F460, .name = "GD32F460" }, #else #error MCU Type info not defined for STM (or clone) #endif }; unsigned revision = 0; #if defined(STM32H743xx) switch (HAL_GetREVID()) { case REV_ID_Y: revision = 1; break; case REV_ID_X: revision = 2; break; case REV_ID_V: revision = 3; break; default: revision = 0; } #endif return info + revision; }