SimpleFOClibrary  2.1
stm32_mcu.cpp
Go to the documentation of this file.
1 
2 #include "../hardware_api.h"
3 
4 #if defined(_STM32_DEF_)
5 // default pwm parameters
6 #define _PWM_RESOLUTION 12 // 12bit
7 #define _PWM_RANGE 4095.0// 2^12 -1 = 4095
8 #define _PWM_FREQUENCY 25000 // 25khz
9 #define _PWM_FREQUENCY_MAX 50000 // 50khz
10 
11 // 6pwm parameters
12 #define _HARDWARE_6PWM 1
13 #define _SOFTWARE_6PWM 0
14 #define _ERROR_6PWM -1
15 
16 
17 // setting pwm to hardware pin - instead analogWrite()
18 void _setPwm(int ulPin, uint32_t value, int resolution)
19 {
20  PinName pin = digitalPinToPinName(ulPin);
21  TIM_TypeDef *Instance = (TIM_TypeDef *)pinmap_peripheral(pin, PinMap_PWM);
22  uint32_t index = get_timer_index(Instance);
23  HardwareTimer *HT = (HardwareTimer *)(HardwareTimer_Handle[index]->__this);
24 
25  uint32_t channel = STM_PIN_CHANNEL(pinmap_function(pin, PinMap_PWM));
26  HT->setCaptureCompare(channel, value, (TimerCompareFormat_t)resolution);
27 }
28 
29 
30 // init pin pwm
31 HardwareTimer* _initPinPWM(uint32_t PWM_freq, int ulPin)
32 {
33  PinName pin = digitalPinToPinName(ulPin);
34  TIM_TypeDef *Instance = (TIM_TypeDef *)pinmap_peripheral(pin, PinMap_PWM);
35 
36  uint32_t index = get_timer_index(Instance);
37  if (HardwareTimer_Handle[index] == NULL) {
38  HardwareTimer_Handle[index]->__this = new HardwareTimer((TIM_TypeDef *)pinmap_peripheral(pin, PinMap_PWM));
39  HardwareTimer_Handle[index]->handle.Init.CounterMode = TIM_COUNTERMODE_CENTERALIGNED3;
40  HAL_TIM_Base_Init(&(HardwareTimer_Handle[index]->handle));
41  }
42  HardwareTimer *HT = (HardwareTimer *)(HardwareTimer_Handle[index]->__this);
43  uint32_t channel = STM_PIN_CHANNEL(pinmap_function(pin, PinMap_PWM));
44  HT->setMode(channel, TIMER_OUTPUT_COMPARE_PWM1, pin);
45  HT->setOverflow(PWM_freq, HERTZ_FORMAT);
46  HT->pause();
47  HT->refresh();
48  return HT;
49 }
50 
51 
52 // init high side pin
53 HardwareTimer* _initPinPWMHigh(uint32_t PWM_freq, int ulPin)
54 {
55  return _initPinPWM(PWM_freq, ulPin);
56 }
57 
58 // init low side pin
59 HardwareTimer* _initPinPWMLow(uint32_t PWM_freq, int ulPin)
60 {
61  PinName pin = digitalPinToPinName(ulPin);
62  TIM_TypeDef *Instance = (TIM_TypeDef *)pinmap_peripheral(pin, PinMap_PWM);
63  uint32_t index = get_timer_index(Instance);
64 
65  if (HardwareTimer_Handle[index] == NULL) {
66  HardwareTimer_Handle[index]->__this = new HardwareTimer((TIM_TypeDef *)pinmap_peripheral(pin, PinMap_PWM));
67  HardwareTimer_Handle[index]->handle.Init.CounterMode = TIM_COUNTERMODE_CENTERALIGNED3;
68  HAL_TIM_Base_Init(&(HardwareTimer_Handle[index]->handle));
69  TIM_OC_InitTypeDef sConfigOC = TIM_OC_InitTypeDef();
70  sConfigOC.OCMode = TIM_OCMODE_PWM2;
71  sConfigOC.Pulse = 100;
72  sConfigOC.OCPolarity = TIM_OCPOLARITY_LOW;
73  sConfigOC.OCNPolarity = TIM_OCNPOLARITY_HIGH;
74  sConfigOC.OCFastMode = TIM_OCFAST_DISABLE;
75  sConfigOC.OCIdleState = TIM_OCIDLESTATE_SET;
76  sConfigOC.OCNIdleState = TIM_OCNIDLESTATE_RESET;
77  uint32_t channel = STM_PIN_CHANNEL(pinmap_function(pin, PinMap_PWM));
78  HAL_TIM_PWM_ConfigChannel(&(HardwareTimer_Handle[index]->handle), &sConfigOC, channel);
79  }
80  HardwareTimer *HT = (HardwareTimer *)(HardwareTimer_Handle[index]->__this);
81  uint32_t channel = STM_PIN_CHANNEL(pinmap_function(pin, PinMap_PWM));
82  HT->setMode(channel, TIMER_OUTPUT_COMPARE_PWM2, pin);
83  HT->setOverflow(PWM_freq, HERTZ_FORMAT);
84  HT->pause();
85  HT->refresh();
86  return HT;
87 }
88 
89 
90 // align the timers to end the init
91 void _alignPWMTimers(HardwareTimer *HT1,HardwareTimer *HT2,HardwareTimer *HT3)
92 {
93  HT1->pause();
94  HT1->refresh();
95  HT2->pause();
96  HT2->refresh();
97  HT3->pause();
98  HT3->refresh();
99  HT1->resume();
100  HT2->resume();
101  HT3->resume();
102 }
103 
104 // align the timers to end the init
105 void _alignPWMTimers(HardwareTimer *HT1,HardwareTimer *HT2,HardwareTimer *HT3,HardwareTimer *HT4)
106 {
107  HT1->pause();
108  HT1->refresh();
109  HT2->pause();
110  HT2->refresh();
111  HT3->pause();
112  HT3->refresh();
113  HT4->pause();
114  HT4->refresh();
115  HT1->resume();
116  HT2->resume();
117  HT3->resume();
118  HT4->resume();
119 }
120 
121 // configure hardware 6pwm interface only one timer with inverted channels
122 HardwareTimer* _initHardware6PWMInterface(uint32_t PWM_freq, float dead_zone, int pinA_h, int pinA_l, int pinB_h, int pinB_l, int pinC_h, int pinC_l)
123 {
124  PinName uhPinName = digitalPinToPinName(pinA_h);
125  PinName ulPinName = digitalPinToPinName(pinA_l);
126  PinName vhPinName = digitalPinToPinName(pinB_h);
127  PinName vlPinName = digitalPinToPinName(pinB_l);
128  PinName whPinName = digitalPinToPinName(pinC_h);
129  PinName wlPinName = digitalPinToPinName(pinC_l);
130 
131  TIM_TypeDef *Instance = (TIM_TypeDef *)pinmap_peripheral(uhPinName, PinMap_PWM);
132 
133  uint32_t index = get_timer_index(Instance);
134 
135  if (HardwareTimer_Handle[index] == NULL) {
136  HardwareTimer_Handle[index]->__this = new HardwareTimer((TIM_TypeDef *)pinmap_peripheral(uhPinName, PinMap_PWM));
137  HardwareTimer_Handle[index]->handle.Init.CounterMode = TIM_COUNTERMODE_CENTERALIGNED3;
138  HAL_TIM_Base_Init(&(HardwareTimer_Handle[index]->handle));
139  ((HardwareTimer *)HardwareTimer_Handle[index]->__this)->setOverflow(PWM_freq, HERTZ_FORMAT);
140  }
141  HardwareTimer *HT = (HardwareTimer *)(HardwareTimer_Handle[index]->__this);
142 
143  HT->setMode(STM_PIN_CHANNEL(pinmap_function(uhPinName, PinMap_PWM)), TIMER_OUTPUT_COMPARE_PWM1, uhPinName);
144  HT->setMode(STM_PIN_CHANNEL(pinmap_function(ulPinName, PinMap_PWM)), TIMER_OUTPUT_COMPARE_PWM1, ulPinName);
145  HT->setMode(STM_PIN_CHANNEL(pinmap_function(vhPinName, PinMap_PWM)), TIMER_OUTPUT_COMPARE_PWM1, vhPinName);
146  HT->setMode(STM_PIN_CHANNEL(pinmap_function(vlPinName, PinMap_PWM)), TIMER_OUTPUT_COMPARE_PWM1, vlPinName);
147  HT->setMode(STM_PIN_CHANNEL(pinmap_function(whPinName, PinMap_PWM)), TIMER_OUTPUT_COMPARE_PWM1, whPinName);
148  HT->setMode(STM_PIN_CHANNEL(pinmap_function(wlPinName, PinMap_PWM)), TIMER_OUTPUT_COMPARE_PWM1, wlPinName);
149 
150  // dead time is set in nanoseconds
151  uint32_t dead_time_ns = (float)(1e9/PWM_freq)*dead_zone;
152  uint32_t dead_time = __LL_TIM_CALC_DEADTIME(SystemCoreClock, LL_TIM_GetClockDivision(HT->getHandle()->Instance), dead_time_ns);
153  LL_TIM_OC_SetDeadTime(HT->getHandle()->Instance, dead_time); // deadtime is non linear!
154  LL_TIM_CC_EnableChannel(HT->getHandle()->Instance, LL_TIM_CHANNEL_CH1 | LL_TIM_CHANNEL_CH1N | LL_TIM_CHANNEL_CH2 | LL_TIM_CHANNEL_CH2N | LL_TIM_CHANNEL_CH3 | LL_TIM_CHANNEL_CH3N);
155 
156  HT->pause();
157  HT->refresh();
158  HT->resume();
159  return HT;
160 }
161 
162 
163 // returns 0 if each pair of pwm channels has same channel
164 // returns 1 all the channels belong to the same timer - hardware inverted channels
165 // returns -1 if neither - avoid configuring - error!!!
166 int _interfaceType(const int pinA_h, const int pinA_l, const int pinB_h, const int pinB_l, const int pinC_h, const int pinC_l){
167  PinName nameAH = digitalPinToPinName(pinA_h);
168  PinName nameAL = digitalPinToPinName(pinA_l);
169  PinName nameBH = digitalPinToPinName(pinB_h);
170  PinName nameBL = digitalPinToPinName(pinB_l);
171  PinName nameCH = digitalPinToPinName(pinC_h);
172  PinName nameCL = digitalPinToPinName(pinC_l);
173  int tim1 = get_timer_index((TIM_TypeDef *)pinmap_peripheral(nameAH, PinMap_PWM));
174  int tim2 = get_timer_index((TIM_TypeDef *)pinmap_peripheral(nameAL, PinMap_PWM));
175  int tim3 = get_timer_index((TIM_TypeDef *)pinmap_peripheral(nameBH, PinMap_PWM));
176  int tim4 = get_timer_index((TIM_TypeDef *)pinmap_peripheral(nameBL, PinMap_PWM));
177  int tim5 = get_timer_index((TIM_TypeDef *)pinmap_peripheral(nameCH, PinMap_PWM));
178  int tim6 = get_timer_index((TIM_TypeDef *)pinmap_peripheral(nameCL, PinMap_PWM));
179  if(tim1 == tim2 && tim2==tim3 && tim3==tim4 && tim4==tim5 && tim5==tim6)
180  return _HARDWARE_6PWM; // hardware 6pwm interface - only on timer
181  else if(tim1 == tim2 && tim3==tim4 && tim5==tim6)
182  return _SOFTWARE_6PWM; // software 6pwm interface - each pair of high-low side same timer
183  else
184  return _ERROR_6PWM; // might be error avoid configuration
185 }
186 
187 
188 
189 // function setting the high pwm frequency to the supplied pins
190 // - Stepper motor - 2PWM setting
191 // - hardware speciffic
192 void _configure2PWM(long pwm_frequency,const int pinA, const int pinB) {
193  if( !pwm_frequency || !_isset(pwm_frequency) ) pwm_frequency = _PWM_FREQUENCY; // default frequency 25khz
194  else pwm_frequency = _constrain(pwm_frequency, 0, _PWM_FREQUENCY_MAX); // constrain to 50kHz max
195  // center-aligned frequency is uses two periods
196  pwm_frequency *=2;
197 
198  HardwareTimer* HT1 = _initPinPWM(pwm_frequency, pinA);
199  HardwareTimer* HT2 = _initPinPWM(pwm_frequency, pinB);
200  // allign the timers
201  _alignPWMTimers(HT1, HT2, HT2);
202 }
203 
204 
205 // function setting the high pwm frequency to the supplied pins
206 // - BLDC motor - 3PWM setting
207 // - hardware speciffic
208 void _configure3PWM(long pwm_frequency,const int pinA, const int pinB, const int pinC) {
209  if( !pwm_frequency || !_isset(pwm_frequency) ) pwm_frequency = _PWM_FREQUENCY; // default frequency 25khz
210  else pwm_frequency = _constrain(pwm_frequency, 0, _PWM_FREQUENCY_MAX); // constrain to 50kHz max
211  // center-aligned frequency is uses two periods
212  pwm_frequency *=2;
213 
214  HardwareTimer* HT1 = _initPinPWM(pwm_frequency, pinA);
215  HardwareTimer* HT2 = _initPinPWM(pwm_frequency, pinB);
216  HardwareTimer* HT3 = _initPinPWM(pwm_frequency, pinC);
217  // allign the timers
218  _alignPWMTimers(HT1, HT2, HT3);
219 }
220 
221 // function setting the high pwm frequency to the supplied pins
222 // - Stepper motor - 4PWM setting
223 // - hardware speciffic
224 void _configure4PWM(long pwm_frequency,const int pinA, const int pinB, const int pinC, const int pinD) {
225  if( !pwm_frequency || !_isset(pwm_frequency) ) pwm_frequency = _PWM_FREQUENCY; // default frequency 25khz
226  else pwm_frequency = _constrain(pwm_frequency, 0, _PWM_FREQUENCY_MAX); // constrain to 50kHz max
227  // center-aligned frequency is uses two periods
228  pwm_frequency *=2;
229 
230  HardwareTimer* HT1 = _initPinPWM(pwm_frequency, pinA);
231  HardwareTimer* HT2 = _initPinPWM(pwm_frequency, pinB);
232  HardwareTimer* HT3 = _initPinPWM(pwm_frequency, pinC);
233  HardwareTimer* HT4 = _initPinPWM(pwm_frequency, pinD);
234  // allign the timers
235  _alignPWMTimers(HT1, HT2, HT3, HT4);
236 }
237 
238 // function setting the pwm duty cycle to the hardware
239 // - Stepper motor - 2PWM setting
240 //- hardware speciffic
241 void _writeDutyCycle2PWM(float dc_a, float dc_b, int pinA, int pinB){
242  // transform duty cycle from [0,1] to [0,4095]
243  _setPwm(pinA, _PWM_RANGE*dc_a, _PWM_RESOLUTION);
244  _setPwm(pinB, _PWM_RANGE*dc_b, _PWM_RESOLUTION);
245 }
246 
247 // function setting the pwm duty cycle to the hardware
248 // - BLDC motor - 3PWM setting
249 //- hardware speciffic
250 void _writeDutyCycle3PWM(float dc_a, float dc_b, float dc_c, int pinA, int pinB, int pinC){
251  // transform duty cycle from [0,1] to [0,4095]
252  _setPwm(pinA, _PWM_RANGE*dc_a, _PWM_RESOLUTION);
253  _setPwm(pinB, _PWM_RANGE*dc_b, _PWM_RESOLUTION);
254  _setPwm(pinC, _PWM_RANGE*dc_c, _PWM_RESOLUTION);
255 }
256 
257 
258 // function setting the pwm duty cycle to the hardware
259 // - Stepper motor - 4PWM setting
260 //- hardware speciffic
261 void _writeDutyCycle4PWM(float dc_1a, float dc_1b, float dc_2a, float dc_2b, int pin1A, int pin1B, int pin2A, int pin2B){
262  // transform duty cycle from [0,1] to [0,4095]
263  _setPwm(pin1A, _PWM_RANGE*dc_1a, _PWM_RESOLUTION);
264  _setPwm(pin1B, _PWM_RANGE*dc_1b, _PWM_RESOLUTION);
265  _setPwm(pin2A, _PWM_RANGE*dc_2a, _PWM_RESOLUTION);
266  _setPwm(pin2B, _PWM_RANGE*dc_2b, _PWM_RESOLUTION);
267 }
268 
269 
270 
271 
272 // Configuring PWM frequency, resolution and alignment
273 // - BLDC driver - 6PWM setting
274 // - hardware specific
275 int _configure6PWM(long pwm_frequency, float dead_zone, const int pinA_h, const int pinA_l, const int pinB_h, const int pinB_l, const int pinC_h, const int pinC_l){
276  if( !pwm_frequency || !_isset(pwm_frequency) ) pwm_frequency = _PWM_FREQUENCY; // default frequency 25khz
277  else pwm_frequency = _constrain(pwm_frequency, 0, _PWM_FREQUENCY_MAX); // constrain to |%0kHz max
278  // center-aligned frequency is uses two periods
279  pwm_frequency *=2;
280 
281  // find configuration
282  int config = _interfaceType(pinA_h, pinA_l, pinB_h, pinB_l, pinC_h, pinC_l);
283  // configure accordingly
284  switch(config){
285  case _ERROR_6PWM:
286  return -1; // fail
287  break;
288  case _HARDWARE_6PWM:
289  _initHardware6PWMInterface(pwm_frequency, dead_zone, pinA_h, pinA_l, pinB_h, pinB_l, pinC_h, pinC_l);
290  break;
291  case _SOFTWARE_6PWM:
292  HardwareTimer* HT1 = _initPinPWMHigh(pwm_frequency, pinA_h);
293  _initPinPWMLow(pwm_frequency, pinA_l);
294  HardwareTimer* HT2 = _initPinPWMHigh(pwm_frequency,pinB_h);
295  _initPinPWMLow(pwm_frequency, pinB_l);
296  HardwareTimer* HT3 = _initPinPWMHigh(pwm_frequency,pinC_h);
297  _initPinPWMLow(pwm_frequency, pinC_l);
298  _alignPWMTimers(HT1, HT2, HT3);
299  break;
300  }
301  return 0; // success
302 }
303 
304 // Function setting the duty cycle to the pwm pin (ex. analogWrite())
305 // - BLDC driver - 6PWM setting
306 // - hardware specific
307 void _writeDutyCycle6PWM(float dc_a, float dc_b, float dc_c, float dead_zone, int pinA_h, int pinA_l, int pinB_h, int pinB_l, int pinC_h, int pinC_l){
308  // find configuration
309  int config = _interfaceType(pinA_h, pinA_l, pinB_h, pinB_l, pinC_h, pinC_l);
310  // set pwm accordingly
311  switch(config){
312  case _HARDWARE_6PWM:
313  _setPwm(pinA_h, _PWM_RANGE*dc_a, _PWM_RESOLUTION);
314  _setPwm(pinB_h, _PWM_RANGE*dc_b, _PWM_RESOLUTION);
315  _setPwm(pinC_h, _PWM_RANGE*dc_c, _PWM_RESOLUTION);
316  break;
317  case _SOFTWARE_6PWM:
318  _setPwm(pinA_l, _constrain(dc_a + dead_zone/2, 0, 1)*_PWM_RANGE, _PWM_RESOLUTION);
319  _setPwm(pinA_h, _constrain(dc_a - dead_zone/2, 0, 1)*_PWM_RANGE, _PWM_RESOLUTION);
320  _setPwm(pinB_l, _constrain(dc_b + dead_zone/2, 0, 1)*_PWM_RANGE, _PWM_RESOLUTION);
321  _setPwm(pinB_h, _constrain(dc_b - dead_zone/2, 0, 1)*_PWM_RANGE, _PWM_RESOLUTION);
322  _setPwm(pinC_l, _constrain(dc_c + dead_zone/2, 0, 1)*_PWM_RANGE, _PWM_RESOLUTION);
323  _setPwm(pinC_h, _constrain(dc_c - dead_zone/2, 0, 1)*_PWM_RANGE, _PWM_RESOLUTION);
324  break;
325  }
326 }
327 #endif
_configure3PWM
void _configure3PWM(long pwm_frequency, const int pinA, const int pinB, const int pinC)
Definition: drivers/hardware_specific/generic_mcu.cpp:31
_configure4PWM
void _configure4PWM(long pwm_frequency, const int pin1A, const int pin1B, const int pin2A, const int pin2B)
Definition: drivers/hardware_specific/generic_mcu.cpp:40
_constrain
#define _constrain(amt, low, high)
Definition: foc_utils.h:9
_isset
#define _isset(a)
Definition: foc_utils.h:11
_writeDutyCycle3PWM
void _writeDutyCycle3PWM(float dc_a, float dc_b, float dc_c, int pinA, int pinB, int pinC)
Definition: drivers/hardware_specific/generic_mcu.cpp:64
_writeDutyCycle2PWM
void _writeDutyCycle2PWM(float dc_a, float dc_b, int pinA, int pinB)
Definition: drivers/hardware_specific/generic_mcu.cpp:55
_writeDutyCycle4PWM
void _writeDutyCycle4PWM(float dc_1a, float dc_1b, float dc_2a, float dc_2b, int pin1A, int pin1B, int pin2A, int pin2B)
Definition: drivers/hardware_specific/generic_mcu.cpp:74
_writeDutyCycle6PWM
void _writeDutyCycle6PWM(float dc_a, float dc_b, float dc_c, float dead_zone, int pinA_h, int pinA_l, int pinB_h, int pinB_l, int pinC_h, int pinC_l)
Definition: drivers/hardware_specific/generic_mcu.cpp:86
_configure6PWM
int _configure6PWM(long pwm_frequency, float dead_zone, const int pinA_h, const int pinA_l, const int pinB_h, const int pinB_l, const int pinC_h, const int pinC_l)
Definition: drivers/hardware_specific/generic_mcu.cpp:47
_configure2PWM
void _configure2PWM(long pwm_frequency, const int pinA, const int pinB)
Definition: drivers/hardware_specific/generic_mcu.cpp:23