Skip to content

Commit b34bd62

Browse files
committed
initial support for teensy4 low-side current sensing (only for 6pwm at the motment) - in progress
1 parent 3ad11ee commit b34bd62

File tree

4 files changed

+273
-11
lines changed

4 files changed

+273
-11
lines changed
Lines changed: 191 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,191 @@
1+
#include "teensy4_mcu.h"
2+
#include "../../../drivers/hardware_specific/teensy/teensy4_mcu.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+
// function finding the TRIG event given the flexpwm timer and the submodule
10+
// returning -1 if the submodule is not valid or no trigger is available
11+
// allowing flexpwm1-4 and submodule 0-3
12+
//
13+
// the flags are defined in the imxrt.h file
14+
// https://github.com/PaulStoffregen/cores/blob/dd6aa8419ee173a0a6593eab669fbff54ed85f48/teensy4/imxrt.h#L9662
15+
int flextim__submodule_to_trig(IMXRT_FLEXPWM_t* flexpwm, int submodule){
16+
if(submodule <0 && submodule > 3) return -1;
17+
if(flexpwm == &IMXRT_FLEXPWM1){
18+
return XBARA1_IN_FLEXPWM1_PWM1_OUT_TRIG0 + submodule;
19+
}else if(flexpwm == &IMXRT_FLEXPWM2){
20+
return XBARA1_IN_FLEXPWM2_PWM1_OUT_TRIG0 + submodule;
21+
}else if(flexpwm == &IMXRT_FLEXPWM3){
22+
return XBARA1_IN_FLEXPWM3_PWM1_OUT_TRIG0 + submodule;
23+
}else if(flexpwm == &IMXRT_FLEXPWM4){
24+
return XBARA1_IN_FLEXPWM4_PWM1_OUT_TRIG0 + submodule;
25+
}
26+
return -1;
27+
}
28+
29+
volatile uint32_t val0, val1;
30+
31+
void read_currents(uint32_t *a, uint32_t*b){
32+
*a = val0;
33+
*b = val1;
34+
}
35+
36+
// interrupt service routine for the ADC_ETC0
37+
// reading the ADC values and clearing the interrupt
38+
void adcetc0_isr() {
39+
digitalWrite(30,HIGH);
40+
ADC_ETC_DONE0_1_IRQ |= 1; // clear
41+
val0 = ADC_ETC_TRIG0_RESULT_1_0 & 4095;
42+
val1 = (ADC_ETC_TRIG0_RESULT_1_0 >> 16) & 4095;
43+
asm("dsb");
44+
digitalWrite(30,LOW);
45+
}
46+
47+
// function initializing the ADC2
48+
// and the ADC_ETC trigger for the low side current sensing
49+
void adc1_init() {
50+
//Tried many configurations, but this seems to be best:
51+
ADC1_CFG = ADC_CFG_OVWREN //Allow overwriting of the next converted Data onto the existing
52+
| ADC_CFG_ADICLK(0) // input clock select - IPG clock
53+
| ADC_CFG_MODE(2) // 12-bit conversion 0 8-bit conversion 1 10-bit conversion 2 12-bit conversion
54+
| ADC_CFG_ADIV(2) // Input clock / 4
55+
| ADC_CFG_ADSTS(0) // Sample period (ADC clocks) = 3 if ADLSMP=0b
56+
| ADC_CFG_ADHSC // High speed operation
57+
| ADC_CFG_ADTRG; // Hardware trigger selected
58+
59+
60+
//Calibration of ADC1
61+
ADC1_GC |= ADC_GC_CAL; // begin cal ADC1
62+
while (ADC1_GC & ADC_GC_CAL) ;
63+
64+
ADC1_HC0 = 16; // ADC_ETC channel
65+
// use the second interrupt if necessary (for more than 2 channels)
66+
// ADC1_HC1 = 16;
67+
}
68+
69+
// function initializing the ADC2
70+
// and the ADC_ETC trigger for the low side current sensing
71+
void adc2_init(){
72+
73+
// configuring ADC2
74+
//Tried many configurations, but this seems to be best:
75+
ADC1_CFG = ADC_CFG_OVWREN //Allow overwriting of the next converted Data onto the existing
76+
| ADC_CFG_ADICLK(0) // input clock select - IPG clock
77+
| ADC_CFG_MODE(2) // 12-bit conversion 0 8-bit conversion 1 10-bit conversion 2 12-bit conversion
78+
| ADC_CFG_ADIV(2) // Input clock / 4
79+
| ADC_CFG_ADSTS(0) // Sample period (ADC clocks) = 3 if ADLSMP=0b
80+
| ADC_CFG_ADHSC // High speed operation
81+
| ADC_CFG_ADTRG; // Hardware trigger selected
82+
83+
//Calibration of ADC2
84+
ADC2_GC |= ADC_GC_CAL; // begin cal ADC2
85+
while (ADC2_GC & ADC_GC_CAL) ;
86+
87+
ADC2_HC0 = 16; // ADC_ETC channel
88+
// use the second interrupt if necessary (for more than 2 channels)
89+
// ADC2_HC1 = 16;
90+
}
91+
92+
void adc_etc_init(int pin1, int pin2) {
93+
ADC_ETC_CTRL &= ~(1 << 31); // SOFTRST
94+
ADC_ETC_CTRL = 0x40000001; // start with trigger 0
95+
ADC_ETC_TRIG0_CTRL = 0x100; // chainlength -1
96+
97+
// ADC1 7 8, chain channel, HWTS, IE, B2B
98+
// pg 3516, section 66.5.1.8
99+
ADC_ETC_TRIG0_CHAIN_1_0 =
100+
ADC_ETC_TRIG_CHAIN_IE1(0) | // no interrupt on first or set 2 if interrupt when Done1
101+
ADC_ETC_TRIG_CHAIN_B2B1 | // Enable B2B, back to back ADC trigger
102+
ADC_ETC_TRIG_CHAIN_HWTS1(1) |
103+
ADC_ETC_TRIG_CHAIN_CSEL1(pin_to_channel[pin1]) | // ADC channel 8
104+
ADC_ETC_TRIG_CHAIN_IE0(1) | // interrupt when Done0
105+
ADC_ETC_TRIG_CHAIN_B2B1 | // Enable B2B, back to back ADC trigger
106+
ADC_ETC_TRIG_CHAIN_HWTS0(1) |
107+
ADC_ETC_TRIG_CHAIN_CSEL0(pin_to_channel[pin2]); // ADC channel 7
108+
109+
attachInterruptVector(IRQ_ADC_ETC0, adcetc0_isr);
110+
NVIC_ENABLE_IRQ(IRQ_ADC_ETC0);
111+
// use the second interrupt if necessary (for more than 2 channels)
112+
// attachInterruptVector(IRQ_ADC_ETC1, adcetc1_isr);
113+
// NVIC_ENABLE_IRQ(IRQ_ADC_ETC1);
114+
}
115+
116+
117+
void xbar_connect(unsigned int input, unsigned int output)
118+
{
119+
if (input >= 88) return;
120+
if (output >= 132) return;
121+
volatile uint16_t *xbar = &XBARA1_SEL0 + (output / 2);
122+
uint16_t val = *xbar;
123+
if (!(output & 1)) {
124+
val = (val & 0xFF00) | input;
125+
} else {
126+
val = (val & 0x00FF) | (input << 8);
127+
}
128+
*xbar = val;
129+
}
130+
void xbar_init() {
131+
CCM_CCGR2 |= CCM_CCGR2_XBAR1(CCM_CCGR_ON); //turn clock on for xbara1
132+
}
133+
134+
135+
// function reading an ADC value and returning the read voltage
136+
float _readADCVoltageLowSide(const int pinA, const void* cs_params){
137+
138+
GenericCurrentSenseParams* params = (GenericCurrentSenseParams*) cs_params;
139+
float adc_voltage_conv = params->adc_voltage_conv;
140+
if (pinA == params->pins[0]) {
141+
return val0 * adc_voltage_conv;
142+
} else if (pinA == params->pins[1]) {
143+
return val1 * adc_voltage_conv;
144+
}
145+
return 0.0;
146+
}
147+
148+
// Configure low side for generic mcu
149+
// cannot do much but
150+
void* _configureADCLowSide(const void* driver_params, const int pinA,const int pinB,const int pinC){
151+
_UNUSED(driver_params);
152+
153+
pinMode(30,OUTPUT);
154+
155+
if( _isset(pinA) ) pinMode(pinA, INPUT);
156+
if( _isset(pinB) ) pinMode(pinB, INPUT);
157+
if( _isset(pinC) ) pinMode(pinC, INPUT);
158+
159+
adc1_init();
160+
adc_etc_init(pinA, pinB);
161+
xbar_init();
162+
GenericCurrentSenseParams* params = new GenericCurrentSenseParams {
163+
.pins = { pinA, pinB, pinC },
164+
.adc_voltage_conv = (_ADC_VOLTAGE)/(_ADC_RESOLUTION)
165+
};
166+
return params;
167+
}
168+
169+
// sync driver and the adc
170+
void _driverSyncLowSide(void* driver_params, void* cs_params){
171+
Teensy4DriverParams* par = (Teensy4DriverParams*) driver_params;
172+
IMXRT_FLEXPWM_t* flexpwm = par->flextimers[0];
173+
int submodule = par->submodules[0];
174+
175+
// do xbar connect here
176+
177+
int xbar_trig_pwm = flextim__submodule_to_trig(flexpwm, submodule);
178+
if(xbar_trig_pwm<0) return;
179+
180+
xbar_connect((uint32_t)xbar_trig_pwm, XBARA1_OUT_ADC_ETC_TRIG00); //FlexPWM to adc_etc
181+
182+
// setup the ADC_ETC trigger
183+
flexpwm->SM[submodule].TCTRL = FLEXPWM_SMTCTRL_OUT_TRIG_EN(1<<4);
184+
// setup this val4 for interrupt on val5 match for ADC sync
185+
// reading two ARC takes about 5us. So put the interrupt 2.5us befor the center
186+
flexpwm->SM[submodule].VAL4 = -int(2.5e-6*par->pwm_frequency*flexpwm->SM[submodule].VAL1) ; // 2.5us before center
187+
188+
}
189+
190+
191+
#endif
Lines changed: 77 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,77 @@
1+
2+
#ifndef TEENSY4_CURRENTSENSE_MCU_DEF
3+
#define TEENSY4_CURRENTSENSE_MCU_DEF
4+
5+
#include "../../hardware_api.h"
6+
#include "../../../common/foc_utils.h"
7+
8+
// if defined
9+
// - Teensy 4.0
10+
// - Teensy 4.1
11+
#if defined(__arm__) && defined(CORE_TEENSY) && ( defined(__IMXRT1062__) || defined(ARDUINO_TEENSY40) || defined(ARDUINO_TEENSY41) || defined(ARDUINO_TEENSY_MICROMOD) )
12+
13+
#define _ADC_VOLTAGE 3.3f
14+
#define _ADC_RESOLUTION 4026.0f
15+
16+
// generic implementation of the hardware specific structure
17+
// containing all the necessary current sense parameters
18+
// will be returned as a void pointer from the _configureADCx functions
19+
// will be provided to the _readADCVoltageX() as a void pointer
20+
typedef struct Teensy4CurrentSenseParams {
21+
int pins[3] = {(int)NOT_SET};
22+
float adc_voltage_conv;
23+
} Teensy4CurrentSenseParams;
24+
25+
26+
27+
const uint8_t pin_to_channel[] = { // pg 482
28+
7, // 0/A0 AD_B1_02
29+
8, // 1/A1 AD_B1_03
30+
12, // 2/A2 AD_B1_07
31+
11, // 3/A3 AD_B1_06
32+
6, // 4/A4 AD_B1_01
33+
5, // 5/A5 AD_B1_00
34+
15, // 6/A6 AD_B1_10
35+
0, // 7/A7 AD_B1_11
36+
13, // 8/A8 AD_B1_08
37+
14, // 9/A9 AD_B1_09
38+
1, // 24/A10 AD_B0_12
39+
2, // 25/A11 AD_B0_13
40+
128+3, // 26/A12 AD_B1_14 - only on ADC2, 3
41+
128+4, // 27/A13 AD_B1_15 - only on ADC2, 4
42+
7, // 14/A0 AD_B1_02
43+
8, // 15/A1 AD_B1_03
44+
12, // 16/A2 AD_B1_07
45+
11, // 17/A3 AD_B1_06
46+
6, // 18/A4 AD_B1_01
47+
5, // 19/A5 AD_B1_00
48+
15, // 20/A6 AD_B1_10
49+
0, // 21/A7 AD_B1_11
50+
13, // 22/A8 AD_B1_08
51+
14, // 23/A9 AD_B1_09
52+
1, // 24/A10 AD_B0_12
53+
2, // 25/A11 AD_B0_13
54+
128+3, // 26/A12 AD_B1_14 - only on ADC2, 3
55+
128+4, // 27/A13 AD_B1_15 - only on ADC2, 4
56+
#ifdef ARDUINO_TEENSY41
57+
255, // 28
58+
255, // 29
59+
255, // 30
60+
255, // 31
61+
255, // 32
62+
255, // 33
63+
255, // 34
64+
255, // 35
65+
255, // 36
66+
255, // 37
67+
128+1, // 38/A14 AD_B1_12 - only on ADC2, 1
68+
128+2, // 39/A15 AD_B1_13 - only on ADC2, 2
69+
9, // 40/A16 AD_B1_04
70+
10, // 41/A17 AD_B1_05
71+
#endif
72+
};
73+
74+
75+
#endif
76+
77+
#endif

src/current_sense/hardware_specific/teensy_mcu.cpp renamed to src/current_sense/hardware_specific/teensy/teensy_mcu.cpp

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -1,4 +1,4 @@
1-
#include "../hardware_api.h"
1+
#include "../../hardware_api.h"
22

33
#if defined(__arm__) && defined(CORE_TEENSY)
44

src/drivers/hardware_specific/teensy/teensy4_mcu.cpp

Lines changed: 4 additions & 10 deletions
Original file line numberDiff line numberDiff line change
@@ -177,18 +177,15 @@ void setup_pwm_pair (IMXRT_FLEXPWM_t * flexpwm, int submodule, const long freque
177177
FLEXPWM_SMCTRL2_FRCEN | FLEXPWM_SMCTRL2_INIT_SEL(0) | FLEXPWM_SMCTRL2_FORCE_SEL(6);
178178
flexpwm->SM[submodule].CTRL = FLEXPWM_SMCTRL_FULL | FLEXPWM_SMCTRL_HALF | FLEXPWM_SMCTRL_PRSC(prescale) ;
179179
// https://github.com/PaulStoffregen/cores/blob/70ba01accd728abe75ebfc8dcd8b3d3a8f3e3f25/teensy4/imxrt.h#L4948
180-
flexpwm->SM[submodule].OCTRL = 0;//channel_to_invert==2 ? 0 : FLEXPWM_SMOCTRL_POLA | FLEXPWM_SMOCTRL_POLB ;
180+
flexpwm->SM[submodule].OCTRL = 0; //FLEXPWM_SMOCTRL_POLA | FLEXPWM_SMOCTRL_POLB;//channel_to_invert==2 ? 0 : FLEXPWM_SMOCTRL_POLA | FLEXPWM_SMOCTRL_POLB ;
181181
flexpwm->SM[submodule].DTCNT0 = dead_time ; // should try this out (deadtime control)
182182
flexpwm->SM[submodule].DTCNT1 = dead_time ; // should try this out (deadtime control)
183-
// flexpwm->SM[submodule].TCTRL = FLEXPWM_SMTCTRL_OUT_TRIG_EN (0b000010) ; // sync trig out on VAL1 match.
184183
flexpwm->SM[submodule].INIT = -half_cycle; // count from -HALFCYCLE to +HALFCYCLE
185-
flexpwm->SM[submodule].VAL0 = 0 ;
184+
flexpwm->SM[submodule].VAL0 = 0;
186185
flexpwm->SM[submodule].VAL1 = half_cycle ;
187186
flexpwm->SM[submodule].VAL2 = -mid_pwm ;
188187
flexpwm->SM[submodule].VAL3 = +mid_pwm ;
189-
// flexpwm->SM[submodule].VAL4 = -mid_pwm ;
190-
// flexpwm->SM[submodule].VAL5 = +mid_pwm ;
191-
188+
192189
flexpwm->MCTRL |= FLEXPWM_MCTRL_LDOK (submodule_mask) ; // loading reenabled
193190
flexpwm->MCTRL |= FLEXPWM_MCTRL_RUN (submodule_mask) ; // start it running
194191
}
@@ -207,14 +204,11 @@ void startup_pwm_pair (IMXRT_FLEXPWM_t * flexpwm, int submodule)
207204

208205
// PWM setting on the high and low pair of the PWM channels
209206
void write_pwm_pair(IMXRT_FLEXPWM_t * flexpwm, int submodule, float duty){
210-
211207
int mid_pwm = int((half_cycle)/2.0f);
212208
int count_pwm = int(mid_pwm*(duty*2-1)) + mid_pwm;
213209

214210
flexpwm->SM[submodule].VAL2 = count_pwm; // A on
215211
flexpwm->SM[submodule].VAL3 = -count_pwm ; // A off
216-
// flexpwm->SM[submodule].VAL4 = - count_pwm ; // B off (assuming B inverted)
217-
// flexpwm->SM[submodule].VAL5 = + count_pwm ; // B on
218212
flexpwm->MCTRL |= FLEXPWM_MCTRL_LDOK (1<<submodule) ; // signal new values
219213
}
220214

@@ -262,7 +256,7 @@ void* _configure6PWM(long pwm_frequency, float dead_zone, const int pinA_h, cons
262256

263257

264258
Teensy4DriverParams* params = new Teensy4DriverParams {
265-
.flextimers = { flexpwmA,flexpwmB, flexpwmC},
259+
.flextimers = { flexpwmA, flexpwmB, flexpwmC},
266260
.submodules = { submoduleA, submoduleB, submoduleC},
267261
.pwm_frequency = pwm_frequency,
268262
.dead_zone = dead_zone

0 commit comments

Comments
 (0)