APM:Libraries
stopwatch.c
Go to the documentation of this file.
1 #pragma GCC optimize ("O2")
2 
3 #include <stm32f4xx.h>
4 #include <hal.h>
5 /*
6  * Provides a micro-second granular delay using the CPU cycle counter.
7  */
8 
9 /* cycles per microsecond */
10 uint32_t us_ticks;
11 
12 void stopwatch_init(void)
13 {
14  us_ticks = SystemCoreClock / 1000000;
15 
16  /* turn on access to the DWT registers */
17  DEMCR |= DEMCR_TRCENA;
18  /* enable the CPU cycle counter */
19  DWT_CTRL |= CYCCNTENA;
20 
22 }
23 
24 
25 void stopwatch_delay_us(uint32_t us){
26 // we don't call stopwatch_reset() because any delay() in interrupt will reset main counter. It should be free running
27  uint32_t ts = stopwatch_getticks(); // start time in ticks
28  uint32_t dly = us * us_ticks; // delay in ticks
29  while(1) {
30  uint32_t now = stopwatch_getticks(); // current time in ticks
31  uint32_t dt = now - ts;
32 
33  if (dt >= dly)
34  break;
35  }
36 }
static uint32_t stopwatch_getticks()
Definition: stopwatch.h:33
uint32_t SystemCoreClock
void stopwatch_init(void)
Definition: stopwatch.c:12
#define DEMCR
Definition: stopwatch.h:14
#define CYCCNTENA
Definition: stopwatch.h:17
#define DWT_CTRL
Definition: stopwatch.h:16
uint32_t us_ticks
Definition: stopwatch.c:10
#define DEMCR_TRCENA
Definition: stopwatch.h:11
static void stopwatch_reset(void)
Definition: stopwatch.h:24
void stopwatch_delay_us(uint32_t us)
Definition: stopwatch.c:25