2#include "../../../communication/SimpleFOCDebug.h"
7#if defined(__arm__) && defined(CORE_TEENSY) && ( defined(__IMXRT1062__) || defined(ARDUINO_TEENSY40) || defined(ARDUINO_TEENSY41) || defined(ARDUINO_TEENSY_MICROMOD) )
10#pragma message("SimpleFOC: compiling for Teensy 4.x")
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;
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;
50 }
else if(flexpwm == &IMXRT_FLEXPWM4){
51 return XBARA1_OUT_FLEXPWM4_EXT_SYNC0 + 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;
67void xbar_connect(
unsigned int input,
unsigned int output)
69 if (input >= 88)
return;
70 if (output >= 132)
return;
71 volatile uint16_t *xbar = &XBARA1_SEL0 + (output / 2);
74 val = (val & 0xFF00) | input;
76 val = (val & 0x00FF) | (input << 8);
82 CCM_CCGR2 |= CCM_CCGR2_XBAR1(CCM_CCGR_ON);
87IMXRT_FLEXPWM_t* get_flexpwm(uint8_t pin){
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
94 sprintf (
s,
"TEENSY-DRV: ERR: Pin: %d not Flextimer pin!", 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;
107 if(flexpwm !=
nullptr){
108#ifdef SIMPLEFOC_TEENSY_DEBUG
110 sprintf (
s,
"TEENSY-DRV: Pin: %d on Flextimer %d.", pin, ((info->module >> 4) & 3) + 1);
121int get_submodule(uint8_t pin){
123 const struct pwm_pin_info_struct *info;
124 if (pin >= CORE_NUM_DIGITAL){
125#ifdef SIMPLEFOC_TEENSY_DEBUG
127 sprintf (
s,
"TEENSY-DRV: ERR: Pin: %d not Flextimer pin!", pin);
133 info = pwm_pin_info + pin;
134 int sm1 = info->module&0x3;
136 if (sm1 >= 0 && sm1 < 4) {
137#ifdef SIMPLEFOC_TEENSY_DEBUG
139 sprintf (
s,
"TEENSY-DRV: Pin %d on submodule %d.", pin, sm1);
144#ifdef SIMPLEFOC_TEENSY_DEBUG
146 sprintf (
s,
"TEENSY-DRV: ERR: Pin: %d not in submodule!", pin);
155IMXRT_FLEXPWM_t* get_flexpwm(uint8_t pin, uint8_t pin1){
157 const struct pwm_pin_info_struct *info;
158 if (pin >= CORE_NUM_DIGITAL || pin1 >= CORE_NUM_DIGITAL) {
159#ifdef SIMPLEFOC_TEENSY_DEBUG
161 sprintf (
s,
"TEENSY-DRV: ERR: Pins: %d, %d not Flextimer pins!", pin, pin1);
166 info = pwm_pin_info + 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;
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;
183 if(flexpwm1 == flexpwm2){
185 sprintf (
s,
"TEENSY-DRV: Pins: %d, %d on Flextimer %d.", pin, pin1, ((info->module >> 4) & 3) + 1);
189#ifdef SIMPLEFOC_TEENSY_DEBUG
191 sprintf (
s,
"TEENSY-DRV: ERR: Pins: %d, %d not in same Flextimer!", pin, pin1);
201int get_submodule(uint8_t pin, uint8_t pin1){
203 const struct pwm_pin_info_struct *info;
204 if (pin >= CORE_NUM_DIGITAL || pin1 >= CORE_NUM_DIGITAL){
205#ifdef SIMPLEFOC_TEENSY_DEBUG
207 sprintf (
s,
"TEENSY-DRV: ERR: Pins: %d, %d not Flextimer pins!", pin, pin1);
213 info = pwm_pin_info + pin;
214 int sm1 = info->module&0x3;
215 info = pwm_pin_info + pin1;
216 int sm2 = info->module&0x3;
220 sprintf (
s,
"TEENSY-DRV: Pins: %d, %d on submodule %d.", pin, pin1, sm1);
224#ifdef SIMPLEFOC_TEENSY_DEBUG
226 sprintf (
s,
"TEENSY-DRV: ERR: Pins: %d, %d not in same submodule!", pin, pin1);
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
244 sprintf (
s,
"TEENSY-DRV: ERR: Pin: %d not Flextimer pin!", pin);
249#ifdef SIMPLEFOC_TEENSY_DEBUG
251 sprintf (
s,
"TEENSY-DRV: Pin: %d on channel %s.", pin, info->channel==0 ?
"X" : info->channel==1 ?
"A" :
"B");
254 return info->channel;
259int get_inverted_channel(uint8_t pin, uint8_t pin1){
261 if (pin >= CORE_NUM_DIGITAL || pin1 >= CORE_NUM_DIGITAL){
262#ifdef SIMPLEFOC_TEENSY_DEBUG
264 sprintf (
s,
"TEENSY-DRV: ERR: Pins: %d, %d not Flextimer pins!", pin, pin1);
270 int ch1 = get_channel(pin);
271 int ch2 = get_channel(pin1);
274#ifdef SIMPLEFOC_TEENSY_DEBUG
276 sprintf (
s,
"TEENSY-DRV: ERR: Pin: %d on channel %s - only A supported", pin1, ch1==2 ?
"B" :
"X");
280 }
else if (ch2 != 2) {
281#ifdef SIMPLEFOC_TEENSY_DEBUG
283 sprintf (
s,
"TEENSY-DRV: ERR: Inverted pin: %d on channel %s - only B supported", pin1, ch2==1 ?
"A" :
"X");
288#ifdef SIMPLEFOC_TEENSY_DEBUG
290 sprintf (
s,
"TEENSY-DRV: Pin: %d on channel B inverted.", pin1);
301void setup_pwm_pair (IMXRT_FLEXPWM_t * flexpwm,
int submodule,
bool ext_sync,
const long frequency,
float dead_zone )
303 int submodule_mask = 1 << submodule ;
304 flexpwm->MCTRL &= ~ FLEXPWM_MCTRL_RUN (submodule_mask) ;
305 flexpwm->MCTRL |= FLEXPWM_MCTRL_CLDOK (submodule_mask) ;
309 uint32_t newdiv = (uint32_t)((
float)F_BUS_ACTUAL / frequency + 0.5f);
310 uint32_t prescale = 0;
312 while (newdiv > 65535 && prescale < 7) {
313 newdiv = newdiv >> 1;
314 prescale = prescale + 1;
316 if (newdiv > 65535) {
318 }
else if (newdiv < 2) {
323 int half_cycle = int(newdiv/2.0f);
324 int dead_time = int(
dead_zone*half_cycle);
325 int mid_pwm = int((half_cycle)/2.0f);
328 int sel = ext_sync ? 3 : 0;
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) ;
336 flexpwm->SM[submodule].OCTRL = 0;
337 if (!ext_sync) flexpwm->SM[submodule].TCTRL = FLEXPWM_SMTCTRL_OUT_TRIG_EN (0b000010) ;
338 flexpwm->SM[submodule].DTCNT0 = dead_time ;
339 flexpwm->SM[submodule].DTCNT1 = dead_time ;
340 flexpwm->SM[submodule].INIT = -half_cycle;
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 ;
346 flexpwm->MCTRL |= FLEXPWM_MCTRL_LDOK (submodule_mask) ;
347 flexpwm->MCTRL |= FLEXPWM_MCTRL_RUN (submodule_mask) ;
355void setup_pwm_timer_submodule (IMXRT_FLEXPWM_t * flexpwm,
int submodule,
bool ext_sync,
const long frequency)
357 int submodule_mask = 1 << submodule ;
358 flexpwm->MCTRL &= ~ FLEXPWM_MCTRL_RUN (submodule_mask) ;
359 flexpwm->MCTRL |= FLEXPWM_MCTRL_CLDOK (submodule_mask) ;
362 uint32_t newdiv = (uint32_t)((
float)F_BUS_ACTUAL / frequency + 0.5f);
363 uint32_t prescale = 0;
365 while (newdiv > 65535 && prescale < 7) {
366 newdiv = newdiv >> 1;
367 prescale = prescale + 1;
369 if (newdiv > 65535) {
371 }
else if (newdiv < 2) {
376 int half_cycle = int(newdiv/2.0f);
379 int sel = ext_sync ? 3 : 0;
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) ;
387 flexpwm->SM[submodule].OCTRL = 0;
388 if (!ext_sync) flexpwm->SM[submodule].TCTRL = FLEXPWM_SMTCTRL_OUT_TRIG_EN (0b000010) ;
389 flexpwm->SM[submodule].DTCNT0 = 0 ;
390 flexpwm->SM[submodule].DTCNT1 = 0 ;
391 flexpwm->SM[submodule].INIT = -half_cycle;
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 ;
399 flexpwm->MCTRL |= FLEXPWM_MCTRL_LDOK (submodule_mask) ;
400 flexpwm->MCTRL |= FLEXPWM_MCTRL_RUN (submodule_mask) ;
405void startup_pwm_pair (IMXRT_FLEXPWM_t * flexpwm,
int submodule,
int channel)
407 int submodule_mask = 1 << submodule ;
409 if(channel==1) flexpwm->OUTEN |= FLEXPWM_OUTEN_PWMA_EN (submodule_mask);
410 else if(channel==2) flexpwm->OUTEN |= FLEXPWM_OUTEN_PWMB_EN (submodule_mask);
416void startup_pwm_pair (IMXRT_FLEXPWM_t * flexpwm,
int submodule)
418 int submodule_mask = 1 << submodule ;
420 flexpwm->OUTEN |= FLEXPWM_OUTEN_PWMA_EN (submodule_mask);
421 flexpwm->OUTEN |= FLEXPWM_OUTEN_PWMB_EN (submodule_mask);
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;
432 flexpwm->SM[submodule].VAL2 = -count_pwm;
433 flexpwm->SM[submodule].VAL3 = count_pwm ;
434 flexpwm->MCTRL |= FLEXPWM_MCTRL_LDOK (1<<submodule) ;
441 if(!pwm_frequency || !
_isset(pwm_frequency) ) pwm_frequency = _PWM_FREQUENCY;
442 else pwm_frequency =
_constrain(pwm_frequency, 0, _PWM_FREQUENCY_MAX);
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;
450 inverted_channelA = get_inverted_channel(
pinA_h,
pinA_l);
453 inverted_channelB = get_inverted_channel(
pinB_h,
pinB_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);
461 if((flexpwmA ==
nullptr) || (flexpwmB ==
nullptr) || (flexpwmC ==
nullptr) ){
462#ifdef SIMPLEFOC_TEENSY_DEBUG
463 SIMPLEFOC_DEBUG(
"TEENSY-DRV: ERR: Flextimer problem - failed driver config!");
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!");
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!");
480 #ifdef SIMPLEFOC_TEENSY_DEBUG
482 sprintf(buff,
"TEENSY-DRV: Syncing to Master FlexPWM: %d, Submodule: %d", flexpwm_to_index(flexpwmC), submoduleC);
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);
489 setup_pwm_pair (flexpwmA, submoduleA,
true, pwm_frequency,
dead_zone) ;
490 setup_pwm_pair (flexpwmB, submoduleB,
true, pwm_frequency,
dead_zone) ;
491 setup_pwm_pair (flexpwmC, submoduleC,
false, pwm_frequency,
dead_zone) ;
492 delayMicroseconds (100) ;
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)) ;
501 startup_pwm_pair (flexpwmA, submoduleA) ;
502 startup_pwm_pair (flexpwmB, submoduleB) ;
503 startup_pwm_pair (flexpwmC, submoduleC) ;
505 delayMicroseconds(50) ;
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 ;
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},
530static inline void _teensy4_apply_phase_state(
531 IMXRT_FLEXPWM_t *flexpwm,
int submodule,
PhaseState state
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 );
541 flexpwm->OUTEN &= ~( enable_a | enable_b );
544 flexpwm->OUTEN |= enable_a;
545 flexpwm->OUTEN &= ~enable_b;
548 flexpwm->OUTEN &= ~enable_a;
549 flexpwm->OUTEN |= enable_b;
553 flexpwm->OUTEN |= ( enable_a | enable_b );
562 Teensy4DriverParams *p = (Teensy4DriverParams *)( (TeensyDriverParams *)
params )->additional_params;
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 );
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 );
584void write_pwm_on_pin(IMXRT_FLEXPWM_t *p,
unsigned int submodule, uint8_t channel,
float duty)
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;
593 p->MCTRL |= FLEXPWM_MCTRL_CLDOK(mask);
596 p->SM[submodule].VAL0 = half_cycle - cval;
597 p->OUTEN |= FLEXPWM_OUTEN_PWMX_EN(mask);
601 p->SM[submodule].VAL2 = -cval;
602 p->SM[submodule].VAL3 = cval;
603 p->OUTEN |= FLEXPWM_OUTEN_PWMA_EN(mask);
607 p->SM[submodule].VAL4 = -cval;
608 p->SM[submodule].VAL5 = cval;
609 p->OUTEN |= FLEXPWM_OUTEN_PWMB_EN(mask);
612 p->MCTRL |= FLEXPWM_MCTRL_LDOK(mask);
615#ifdef SIMPLEFOC_TEENSY4_FORCE_CENTER_ALIGNED_3PWM
621 void* _configureCenterAligned3PMW(
long pwm_frequency,
const int pinA,
const int pinB,
const int pinC) {
623 if(!pwm_frequency || !
_isset(pwm_frequency) ) pwm_frequency = _PWM_FREQUENCY;
624 else pwm_frequency =
_constrain(pwm_frequency, 0, _PWM_FREQUENCY_MAX);
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);
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!");
647 setup_pwm_timer_submodule (flexpwmA, submoduleA,
true, pwm_frequency) ;
648 setup_pwm_timer_submodule (flexpwmB, submoduleB,
true, pwm_frequency) ;
649 setup_pwm_timer_submodule (flexpwmC, submoduleC,
false, pwm_frequency) ;
650 delayMicroseconds (100) ;
653 #ifdef SIMPLEFOC_TEENSY_DEBUG
655 sprintf(buff,
"TEENSY-CS: Syncing to Master FlexPWM: %d, Submodule: %d", flexpwm_to_index(flexpwmC), submoduleC);
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);
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)) ;
668 TeensyDriverParams*
params =
new TeensyDriverParams {
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},
678 startup_pwm_pair (flexpwmA, submoduleA, channelA) ;
679 startup_pwm_pair (flexpwmB, submoduleB, channelB) ;
680 startup_pwm_pair (flexpwmC, submoduleC, channelC) ;
683 *portConfigRegister(
pinA) = pwm_pin_info[
pinA].muxval ;
684 *portConfigRegister(
pinB) = pwm_pin_info[
pinB].muxval ;
685 *portConfigRegister(
pinC) = pwm_pin_info[
pinC].muxval ;
689 #ifdef SIMPLEFOC_TEENSY_DEBUG
690 SIMPLEFOC_DEBUG(
"TEENSY-DRV: Not all pins on Flexpwm A and B channels - cannot configure center-aligned pwm!");
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);
#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
#define _constrain(amt, low, high)