makes GPIO_PIN_RST optional for the sx1276
[ExpressLRS.git] / src / lib / HWTIMER / STM32_hwTimer.cpp
blobde9071c27eedc8f09005cfa08f9f33c1d3e82b44
1 #ifdef PLATFORM_STM32
2 #include "STM32_hwTimer.h"
4 void inline hwTimer::nullCallback(void) {}
6 void (*hwTimer::callbackTick)() = &nullCallback;
7 void (*hwTimer::callbackTock)() = &nullCallback;
9 volatile uint32_t hwTimer::HWtimerInterval = TimerIntervalUSDefault;
10 volatile bool hwTimer::isTick = false;
11 volatile int32_t hwTimer::PhaseShift = 0;
12 volatile int32_t hwTimer::FreqOffset = 0;
13 volatile uint32_t hwTimer::PauseDuration = 0;
14 bool hwTimer::running = false;
15 bool hwTimer::alreadyInit = false;
17 #if defined(TIM1)
18 HardwareTimer(*hwTimer::MyTim) = new HardwareTimer(TIM1);
19 #else
20 // FM30_mini (STM32F373xC) no advanced timer but TIM2 is 32-bit general purpose
21 HardwareTimer(*hwTimer::MyTim) = new HardwareTimer(TIM2);
22 #endif
24 void hwTimer::init()
26 if (!alreadyInit)
28 MyTim->attachInterrupt(hwTimer::callback);
29 MyTim->setMode(1, TIMER_OUTPUT_COMPARE);
30 #if defined(TARGET_TX)
31 // The prescaler only adjusts AFTER the overflow interrupt fires so
32 // to make Pause() work, the prescaler needs to be fixed to avoid
33 // having to ramp between prescalers
34 MyTim->setPrescaleFactor(MyTim->getTimerClkFreq() / 1000000); // 1us per tick
35 MyTim->setOverflow(hwTimer::HWtimerInterval >> 1, TICK_FORMAT);
36 #else
37 MyTim->setOverflow(hwTimer::HWtimerInterval >> 1, MICROSEC_FORMAT); // 22(50Hz) to 3(500Hz) scaler
38 #endif
39 MyTim->setPreloadEnable(false);
40 alreadyInit = true;
44 void hwTimer::stop()
46 running = false;
47 MyTim->pause();
48 MyTim->setCount(0);
52 * Schedule a pause of the specified duration, in us -- TX Only
53 * Will pause until the TICK interrupt, then the next timer will
54 * fire Duration - interval/2 after that
55 * 65535us max!
57 void hwTimer::pause(uint32_t duration)
59 #if defined(TARGET_TX)
60 PauseDuration = duration;
61 while(PauseDuration);
62 #endif
65 void hwTimer::resume()
67 isTick = false;
68 running = true;
69 #if defined(TARGET_TX)
70 MyTim->setOverflow(hwTimer::HWtimerInterval >> 1, TICK_FORMAT);
71 #else
72 MyTim->setOverflow((hwTimer::HWtimerInterval >> 1), MICROSEC_FORMAT);
73 #endif
74 MyTim->setCount(0);
75 MyTim->resume();
76 MyTim->refresh(); // will trigger the interrupt immediately, but will update the prescaler shadow reg
79 void hwTimer::updateInterval(uint32_t newTimerInterval)
81 // timer should not be running when updateInterval() is called
82 hwTimer::HWtimerInterval = newTimerInterval;
85 void hwTimer::resetFreqOffset()
87 FreqOffset = 0;
90 void hwTimer::incFreqOffset()
92 FreqOffset++;
95 void hwTimer::decFreqOffset()
97 FreqOffset--;
100 void hwTimer::phaseShift(int32_t newPhaseShift)
102 int32_t minVal = -(hwTimer::HWtimerInterval >> 2);
103 int32_t maxVal = (hwTimer::HWtimerInterval >> 2);
104 hwTimer::PhaseShift = constrain(newPhaseShift, minVal, maxVal);
107 void hwTimer::callback(void)
109 if (hwTimer::isTick)
111 #if defined(TARGET_TX)
112 if (PauseDuration)
114 MyTim->setOverflow(PauseDuration - (hwTimer::HWtimerInterval >> 1), TICK_FORMAT);
115 PauseDuration = 0;
116 // No tick callback
118 else
120 MyTim->setOverflow(hwTimer::HWtimerInterval >> 1, TICK_FORMAT);
121 hwTimer::callbackTick();
123 #else
124 MyTim->setOverflow((hwTimer::HWtimerInterval >> 1), MICROSEC_FORMAT);
125 uint32_t adjustedInterval = MyTim->getOverflow(TICK_FORMAT) + FreqOffset;
126 MyTim->setOverflow(adjustedInterval, TICK_FORMAT);
127 hwTimer::callbackTick();
128 #endif
130 else
132 #if defined(TARGET_TX)
133 MyTim->setOverflow(hwTimer::HWtimerInterval >> 1, TICK_FORMAT);
134 hwTimer::callbackTock();
135 #else
136 MyTim->setOverflow((hwTimer::HWtimerInterval >> 1) + hwTimer::PhaseShift, MICROSEC_FORMAT);
137 uint32_t adjustedInterval = MyTim->getOverflow(TICK_FORMAT) + FreqOffset;
138 MyTim->setOverflow(adjustedInterval, TICK_FORMAT);
139 hwTimer::PhaseShift = 0;
140 hwTimer::callbackTock();
141 #endif
143 hwTimer::isTick = !hwTimer::isTick;
145 #endif