SimpleFOClibrary 2.4.0
Loading...
Searching...
No Matches
drivers/hardware_specific/teensy/teensy4_mcu.cpp
Go to the documentation of this file.
1#include "teensy4_mcu.h"
2#include "../../../communication/SimpleFOCDebug.h"
3
4// if defined
5// - Teensy 4.0
6// - Teensy 4.1
7#if defined(__arm__) && defined(CORE_TEENSY) && ( defined(__IMXRT1062__) || defined(ARDUINO_TEENSY40) || defined(ARDUINO_TEENSY41) || defined(ARDUINO_TEENSY_MICROMOD) )
8
9#pragma message("")
10#pragma message("SimpleFOC: compiling for Teensy 4.x")
11#pragma message("")
12
13// #define SIMPLEFOC_TEENSY4_FORCE_CENTER_ALIGNED_3PWM
14
15
16// function finding the TRIG event given the flexpwm timer and the submodule
17// returning -1 if the submodule is not valid or no trigger is available
18// allowing flexpwm1-4 and submodule 0-3
19//
20// the flags are defined in the imxrt.h file
21// https://github.com/PaulStoffregen/cores/blob/dd6aa8419ee173a0a6593eab669fbff54ed85f48/teensy4/imxrt.h#L9662-L9693
22int flexpwm_submodule_to_trig(IMXRT_FLEXPWM_t* flexpwm, int submodule){
23 if(submodule <0 && submodule > 3) return -1;
24 if(flexpwm == &IMXRT_FLEXPWM1){
25 return XBARA1_IN_FLEXPWM1_PWM1_OUT_TRIG0 + submodule;
26 }else if(flexpwm == &IMXRT_FLEXPWM2){
27 return XBARA1_IN_FLEXPWM2_PWM1_OUT_TRIG0 + submodule;
28 }else if(flexpwm == &IMXRT_FLEXPWM3){
29 return XBARA1_IN_FLEXPWM3_PWM1_OUT_TRIG0 + submodule;
30 }else if(flexpwm == &IMXRT_FLEXPWM4){
31 return XBARA1_IN_FLEXPWM4_PWM1_OUT_TRIG0 + submodule;
32 }
33 return -1;
34}
35
36// function finding the EXT_SYNC event given the flexpwm timer and the submodule
37// returning -1 if the submodule is not valid or no trigger is available
38// allowing flexpwm1-4 and submodule 0-3
39//
40// the flags are defined in the imxrt.h file
41// https://github.com/PaulStoffregen/cores/blob/dd6aa8419ee173a0a6593eab669fbff54ed85f48/teensy4/imxrt.h#L9757
42int flexpwm_submodule_to_ext_sync(IMXRT_FLEXPWM_t* flexpwm, int submodule){
43 if(submodule < 0 && submodule > 3) return -1;
44 if(flexpwm == &IMXRT_FLEXPWM1){
45 return XBARA1_OUT_FLEXPWM1_PWM0_EXT_SYNC + submodule;
46 }else if(flexpwm == &IMXRT_FLEXPWM2){
47 return XBARA1_OUT_FLEXPWM2_PWM0_EXT_SYNC + submodule;
48 }else if(flexpwm == &IMXRT_FLEXPWM3){
49 return XBARA1_OUT_FLEXPWM3_EXT_SYNC0 + submodule; // TODO verify why they are not called PWM0_EXT_SYNC but EXT_SYNC0
50 }else if(flexpwm == &IMXRT_FLEXPWM4){
51 return XBARA1_OUT_FLEXPWM4_EXT_SYNC0 + submodule; // TODO verify why they are not called PWM0_EXT_SYNC but EXT_SYNC0
52 }
53 return -1;
54}
55
56// function finding the flexpwm instance given the submodule
57int flexpwm_to_index(IMXRT_FLEXPWM_t* flexpwm){
58 if(flexpwm == &IMXRT_FLEXPWM1) return 1;
59 if(flexpwm == &IMXRT_FLEXPWM2) return 2;
60 if(flexpwm == &IMXRT_FLEXPWM3) return 3;
61 if(flexpwm == &IMXRT_FLEXPWM4) return 4;
62 return -1;
63}
64
65// The i.MXRT1062 uses one config register per two XBAR outputs, so a helper
66// function to make code more readable.
67void xbar_connect(unsigned int input, unsigned int output)
68{
69 if (input >= 88) return;
70 if (output >= 132) return;
71 volatile uint16_t *xbar = &XBARA1_SEL0 + (output / 2);
72 uint16_t val = *xbar;
73 if (!(output & 1)) {
74 val = (val & 0xFF00) | input;
75 } else {
76 val = (val & 0x00FF) | (input << 8);
77 }
78 *xbar = val;
79}
80
81void xbar_init() {
82 CCM_CCGR2 |= CCM_CCGR2_XBAR1(CCM_CCGR_ON); //turn clock on for xbara1
83}
84
85// function which finds the flexpwm instance for a pin
86// if it does not belong to the flexpwm timer it returns a null-pointer
87IMXRT_FLEXPWM_t* get_flexpwm(uint8_t pin){
88
89 const struct pwm_pin_info_struct *info;
90 info = pwm_pin_info + pin;
91 if (pin >= CORE_NUM_DIGITAL || info->type == 2) {
92#ifdef SIMPLEFOC_TEENSY_DEBUG
93 char s[60];
94 sprintf (s, "TEENSY-DRV: ERR: Pin: %d not Flextimer pin!", pin);
96#endif
97 return nullptr;
98 }
99 // FlexPWM pin
100 IMXRT_FLEXPWM_t *flexpwm;
101 switch ((info->module >> 4) & 3) {
102 case 0: flexpwm = &IMXRT_FLEXPWM1; break;
103 case 1: flexpwm = &IMXRT_FLEXPWM2; break;
104 case 2: flexpwm = &IMXRT_FLEXPWM3; break;
105 default: flexpwm = &IMXRT_FLEXPWM4;
106 }
107 if(flexpwm != nullptr){
108#ifdef SIMPLEFOC_TEENSY_DEBUG
109 char s[60];
110 sprintf (s, "TEENSY-DRV: Pin: %d on Flextimer %d.", pin, ((info->module >> 4) & 3) + 1);
112#endif
113 return flexpwm;
114 }
115 return nullptr;
116}
117
118
119// function which finds the timer submodule for a pin
120// if it does not belong to the submodule it returns a -1
121int get_submodule(uint8_t pin){
122
123 const struct pwm_pin_info_struct *info;
124 if (pin >= CORE_NUM_DIGITAL){
125#ifdef SIMPLEFOC_TEENSY_DEBUG
126 char s[60];
127 sprintf (s, "TEENSY-DRV: ERR: Pin: %d not Flextimer pin!", pin);
129#endif
130 return -1;
131 }
132
133 info = pwm_pin_info + pin;
134 int sm1 = info->module&0x3;
135
136 if (sm1 >= 0 && sm1 < 4) {
137#ifdef SIMPLEFOC_TEENSY_DEBUG
138 char s[60];
139 sprintf (s, "TEENSY-DRV: Pin %d on submodule %d.", pin, sm1);
141#endif
142 return sm1;
143 } else {
144#ifdef SIMPLEFOC_TEENSY_DEBUG
145 char s[50];
146 sprintf (s, "TEENSY-DRV: ERR: Pin: %d not in submodule!", pin);
148#endif
149 return -1;
150 }
151}
152
153// function which finds the flexpwm instance for a pair of pins
154// if they do not belong to the same timer it returns a nullpointer
155IMXRT_FLEXPWM_t* get_flexpwm(uint8_t pin, uint8_t pin1){
156
157 const struct pwm_pin_info_struct *info;
158 if (pin >= CORE_NUM_DIGITAL || pin1 >= CORE_NUM_DIGITAL) {
159#ifdef SIMPLEFOC_TEENSY_DEBUG
160 char s[60];
161 sprintf (s, "TEENSY-DRV: ERR: Pins: %d, %d not Flextimer pins!", pin, pin1);
163#endif
164 return nullptr;
165 }
166 info = pwm_pin_info + pin;
167 // FlexPWM pin
168 IMXRT_FLEXPWM_t *flexpwm1,*flexpwm2;
169 switch ((info->module >> 4) & 3) {
170 case 0: flexpwm1 = &IMXRT_FLEXPWM1; break;
171 case 1: flexpwm1 = &IMXRT_FLEXPWM2; break;
172 case 2: flexpwm1 = &IMXRT_FLEXPWM3; break;
173 default: flexpwm1 = &IMXRT_FLEXPWM4;
174 }
175
176 info = pwm_pin_info + pin1;
177 switch ((info->module >> 4) & 3) {
178 case 0: flexpwm2 = &IMXRT_FLEXPWM1; break;
179 case 1: flexpwm2 = &IMXRT_FLEXPWM2; break;
180 case 2: flexpwm2 = &IMXRT_FLEXPWM3; break;
181 default: flexpwm2 = &IMXRT_FLEXPWM4;
182 }
183 if(flexpwm1 == flexpwm2){
184 char s[60];
185 sprintf (s, "TEENSY-DRV: Pins: %d, %d on Flextimer %d.", pin, pin1, ((info->module >> 4) & 3) + 1);
187 return flexpwm1;
188 } else {
189#ifdef SIMPLEFOC_TEENSY_DEBUG
190 char s[60];
191 sprintf (s, "TEENSY-DRV: ERR: Pins: %d, %d not in same Flextimer!", pin, pin1);
193#endif
194 return nullptr;
195 }
196}
197
198
199// function which finds the timer submodule for a pair of pins
200// if they do not belong to the same submodule it returns a -1
201int get_submodule(uint8_t pin, uint8_t pin1){
202
203 const struct pwm_pin_info_struct *info;
204 if (pin >= CORE_NUM_DIGITAL || pin1 >= CORE_NUM_DIGITAL){
205#ifdef SIMPLEFOC_TEENSY_DEBUG
206 char s[60];
207 sprintf (s, "TEENSY-DRV: ERR: Pins: %d, %d not Flextimer pins!", pin, pin1);
209#endif
210 return -1;
211 }
212
213 info = pwm_pin_info + pin;
214 int sm1 = info->module&0x3;
215 info = pwm_pin_info + pin1;
216 int sm2 = info->module&0x3;
217
218 if (sm1 == sm2) {
219 char s[60];
220 sprintf (s, "TEENSY-DRV: Pins: %d, %d on submodule %d.", pin, pin1, sm1);
222 return sm1;
223 } else {
224#ifdef SIMPLEFOC_TEENSY_DEBUG
225 char s[50];
226 sprintf (s, "TEENSY-DRV: ERR: Pins: %d, %d not in same submodule!", pin, pin1);
228#endif
229 return -1;
230 }
231}
232
233
234// function which finds the channel for flexpwm timer pin
235// 0 - X
236// 1 - A
237// 2 - B
238int get_channel(uint8_t pin){
239 const struct pwm_pin_info_struct *info;
240 info = pwm_pin_info + pin;
241 if (pin >= CORE_NUM_DIGITAL || info->type == 2){
242#ifdef SIMPLEFOC_TEENSY_DEBUG
243 char s[90];
244 sprintf (s, "TEENSY-DRV: ERR: Pin: %d not Flextimer pin!", pin);
246#endif
247 return -1;
248 }
249#ifdef SIMPLEFOC_TEENSY_DEBUG
250 char s[60];
251 sprintf (s, "TEENSY-DRV: Pin: %d on channel %s.", pin, info->channel==0 ? "X" : info->channel==1 ? "A" : "B");
253#endif
254 return info->channel;
255}
256
257// function which finds the timer submodule for a pair of pins
258// if they do not belong to the same submodule it returns a -1
259int get_inverted_channel(uint8_t pin, uint8_t pin1){
260
261 if (pin >= CORE_NUM_DIGITAL || pin1 >= CORE_NUM_DIGITAL){
262#ifdef SIMPLEFOC_TEENSY_DEBUG
263 char s[60];
264 sprintf (s, "TEENSY-DRV: ERR: Pins: %d, %d not Flextimer pins!", pin, pin1);
266#endif
267 return -1;
268 }
269
270 int ch1 = get_channel(pin);
271 int ch2 = get_channel(pin1);
272
273 if (ch1 != 1) {
274#ifdef SIMPLEFOC_TEENSY_DEBUG
275 char s[60];
276 sprintf (s, "TEENSY-DRV: ERR: Pin: %d on channel %s - only A supported", pin1, ch1==2 ? "B" : "X");
278#endif
279 return -1;
280 } else if (ch2 != 2) {
281#ifdef SIMPLEFOC_TEENSY_DEBUG
282 char s[60];
283 sprintf (s, "TEENSY-DRV: ERR: Inverted pin: %d on channel %s - only B supported", pin1, ch2==1 ? "A" : "X");
285#endif
286 return -1;
287 } else {
288#ifdef SIMPLEFOC_TEENSY_DEBUG
289 char s[60];
290 sprintf (s, "TEENSY-DRV: Pin: %d on channel B inverted.", pin1);
292#endif
293return ch2;
294 }
295}
296
297// Helper to set up A/B pair on a FlexPWM submodule.
298// can configure sync, prescale and B inversion.
299// sets the desired frequency of the PWM
300// sets the center-aligned pwm
301void setup_pwm_pair (IMXRT_FLEXPWM_t * flexpwm, int submodule, bool ext_sync, const long frequency, float dead_zone )
302{
303 int submodule_mask = 1 << submodule ;
304 flexpwm->MCTRL &= ~ FLEXPWM_MCTRL_RUN (submodule_mask) ; // stop it if its already running
305 flexpwm->MCTRL |= FLEXPWM_MCTRL_CLDOK (submodule_mask) ; // clear load OK
306
307
308 // calculate the counter and prescaler for the desired pwm frequency
309 uint32_t newdiv = (uint32_t)((float)F_BUS_ACTUAL / frequency + 0.5f);
310 uint32_t prescale = 0;
311 //printf(" div=%lu\n", newdiv);
312 while (newdiv > 65535 && prescale < 7) {
313 newdiv = newdiv >> 1;
314 prescale = prescale + 1;
315 }
316 if (newdiv > 65535) {
317 newdiv = 65535;
318 } else if (newdiv < 2) {
319 newdiv = 2;
320 }
321
322 // the halfcycle of the PWM
323 int half_cycle = int(newdiv/2.0f);
324 int dead_time = int(dead_zone*half_cycle); //default dead-time - 2%
325 int mid_pwm = int((half_cycle)/2.0f);
326
327 // if the timer should be externally synced with the master timer
328 int sel = ext_sync ? 3 : 0;
329
330 // setup the timer
331 // https://github.com/PaulStoffregen/cores/blob/master/teensy4/imxrt.h
332 flexpwm->SM[submodule].CTRL2 = FLEXPWM_SMCTRL2_WAITEN | FLEXPWM_SMCTRL2_DBGEN |
333 FLEXPWM_SMCTRL2_FRCEN | FLEXPWM_SMCTRL2_INIT_SEL(sel) | FLEXPWM_SMCTRL2_FORCE_SEL(6);
334 flexpwm->SM[submodule].CTRL = FLEXPWM_SMCTRL_FULL | FLEXPWM_SMCTRL_HALF | FLEXPWM_SMCTRL_PRSC(prescale) ;
335 // https://github.com/PaulStoffregen/cores/blob/70ba01accd728abe75ebfc8dcd8b3d3a8f3e3f25/teensy4/imxrt.h#L4948
336 flexpwm->SM[submodule].OCTRL = 0; //FLEXPWM_SMOCTRL_POLA | FLEXPWM_SMOCTRL_POLB;//channel_to_invert==2 ? 0 : FLEXPWM_SMOCTRL_POLA | FLEXPWM_SMOCTRL_POLB ;
337 if (!ext_sync) flexpwm->SM[submodule].TCTRL = FLEXPWM_SMTCTRL_OUT_TRIG_EN (0b000010) ; // sync trig out on VAL1 match if master timer
338 flexpwm->SM[submodule].DTCNT0 = dead_time ; // should try this out (deadtime control)
339 flexpwm->SM[submodule].DTCNT1 = dead_time ; // should try this out (deadtime control)
340 flexpwm->SM[submodule].INIT = -half_cycle; // count from -HALFCYCLE to +HALFCYCLE
341 flexpwm->SM[submodule].VAL0 = 0;
342 flexpwm->SM[submodule].VAL1 = half_cycle ;
343 flexpwm->SM[submodule].VAL2 = -mid_pwm ;
344 flexpwm->SM[submodule].VAL3 = +mid_pwm ;
345
346 flexpwm->MCTRL |= FLEXPWM_MCTRL_LDOK (submodule_mask) ; // loading reenabled
347 flexpwm->MCTRL |= FLEXPWM_MCTRL_RUN (submodule_mask) ; // start it running
348}
349
350
351// Helper to set up a FlexPWM submodule.
352// can configure sync, prescale
353// sets the desired frequency of the PWM
354// sets the center-aligned pwm
355void setup_pwm_timer_submodule (IMXRT_FLEXPWM_t * flexpwm, int submodule, bool ext_sync, const long frequency)
356{
357 int submodule_mask = 1 << submodule ;
358 flexpwm->MCTRL &= ~ FLEXPWM_MCTRL_RUN (submodule_mask) ; // stop it if its already running
359 flexpwm->MCTRL |= FLEXPWM_MCTRL_CLDOK (submodule_mask) ; // clear load OK
360
361 // calculate the counter and prescaler for the desired pwm frequency
362 uint32_t newdiv = (uint32_t)((float)F_BUS_ACTUAL / frequency + 0.5f);
363 uint32_t prescale = 0;
364 //printf(" div=%lu\n", newdiv);
365 while (newdiv > 65535 && prescale < 7) {
366 newdiv = newdiv >> 1;
367 prescale = prescale + 1;
368 }
369 if (newdiv > 65535) {
370 newdiv = 65535;
371 } else if (newdiv < 2) {
372 newdiv = 2;
373 }
374
375 // the halfcycle of the PWM
376 int half_cycle = int(newdiv/2.0f);
377
378 // if the timer should be externally synced with the master timer
379 int sel = ext_sync ? 3 : 0;
380
381 // setup the timer
382 // https://github.com/PaulStoffregen/cores/blob/master/teensy4/imxrt.h
383 flexpwm->SM[submodule].CTRL2 = FLEXPWM_SMCTRL2_INDEP | FLEXPWM_SMCTRL2_WAITEN | FLEXPWM_SMCTRL2_DBGEN |
384 FLEXPWM_SMCTRL2_FRCEN | FLEXPWM_SMCTRL2_INIT_SEL(sel) | FLEXPWM_SMCTRL2_FORCE_SEL(6);
385 flexpwm->SM[submodule].CTRL = FLEXPWM_SMCTRL_FULL | FLEXPWM_SMCTRL_HALF | FLEXPWM_SMCTRL_PRSC(prescale) ;
386 // https://github.com/PaulStoffregen/cores/blob/70ba01accd728abe75ebfc8dcd8b3d3a8f3e3f25/teensy4/imxrt.h#L4948
387 flexpwm->SM[submodule].OCTRL = 0; //FLEXPWM_SMOCTRL_POLA | FLEXPWM_SMOCTRL_POLB;//channel_to_invert==2 ? 0 : FLEXPWM_SMOCTRL_POLA | FLEXPWM_SMOCTRL_POLB ;
388 if (!ext_sync) flexpwm->SM[submodule].TCTRL = FLEXPWM_SMTCTRL_OUT_TRIG_EN (0b000010) ; // sync trig out on VAL1 match if master timer
389 flexpwm->SM[submodule].DTCNT0 = 0 ;
390 flexpwm->SM[submodule].DTCNT1 = 0 ;
391 flexpwm->SM[submodule].INIT = -half_cycle; // count from -HALFCYCLE to +HALFCYCLE
392 flexpwm->SM[submodule].VAL0 = 0;
393 flexpwm->SM[submodule].VAL1 = half_cycle;
394 flexpwm->SM[submodule].VAL2 = 0 ;
395 flexpwm->SM[submodule].VAL3 = 0 ;
396 flexpwm->SM[submodule].VAL2 = 0 ;
397 flexpwm->SM[submodule].VAL3 = 0 ;
398
399 flexpwm->MCTRL |= FLEXPWM_MCTRL_LDOK (submodule_mask) ; // loading reenabled
400 flexpwm->MCTRL |= FLEXPWM_MCTRL_RUN (submodule_mask) ; // start it running
401}
402
403
404// staring the PWM on A and B channels of the submodule
405void startup_pwm_pair (IMXRT_FLEXPWM_t * flexpwm, int submodule, int channel)
406{
407 int submodule_mask = 1 << submodule ;
408
409 if(channel==1) flexpwm->OUTEN |= FLEXPWM_OUTEN_PWMA_EN (submodule_mask); // enable A output
410 else if(channel==2) flexpwm->OUTEN |= FLEXPWM_OUTEN_PWMB_EN (submodule_mask); // enable B output
411}
412
413
414
415// staring the PWM on A and B channels of the submodule
416void startup_pwm_pair (IMXRT_FLEXPWM_t * flexpwm, int submodule)
417{
418 int submodule_mask = 1 << submodule ;
419
420 flexpwm->OUTEN |= FLEXPWM_OUTEN_PWMA_EN (submodule_mask); // enable A output
421 flexpwm->OUTEN |= FLEXPWM_OUTEN_PWMB_EN (submodule_mask); // enable B output
422}
423
424
425
426// PWM setting on the high and low pair of the PWM channels
427void write_pwm_pair(IMXRT_FLEXPWM_t * flexpwm, int submodule, float duty){
428 int half_cycle = int(flexpwm->SM[submodule].VAL1);
429 int mid_pwm = int((half_cycle)/2.0f);
430 int count_pwm = int(mid_pwm*(duty*2-1)) + mid_pwm;
431
432 flexpwm->SM[submodule].VAL2 = -count_pwm; // A on
433 flexpwm->SM[submodule].VAL3 = count_pwm ; // A off
434 flexpwm->MCTRL |= FLEXPWM_MCTRL_LDOK (1<<submodule) ; // signal new values
435}
436
437// function setting the high pwm frequency to the supplied pins
438// - Stepper motor - 6PWM setting
439// - hardware specific
440void* _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) {
441 if(!pwm_frequency || !_isset(pwm_frequency) ) pwm_frequency = _PWM_FREQUENCY; // default frequency 25khz
442 else pwm_frequency = _constrain(pwm_frequency, 0, _PWM_FREQUENCY_MAX); // constrain to 50kHz max
443
444 IMXRT_FLEXPWM_t *flexpwmA,*flexpwmB,*flexpwmC;
445 int submoduleA,submoduleB,submoduleC;
446 int inverted_channelA,inverted_channelB,inverted_channelC;
447 int channelA,channelB,channelC;
448 flexpwmA = get_flexpwm(pinA_h,pinA_l);
449 submoduleA = get_submodule(pinA_h,pinA_l);
450 inverted_channelA = get_inverted_channel(pinA_h,pinA_l);
451 flexpwmB = get_flexpwm(pinB_h,pinB_l);
452 submoduleB = get_submodule(pinB_h,pinB_l);
453 inverted_channelB = get_inverted_channel(pinB_h,pinB_l);
454 flexpwmC = get_flexpwm(pinC_h,pinC_l);
455 submoduleC = get_submodule(pinC_h,pinC_l);
456 inverted_channelC = get_inverted_channel(pinC_h,pinC_l);
457 channelA = get_channel(pinA_h);
458 channelB = get_channel(pinB_h);
459 channelC = get_channel(pinC_h);
460
461 if((flexpwmA == nullptr) || (flexpwmB == nullptr) || (flexpwmC == nullptr) ){
462#ifdef SIMPLEFOC_TEENSY_DEBUG
463 SIMPLEFOC_DEBUG("TEENSY-DRV: ERR: Flextimer problem - failed driver config!");
464#endif
466 }
467 if((submoduleA < 0) || (submoduleB < 0) || (submoduleC < 0) ){
468#ifdef SIMPLEFOC_TEENSY_DEBUG
469 SIMPLEFOC_DEBUG("TEENSY-DRV: ERR: Flextimer submodule problem - failed driver config!");
470#endif
472 }
473 if((inverted_channelA < 0) || (inverted_channelB < 0) || (inverted_channelC < 0) ){
474#ifdef SIMPLEFOC_TEENSY_DEBUG
475 SIMPLEFOC_DEBUG("TEENSY-DRV: ERR: Flextimer channel problem - failed driver config!");
476#endif
478 }
479
480 #ifdef SIMPLEFOC_TEENSY_DEBUG
481 char buff[100];
482 sprintf(buff, "TEENSY-DRV: Syncing to Master FlexPWM: %d, Submodule: %d", flexpwm_to_index(flexpwmC), submoduleC);
483 SIMPLEFOC_DEBUG(buff);
484 sprintf(buff, "TEENSY-DRV: Slave timers FlexPWM: %d, Submodule: %d and FlexPWM: %d, Submodule: %d", flexpwm_to_index(flexpwmA), submoduleA, flexpwm_to_index(flexpwmB), submoduleB);
485 SIMPLEFOC_DEBUG(buff);
486 #endif
487
488 // Configure FlexPWM units, each driving A/B pair, B inverted.
489 setup_pwm_pair (flexpwmA, submoduleA, true, pwm_frequency, dead_zone) ; // others externally synced
490 setup_pwm_pair (flexpwmB, submoduleB, true, pwm_frequency, dead_zone) ; // others externally synced
491 setup_pwm_pair (flexpwmC, submoduleC, false, pwm_frequency, dead_zone) ; // this is the master, internally synced
492 delayMicroseconds (100) ;
493
494 // turn on XBAR1 clock for all but stop mode
495 xbar_init() ;
496
497 // // Connect trigger to synchronize all timers
498 xbar_connect (flexpwm_submodule_to_trig(flexpwmC, submoduleC), flexpwm_submodule_to_ext_sync(flexpwmA, submoduleA)) ;
499 xbar_connect (flexpwm_submodule_to_trig(flexpwmC, submoduleC), flexpwm_submodule_to_ext_sync(flexpwmB, submoduleB)) ;
500
501 startup_pwm_pair (flexpwmA, submoduleA) ;
502 startup_pwm_pair (flexpwmB, submoduleB) ;
503 startup_pwm_pair (flexpwmC, submoduleC) ;
504
505 delayMicroseconds(50) ;
506 // config the pins 2/3/6/9/8/7 as their FLEXPWM alternates.
507 *portConfigRegister(pinA_h) = pwm_pin_info[pinA_h].muxval ;
508 *portConfigRegister(pinA_l) = pwm_pin_info[pinA_l].muxval ;
509 *portConfigRegister(pinB_h) = pwm_pin_info[pinB_h].muxval ;
510 *portConfigRegister(pinB_l) = pwm_pin_info[pinB_l].muxval ;
511 *portConfigRegister(pinC_h) = pwm_pin_info[pinC_h].muxval ;
512 *portConfigRegister(pinC_l) = pwm_pin_info[pinC_l].muxval ;
513
514
515 TeensyDriverParams* params = new TeensyDriverParams {
517 .pwm_frequency = pwm_frequency,
518 .additional_params = new Teensy4DriverParams {
519 .flextimers = { flexpwmA, flexpwmB, flexpwmC},
520 .submodules = { submoduleA, submoduleB, submoduleC},
521 .channels = {1,2, 1, 2, 1, 2},
522 .dead_zone = dead_zone
523 }
524 };
525 return params;
526}
527
528
529// Helper function to enable or disable pwm pins based on phase state (allows for disabling the motor)
530static inline void _teensy4_apply_phase_state(
531 IMXRT_FLEXPWM_t *flexpwm, int submodule, PhaseState state
532)
533{
534 uint16_t submodule_mask = 1u << submodule;
535 uint16_t enable_a = FLEXPWM_OUTEN_PWMA_EN( submodule_mask );
536 uint16_t enable_b = FLEXPWM_OUTEN_PWMB_EN( submodule_mask );
537
538 switch ( state )
539 {
541 flexpwm->OUTEN &= ~( enable_a | enable_b );
542 break;
544 flexpwm->OUTEN |= enable_a;
545 flexpwm->OUTEN &= ~enable_b;
546 break;
548 flexpwm->OUTEN &= ~enable_a;
549 flexpwm->OUTEN |= enable_b;
550 break;
552 default:
553 flexpwm->OUTEN |= ( enable_a | enable_b );
554 break;
555 }
556}
557
558// function setting the pwm duty cycle to the hardware
559// - Stepper motor - 6PWM setting
560// - hardware specific
561void _writeDutyCycle6PWM(float dc_a, float dc_b, float dc_c, PhaseState *phase_state, void* params){
562 Teensy4DriverParams *p = (Teensy4DriverParams *)( (TeensyDriverParams *)params )->additional_params;
563
567
568 if ( PhaseState::PHASE_OFF == phase_a )
569 dc_a = 0.0f;
570 if ( PhaseState::PHASE_OFF == phase_b )
571 dc_b = 0.0f;
572 if ( PhaseState::PHASE_OFF == phase_c )
573 dc_c = 0.0f;
574
575 _teensy4_apply_phase_state( p->flextimers[ 0 ], p->submodules[ 0 ], phase_a );
576 _teensy4_apply_phase_state( p->flextimers[ 1 ], p->submodules[ 1 ], phase_b );
577 _teensy4_apply_phase_state( p->flextimers[ 2 ], p->submodules[ 2 ], phase_c );
578
579 write_pwm_pair( p->flextimers[ 0 ], p->submodules[ 0 ], dc_a );
580 write_pwm_pair( p->flextimers[ 1 ], p->submodules[ 1 ], dc_b );
581 write_pwm_pair( p->flextimers[ 2 ], p->submodules[ 2 ], dc_c );
582}
583
584void write_pwm_on_pin(IMXRT_FLEXPWM_t *p, unsigned int submodule, uint8_t channel, float duty)
585{
586 uint16_t mask = 1 << submodule;
587 uint32_t half_cycle = p->SM[submodule].VAL1;
588 int mid_pwm = int((half_cycle)/2.0f);
589 int cval = int(mid_pwm*(duty*2-1)) + mid_pwm;
590
591 //printf("flexpwmWrite, p=%08lX, sm=%d, ch=%c, cval=%ld\n",
592 //(uint32_t)p, submodule, channel == 0 ? 'X' : (channel == 1 ? 'A' : 'B'), cval);
593 p->MCTRL |= FLEXPWM_MCTRL_CLDOK(mask);
594 switch (channel) {
595 case 0: // X
596 p->SM[submodule].VAL0 = half_cycle - cval;
597 p->OUTEN |= FLEXPWM_OUTEN_PWMX_EN(mask);
598 //printf(" write channel X\n");
599 break;
600 case 1: // A
601 p->SM[submodule].VAL2 = -cval;
602 p->SM[submodule].VAL3 = cval;
603 p->OUTEN |= FLEXPWM_OUTEN_PWMA_EN(mask);
604 //printf(" write channel A\n");
605 break;
606 case 2: // B
607 p->SM[submodule].VAL4 = -cval;
608 p->SM[submodule].VAL5 = cval;
609 p->OUTEN |= FLEXPWM_OUTEN_PWMB_EN(mask);
610 //printf(" write channel B\n");
611 }
612 p->MCTRL |= FLEXPWM_MCTRL_LDOK(mask);
613}
614
615#ifdef SIMPLEFOC_TEENSY4_FORCE_CENTER_ALIGNED_3PWM
616
617// function setting the high pwm frequency to the supplied pins
618// - BLDC motor - 3PWM setting
619// - hardware speciffic
620// in generic case dont do anything
621 void* _configureCenterAligned3PMW(long pwm_frequency,const int pinA, const int pinB, const int pinC) {
622
623 if(!pwm_frequency || !_isset(pwm_frequency) ) pwm_frequency = _PWM_FREQUENCY; // default frequency 25khz
624 else pwm_frequency = _constrain(pwm_frequency, 0, _PWM_FREQUENCY_MAX); // constrain to 50kHz max
625
626 IMXRT_FLEXPWM_t *flexpwmA,*flexpwmB,*flexpwmC;
627 int submoduleA,submoduleB,submoduleC;
628 flexpwmA = get_flexpwm(pinA);
629 submoduleA = get_submodule(pinA);
630 flexpwmB = get_flexpwm(pinB);
631 submoduleB = get_submodule(pinB);
632 flexpwmC = get_flexpwm(pinC);
633 submoduleC = get_submodule(pinC);
634 int channelA = get_channel(pinA);
635 int channelB = get_channel(pinB);
636 int channelC = get_channel(pinC);
637
638
639 // if pins belong to the flextimers and they only use submodules A and B
640 // we can configure the center-aligned pwm
641 if((flexpwmA != nullptr) && (flexpwmB != nullptr) && (flexpwmC != nullptr) && (channelA > 0) && (channelB > 0) && (channelC > 0) ){
642 #ifdef SIMPLEFOC_TEENSY_DEBUG
643 SIMPLEFOC_DEBUG("TEENSY-DRV: All pins on Flexpwm A or B channels - Configuring center-aligned pwm!");
644 #endif
645
646 // Configure FlexPWM units
647 setup_pwm_timer_submodule (flexpwmA, submoduleA, true, pwm_frequency) ; // others externally synced
648 setup_pwm_timer_submodule (flexpwmB, submoduleB, true, pwm_frequency) ; // others externally synced
649 setup_pwm_timer_submodule (flexpwmC, submoduleC, false, pwm_frequency) ; // this is the master, internally synced
650 delayMicroseconds (100) ;
651
652
653 #ifdef SIMPLEFOC_TEENSY_DEBUG
654 char buff[100];
655 sprintf(buff, "TEENSY-CS: Syncing to Master FlexPWM: %d, Submodule: %d", flexpwm_to_index(flexpwmC), submoduleC);
656 SIMPLEFOC_DEBUG(buff);
657 sprintf(buff, "TEENSY-CS: Slave timers FlexPWM: %d, Submodule: %d and FlexPWM: %d, Submodule: %d", flexpwm_to_index(flexpwmA), submoduleA, flexpwm_to_index(flexpwmB), submoduleB);
658 SIMPLEFOC_DEBUG(buff);
659 #endif
660
661 // // turn on XBAR1 clock for all but stop mode
662 xbar_init() ;
663
664 // // Connect trigger to synchronize all timers
665 xbar_connect (flexpwm_submodule_to_trig(flexpwmC, submoduleC), flexpwm_submodule_to_ext_sync(flexpwmA, submoduleA)) ;
666 xbar_connect (flexpwm_submodule_to_trig(flexpwmC, submoduleC), flexpwm_submodule_to_ext_sync(flexpwmB, submoduleB)) ;
667
668 TeensyDriverParams* params = new TeensyDriverParams {
669 .pins = { pinA, pinB, pinC },
670 .pwm_frequency = pwm_frequency,
671 .additional_params = new Teensy4DriverParams {
672 .flextimers = { flexpwmA, flexpwmB, flexpwmC},
673 .submodules = { submoduleA, submoduleB, submoduleC},
674 .channels = {channelA, channelB, channelC},
675 }
676 };
677
678 startup_pwm_pair (flexpwmA, submoduleA, channelA) ;
679 startup_pwm_pair (flexpwmB, submoduleB, channelB) ;
680 startup_pwm_pair (flexpwmC, submoduleC, channelC) ;
681
682 // // config the pins 2/3/6/9/8/7 as their FLEXPWM alternates.
683 *portConfigRegister(pinA) = pwm_pin_info[pinA].muxval ;
684 *portConfigRegister(pinB) = pwm_pin_info[pinB].muxval ;
685 *portConfigRegister(pinC) = pwm_pin_info[pinC].muxval ;
686
687 return params;
688 }else{
689 #ifdef SIMPLEFOC_TEENSY_DEBUG
690 SIMPLEFOC_DEBUG("TEENSY-DRV: Not all pins on Flexpwm A and B channels - cannot configure center-aligned pwm!");
691 #endif
693 }
694
695}
696
697// function setting the pwm duty cycle to the hardware
698// - Stepper motor - 6PWM setting
699// - hardware specific
700void _writeCenterAligned3PMW(float dc_a, float dc_b, float dc_c, void* params){
701 Teensy4DriverParams* p = (Teensy4DriverParams*)((TeensyDriverParams*)params)->additional_params;
702 write_pwm_on_pin (p->flextimers[0], p->submodules[0], p->channels[0], dc_a);
703 write_pwm_on_pin (p->flextimers[1], p->submodules[1], p->channels[1], dc_b);
704 write_pwm_on_pin (p->flextimers[2], p->submodules[2], p->channels[2], dc_c);
705}
706
707#endif
708
709#endif
PhaseState
Definition FOCDriver.h:7
@ PHASE_HI
Definition FOCDriver.h:10
@ PHASE_ON
Definition FOCDriver.h:9
@ PHASE_LO
Definition FOCDriver.h:11
@ PHASE_OFF
Definition FOCDriver.h:8
#define SIMPLEFOC_DEBUG(msg,...)
const int const int const int pinC
GenericCurrentSenseParams * params
void * _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)
#define SIMPLEFOC_DRIVER_INIT_FAILED
void _writeDutyCycle6PWM(float dc_a, float dc_b, float dc_c, PhaseState *phase_state, void *params)
float const int const int const int pinB_h
float const int const int const int const int pinB_l
float const int const int const int const int const int pinC_h
float float PhaseState * phase_state
float const int const int const int const int const int const int pinC_l
float const int const int pinA_l
float * s
Definition foc_utils.cpp:43
#define _isset(a)
Definition foc_utils.h:13
#define _constrain(amt, low, high)
Definition foc_utils.h:11