Skip to content
Snippets Groups Projects
Commit 381e1353 authored by Quentin Bolsee's avatar Quentin Bolsee
Browse files

use TCC0 at 20kHz PWM

parent 8831e93d
No related branches found
No related tags found
No related merge requests found
......@@ -12,6 +12,17 @@ This is a variant based on the DRV8428P which is a dual H-bridge chip in the DRV
## Microstepping
Microstepping involves applying PWM on the H-bridges inputs, this is still under development. A quick test showed 732Hz is too slow; the motor vibrates when any sort of load is applied. A higher frequency should be feasible by decreasing TCC0's counter. For 20kHz, a counter of 2400 (instead of 0xFFFF) should be ok with TCC0 in 16-bit mode. Pins PA8, PA9, PA14 and PA15 can all be MUXed to TCC0's outputs with proper settings.
<img src="microstep.mp4" width="100%">
Microstepping up to 32 is achieved through PWM on the H-bridge inputs. A high frequency is needed, therefore 4 channels of TCC0 are used:
| Pin | TCC0 channel | MUX |
|------|--------------|-----|
| PA8 | 2 | E |
| PA8 | 3 | E |
| PA14 | 0 | F |
| PA15 | 1 | F |
TCC0 is then setup in normal PWM mode with a period of 2400, yielding 20kHz with a prescaler of 1. This is more than 11 bits of resolution for a nice, smooth sine signal on each of the PWM inputs:
<img src="img/pwm_lookup.png" width="100%">
serialstep/serialstep-DRV8428P/img/pwm_lookup.png

56.9 KiB

......@@ -4,7 +4,7 @@ import matplotlib.pyplot as plt
def main():
peak = 4095
peak = 2400
n_micro = 32
# 4 phase cycle
......@@ -12,12 +12,16 @@ def main():
i = np.arange(n_tot)
theta = i * 2 * math.pi/n_tot
table_ideal = peak * np.sin(theta)
table_ideal[2 * n_micro:] = 0
table = np.round(table_ideal).astype(np.int32)
table[2 * n_micro:] = 0
plt.figure()
plt.plot(table_ideal, "b")
plt.step(table, "r")
plt.title("xIN PWM lookup")
plt.xlabel("index")
plt.ylabel("value")
plt.legend(["ideal", "quantized"])
plt.show()
print("int sine_table[] = {")
......
......@@ -12,31 +12,45 @@
// warranty is provided, and users accept all liability.
//
#define INCR_MOD(a, b, c) ((a+b)%c)
// pins
#define LEDA 4
#define LEDC 2
#define NSLEEP 5
#define AIN1 8
#define AIN2 9
#define BIN1 14
#define BIN2 15
#define BUTTON 31
#define BLINK 100
// TCC0 channels
#define AIN1_CH 2
#define AIN2_CH 3
#define BIN1_CH 0
#define BIN2_CH 1
// peripherals
#define AIN1_PER PER_TIMER
#define AIN2_PER PER_TIMER
#define BIN1_PER PER_TIMER_ALT
#define BIN2_PER PER_TIMER_ALT
// any power of 2 <= TABLE_MICROSTEP
#define MICROSTEP 32
// constants
#define TABLE_MICROSTEP 32
#define CYCLE 4
#define TCC0_PERIOD 2400
#define TABLE_LENGTH (CYCLE*TABLE_MICROSTEP)
#define TABLE_INCR (TABLE_MICROSTEP/MICROSTEP)
// power of 2, <= TABLE_MICROSTEP
#define MICROSTEP 2
// macros
#define SYNC_TCC0() while (TCC0->SYNCBUSY.reg & TCC_SYNCBUSY_MASK)
#define INCR_MOD(a, b, c) (((a+b)%c + c) % c)
unsigned int sine_table[] = {
0, 201, 401, 601, 799, 995,1189,1380,1567,1751,1930,2105,2275,2439,2598,2750,2896,3034,3165,3289,3405,3512,3611,3702,3783,3856,3919,3972,4016,4051,4075,4090,
4095,4090,4075,4051,4016,3972,3919,3856,3783,3702,3611,3512,3405,3289,3165,3034,2896,2750,2598,2439,2275,2105,1930,1751,1567,1380,1189, 995, 799, 601, 401, 201,
uint16_t sine_table[] = {
0, 118, 235, 352, 468, 583, 697, 809, 918,1026,1131,1234,1333,1430,1523,1612,1697,1778,1855,1928,1996,2059,2117,2170,2217,2260,2297,2328,2354,2374,2388,2397,
2400,2397,2388,2374,2354,2328,2297,2260,2217,2170,2117,2059,1996,1928,1855,1778,1697,1612,1523,1430,1333,1234,1131,1026, 918, 809, 697, 583, 468, 352, 235, 118,
0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0,
0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0
};
......@@ -47,6 +61,48 @@ int count_A2 = 2*TABLE_MICROSTEP;
int count_B1 = TABLE_MICROSTEP;
int count_B2 = 3*TABLE_MICROSTEP;
void setup_peripheral(uint8_t pinNum, EPioPeripheral peripheral) {
uint8_t pinCfg = (PORT->Group[PORTA].PINCFG[pinNum].reg & PORT_PINCFG_PULLEN);
if ( pinNum & 1 ) { // odd pin
uint32_t temp = (PORT->Group[PORTA].PMUX[pinNum >> 1].reg) & PORT_PMUX_PMUXE( 0xF ) ;
PORT->Group[PORTA].PMUX[pinNum >> 1].reg = temp|PORT_PMUX_PMUXO( peripheral ) ;
} else { // even pin
uint32_t temp = (PORT->Group[PORTA].PMUX[pinNum >> 1].reg) & PORT_PMUX_PMUXO( 0xF ) ;
PORT->Group[PORTA].PMUX[pinNum >> 1].reg = temp|PORT_PMUX_PMUXE( peripheral ) ;
}
pinCfg |= PORT_PINCFG_PMUXEN; // Enable peripheral mux
PORT->Group[PORTA].PINCFG[pinNum].reg = (uint8_t)pinCfg;
}
void setup_timer() {
setup_peripheral(BIN1, BIN1_PER);
setup_peripheral(BIN2, BIN2_PER);
setup_peripheral(AIN1, AIN1_PER);
setup_peripheral(AIN2, AIN2_PER);
GCLK->CLKCTRL.reg = (uint16_t) (GCLK_CLKCTRL_CLKEN | GCLK_CLKCTRL_GEN_GCLK0 | GCM_TCC0) ;
while ( GCLK->STATUS.bit.SYNCBUSY == 1 );
TCC0->CTRLA.bit.ENABLE = 0;
SYNC_TCC0();
TCC0->WAVE.reg |= TCC_WAVE_WAVEGEN_NPWM;
SYNC_TCC0();
TCC0->PER.reg = TCC0_PERIOD;
SYNC_TCC0();
TCC0->CTRLA.bit.ENABLE = 1;
SYNC_TCC0();
}
void update_pwm(int timerChannel, uint16_t value) {
TCC0->CTRLBSET.bit.LUPD = 1;
SYNC_TCC0();
TCC0->CCB[timerChannel].reg = (uint32_t) value;
SYNC_TCC0();
TCC0->CTRLBCLR.bit.LUPD = 1;
SYNC_TCC0();
}
void setup() {
SerialUSB.begin(0);
digitalWrite(LEDA,HIGH);
......@@ -55,17 +111,10 @@ void setup() {
pinMode(LEDC,OUTPUT);
digitalWrite(NSLEEP,HIGH);
pinMode(NSLEEP,OUTPUT);
digitalWrite(AIN1,LOW);
pinMode(AIN1,OUTPUT);
digitalWrite(AIN2,LOW);
pinMode(AIN2,OUTPUT);
digitalWrite(BIN1,LOW);
pinMode(BIN1,OUTPUT);
digitalWrite(BIN2,LOW);
pinMode(BIN2,OUTPUT);
pinMode(BUTTON, INPUT_PULLUP);
// 10-bit PWM
analogWriteResolution(12);
// init TCC0 and enable outputs
setup_timer();
// init stepping
step(0);
}
......@@ -77,10 +126,11 @@ void step(int val) {
count_A2 = INCR_MOD(count_A2, val_incr, TABLE_LENGTH);
count_B1 = INCR_MOD(count_B1, val_incr, TABLE_LENGTH);
count_B2 = INCR_MOD(count_B2, val_incr, TABLE_LENGTH);
analogWrite(AIN1, sine_table[count_A1]);
analogWrite(AIN2, sine_table[count_A2]);
analogWrite(BIN1, sine_table[count_B1]);
analogWrite(BIN2, sine_table[count_B2]);
update_pwm(AIN1_CH, sine_table[count_A1]);
update_pwm(AIN2_CH, sine_table[count_A2]);
update_pwm(BIN1_CH, sine_table[count_B1]);
update_pwm(BIN2_CH, sine_table[count_B2]);
}
......
0% Loading or .
You are about to add 0 people to the discussion. Proceed with caution.
Please register or to comment