Fix function brace style
[betaflight.git] / src / main / drivers / system.c
blobb17522d848a93706114a6119c0e771418aac4997
1 /*
2 * This file is part of Cleanflight and Betaflight.
4 * Cleanflight and Betaflight are free software. You can redistribute
5 * this software and/or modify this software under the terms of the
6 * GNU General Public License as published by the Free Software
7 * Foundation, either version 3 of the License, or (at your option)
8 * any later version.
10 * Cleanflight and Betaflight are distributed in the hope that they
11 * will be useful, but WITHOUT ANY WARRANTY; without even the implied
12 * warranty of MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.
13 * See the GNU General Public License for more details.
15 * You should have received a copy of the GNU General Public License
16 * along with this software.
18 * If not, see <http://www.gnu.org/licenses/>.
21 #include <stdbool.h>
22 #include <stdint.h>
23 #include <string.h>
25 #include "platform.h"
27 #include "build/atomic.h"
29 #include "drivers/io.h"
30 #include "drivers/light_led.h"
31 #include "drivers/nvic.h"
32 #include "drivers/resource.h"
33 #include "drivers/sound_beeper.h"
36 #include "system.h"
38 #if defined(STM32F4) || defined(STM32F7) || defined(STM32H7)
39 // See "RM CoreSight Architecture Specification"
40 // B2.3.10 "LSR and LAR, Software Lock Status Register and Software Lock Access Register"
41 // "E1.2.11 LAR, Lock Access Register"
43 #define DWT_LAR_UNLOCK_VALUE 0xC5ACCE55
45 #endif
47 // cycles per microsecond
48 static uint32_t usTicks = 0;
49 // current uptime for 1kHz systick timer. will rollover after 49 days. hopefully we won't care.
50 static volatile uint32_t sysTickUptime = 0;
51 static volatile uint32_t sysTickValStamp = 0;
52 // cached value of RCC->CSR
53 uint32_t cachedRccCsrValue;
54 static uint32_t cpuClockFrequency = 0;
56 void cycleCounterInit(void)
58 #if defined(USE_HAL_DRIVER)
59 cpuClockFrequency = HAL_RCC_GetSysClockFreq();
60 #else
61 RCC_ClocksTypeDef clocks;
62 RCC_GetClocksFreq(&clocks);
63 cpuClockFrequency = clocks.SYSCLK_Frequency;
64 #endif
65 usTicks = cpuClockFrequency / 1000000;
67 CoreDebug->DEMCR |= CoreDebug_DEMCR_TRCENA_Msk;
69 #if defined(DWT_LAR_UNLOCK_VALUE)
70 #if defined(STM32H7)
71 ITM->LAR = DWT_LAR_UNLOCK_VALUE;
72 #elif defined(STM32F7)
73 DWT->LAR = DWT_LAR_UNLOCK_VALUE;
74 #elif defined(STM32F4)
75 // Note: DWT_Type does not contain LAR member.
76 #define DWT_LAR
77 __O uint32_t *DWTLAR = (uint32_t *)(DWT_BASE + 0x0FB0);
78 *(DWTLAR) = DWT_LAR_UNLOCK_VALUE;
79 #endif
80 #endif
82 DWT->CYCCNT = 0;
83 DWT->CTRL |= DWT_CTRL_CYCCNTENA_Msk;
86 // SysTick
88 static volatile int sysTickPending = 0;
90 void SysTick_Handler(void)
92 ATOMIC_BLOCK(NVIC_PRIO_MAX) {
93 sysTickUptime++;
94 sysTickValStamp = SysTick->VAL;
95 sysTickPending = 0;
96 (void)(SysTick->CTRL);
98 #ifdef USE_HAL_DRIVER
99 // used by the HAL for some timekeeping and timeouts, should always be 1ms
100 HAL_IncTick();
101 #endif
104 // Return system uptime in microseconds (rollover in 70minutes)
106 uint32_t microsISR(void)
108 register uint32_t ms, pending, cycle_cnt;
110 ATOMIC_BLOCK(NVIC_PRIO_MAX) {
111 cycle_cnt = SysTick->VAL;
113 if (SysTick->CTRL & SysTick_CTRL_COUNTFLAG_Msk) {
114 // Update pending.
115 // Record it for multiple calls within the same rollover period
116 // (Will be cleared when serviced).
117 // Note that multiple rollovers are not considered.
119 sysTickPending = 1;
121 // Read VAL again to ensure the value is read after the rollover.
123 cycle_cnt = SysTick->VAL;
126 ms = sysTickUptime;
127 pending = sysTickPending;
130 return ((ms + pending) * 1000) + (usTicks * 1000 - cycle_cnt) / usTicks;
133 uint32_t micros(void)
135 register uint32_t ms, cycle_cnt;
137 // Call microsISR() in interrupt and elevated (non-zero) BASEPRI context
139 if ((SCB->ICSR & SCB_ICSR_VECTACTIVE_Msk) || (__get_BASEPRI())) {
140 return microsISR();
143 do {
144 ms = sysTickUptime;
145 cycle_cnt = SysTick->VAL;
146 } while (ms != sysTickUptime || cycle_cnt > sysTickValStamp);
148 return (ms * 1000) + (usTicks * 1000 - cycle_cnt) / usTicks;
151 uint32_t getCycleCounter(void)
153 return DWT->CYCCNT;
156 int32_t clockCyclesToMicros(int32_t clockCycles)
158 return clockCycles / usTicks;
161 // Note that this conversion is signed as this is used for periods rather than absolute timestamps
162 int32_t clockCyclesTo10thMicros(int32_t clockCycles)
164 return 10 * clockCycles / (int32_t)usTicks;
167 uint32_t clockMicrosToCycles(uint32_t micros)
169 return micros * usTicks;
172 // Return system uptime in milliseconds (rollover in 49 days)
173 uint32_t millis(void)
175 return sysTickUptime;
178 #if 1
179 void delayMicroseconds(uint32_t us)
181 uint32_t now = micros();
182 while (micros() - now < us);
184 #else
185 void delayMicroseconds(uint32_t us)
187 uint32_t elapsed = 0;
188 uint32_t lastCount = SysTick->VAL;
190 for (;;) {
191 register uint32_t current_count = SysTick->VAL;
192 uint32_t elapsed_us;
194 // measure the time elapsed since the last time we checked
195 elapsed += current_count - lastCount;
196 lastCount = current_count;
198 // convert to microseconds
199 elapsed_us = elapsed / usTicks;
200 if (elapsed_us >= us)
201 break;
203 // reduce the delay by the elapsed time
204 us -= elapsed_us;
206 // keep fractional microseconds for the next iteration
207 elapsed %= usTicks;
210 #endif
212 void delay(uint32_t ms)
214 while (ms--)
215 delayMicroseconds(1000);
218 static void indicate(uint8_t count, uint16_t duration)
220 if (count) {
221 LED1_ON;
222 LED0_OFF;
224 while (count--) {
225 LED1_TOGGLE;
226 LED0_TOGGLE;
227 BEEP_ON;
228 delay(duration);
230 LED1_TOGGLE;
231 LED0_TOGGLE;
232 BEEP_OFF;
233 delay(duration);
238 void indicateFailure(failureMode_e mode, int codeRepeatsRemaining)
240 while (codeRepeatsRemaining--) {
241 indicate(WARNING_FLASH_COUNT, WARNING_FLASH_DURATION_MS);
243 delay(WARNING_PAUSE_DURATION_MS);
245 indicate(mode + 1, WARNING_CODE_DURATION_LONG_MS);
247 delay(1000);
251 void failureMode(failureMode_e mode)
253 indicateFailure(mode, 10);
255 #ifdef DEBUG
256 systemReset();
257 #else
258 systemResetToBootloader(BOOTLOADER_REQUEST_ROM);
259 #endif
262 void initialiseMemorySections(void)
264 #ifdef USE_ITCM_RAM
265 /* Load functions into ITCM RAM */
266 extern uint8_t tcm_code_start;
267 extern uint8_t tcm_code_end;
268 extern uint8_t tcm_code;
269 memcpy(&tcm_code_start, &tcm_code, (size_t) (&tcm_code_end - &tcm_code_start));
270 #endif
272 #ifdef USE_CCM_CODE
273 /* Load functions into RAM */
274 extern uint8_t ccm_code_start;
275 extern uint8_t ccm_code_end;
276 extern uint8_t ccm_code;
277 memcpy(&ccm_code_start, &ccm_code, (size_t) (&ccm_code_end - &ccm_code_start));
278 #endif
280 #ifdef USE_FAST_DATA
281 /* Load FAST_DATA variable initializers into DTCM RAM */
282 extern uint8_t _sfastram_data;
283 extern uint8_t _efastram_data;
284 extern uint8_t _sfastram_idata;
285 memcpy(&_sfastram_data, &_sfastram_idata, (size_t) (&_efastram_data - &_sfastram_data));
286 #endif
289 #ifdef STM32H7
290 void initialiseD2MemorySections(void)
292 /* Load DMA_DATA variable intializers into D2 RAM */
293 extern uint8_t _sdmaram_bss;
294 extern uint8_t _edmaram_bss;
295 extern uint8_t _sdmaram_data;
296 extern uint8_t _edmaram_data;
297 extern uint8_t _sdmaram_idata;
298 bzero(&_sdmaram_bss, (size_t) (&_edmaram_bss - &_sdmaram_bss));
299 memcpy(&_sdmaram_data, &_sdmaram_idata, (size_t) (&_edmaram_data - &_sdmaram_data));
301 #endif
303 static void unusedPinInit(IO_t io)
305 if (IOGetOwner(io) == OWNER_FREE) {
306 IOConfigGPIO(io, IOCFG_IPU);
310 void unusedPinsInit(void)
312 IOTraversePins(unusedPinInit);