Skip to content
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
40 changes: 26 additions & 14 deletions src/drivers/hardware_specific/samd21_mcu.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -159,6 +159,7 @@ void configureSAMDClock() {
REG_GCLK_GENCTRL = GCLK_GENCTRL_IDC | // Set the duty cycle to 50/50 HIGH/LOW
GCLK_GENCTRL_GENEN | // Enable GCLK4
GCLK_GENCTRL_SRC_DFLL48M | // Set the 48MHz clock source
// GCLK_GENCTRL_SRC_FDPLL | // Set the 96MHz clock source
GCLK_GENCTRL_ID(4); // Select GCLK4
while (GCLK->STATUS.bit.SYNCBUSY); // Wait for synchronization

Expand All @@ -177,6 +178,15 @@ void configureSAMDClock() {
* faster won't be possible without sacrificing resolution.
*/
void configureTCC(tccConfiguration& tccConfig, long pwm_frequency, bool negate, float hw6pwm) {

long pwm_resolution = (24000000) / pwm_frequency;
if (pwm_resolution>SIMPLEFOC_SAMD_MAX_PWM_RESOLUTION)
pwm_resolution = SIMPLEFOC_SAMD_MAX_PWM_RESOLUTION;
if (pwm_resolution<SIMPLEFOC_SAMD_MIN_PWM_RESOLUTION)
pwm_resolution = SIMPLEFOC_SAMD_MIN_PWM_RESOLUTION;
// store for later use
tccConfig.pwm_res = pwm_resolution;

// TODO for the moment we ignore the frequency...
if (!tccConfigured[tccConfig.tcc.tccn]) {
uint32_t GCLK_CLKCTRL_ID_ofthistcc = -1;
Expand Down Expand Up @@ -234,12 +244,12 @@ void configureTCC(tccConfiguration& tccConfig, long pwm_frequency, bool negate,

if (hw6pwm>0.0) {
tcc->WEXCTRL.vec.DTIEN |= (1<<tccConfig.tcc.chan);
tcc->WEXCTRL.bit.DTLS = hw6pwm*(SIMPLEFOC_SAMD_PWM_RESOLUTION-1);
tcc->WEXCTRL.bit.DTHS = hw6pwm*(SIMPLEFOC_SAMD_PWM_RESOLUTION-1);
tcc->WEXCTRL.bit.DTLS = hw6pwm*(pwm_resolution-1);
tcc->WEXCTRL.bit.DTHS = hw6pwm*(pwm_resolution-1);
syncTCC(tcc); // wait for sync
}

tcc->PER.reg = SIMPLEFOC_SAMD_PWM_RESOLUTION - 1; // Set counter Top using the PER register
tcc->PER.reg = pwm_resolution - 1; // Set counter Top using the PER register
while ( tcc->SYNCBUSY.bit.PER == 1 ); // wait for sync

// set all channels to 0%
Expand All @@ -261,7 +271,8 @@ void configureTCC(tccConfiguration& tccConfig, long pwm_frequency, bool negate,
SIMPLEFOC_SAMD_DEBUG_SERIAL.print(tccConfig.tcc.chan);
SIMPLEFOC_SAMD_DEBUG_SERIAL.print("[");
SIMPLEFOC_SAMD_DEBUG_SERIAL.print(tccConfig.wo);
SIMPLEFOC_SAMD_DEBUG_SERIAL.println("]");
SIMPLEFOC_SAMD_DEBUG_SERIAL.print("] pwm res ");
SIMPLEFOC_SAMD_DEBUG_SERIAL.println(pwm_resolution);
#endif
}
}
Expand All @@ -279,8 +290,8 @@ void configureTCC(tccConfiguration& tccConfig, long pwm_frequency, bool negate,

if (hw6pwm>0.0) {
tcc->WEXCTRL.vec.DTIEN |= (1<<tccConfig.tcc.chan);
tcc->WEXCTRL.bit.DTLS = hw6pwm*(SIMPLEFOC_SAMD_PWM_RESOLUTION-1);
tcc->WEXCTRL.bit.DTHS = hw6pwm*(SIMPLEFOC_SAMD_PWM_RESOLUTION-1);
tcc->WEXCTRL.bit.DTLS = hw6pwm*(pwm_resolution-1);
tcc->WEXCTRL.bit.DTHS = hw6pwm*(pwm_resolution-1);
syncTCC(tcc); // wait for sync
}

Expand All @@ -294,7 +305,8 @@ void configureTCC(tccConfiguration& tccConfig, long pwm_frequency, bool negate,
SIMPLEFOC_SAMD_DEBUG_SERIAL.print(tccConfig.tcc.chan);
SIMPLEFOC_SAMD_DEBUG_SERIAL.print("[");
SIMPLEFOC_SAMD_DEBUG_SERIAL.print(tccConfig.wo);
SIMPLEFOC_SAMD_DEBUG_SERIAL.println("]");
SIMPLEFOC_SAMD_DEBUG_SERIAL.print("] pwm res ");
SIMPLEFOC_SAMD_DEBUG_SERIAL.println(pwm_resolution);
#endif
}

Expand All @@ -305,26 +317,26 @@ void configureTCC(tccConfiguration& tccConfig, long pwm_frequency, bool negate,



void writeSAMDDutyCycle(int chaninfo, float dc) {
uint8_t tccn = GetTCNumber(chaninfo);
uint8_t chan = GetTCChannelNumber(chaninfo);
void writeSAMDDutyCycle(tccConfiguration* info, float dc) {
uint8_t tccn = GetTCNumber(info->tcc.chaninfo);
uint8_t chan = GetTCChannelNumber(info->tcc.chaninfo);
if (tccn<TCC_INST_NUM) {
Tcc* tcc = (Tcc*)GetTC(chaninfo);
Tcc* tcc = (Tcc*)GetTC(info->tcc.chaninfo);
// set via CC
// tcc->CC[chan].reg = (uint32_t)((SIMPLEFOC_SAMD_PWM_RESOLUTION-1) * dc);
// uint32_t chanbit = 0x1<<(TCC_SYNCBUSY_CC0_Pos+chan);
// while ( (tcc->SYNCBUSY.reg & chanbit) > 0 );
// set via CCB
while ( (tcc->SYNCBUSY.vec.CC & (0x1<<chan)) > 0 );
tcc->CCB[chan].reg = (uint32_t)((SIMPLEFOC_SAMD_PWM_RESOLUTION-1) * dc);
//while ( (tcc->SYNCBUSY.vec.CC & (0x1<<chan)) > 0 );
tcc->CCB[chan].reg = (uint32_t)((info->pwm_res-1) * dc);
// while ( (tcc->SYNCBUSY.vec.CCB & (0x1<<chan)) > 0 );
// tcc->STATUS.vec.CCBV |= (0x1<<chan);
// while ( tcc->SYNCBUSY.bit.STATUS > 0 );
// tcc->CTRLBSET.reg |= TCC_CTRLBSET_CMD(TCC_CTRLBSET_CMD_UPDATE_Val);
// while ( tcc->SYNCBUSY.bit.CTRLB > 0 );
}
else {
Tc* tc = (Tc*)GetTC(chaninfo);
Tc* tc = (Tc*)GetTC(info->tcc.chaninfo);
tc->COUNT8.CC[chan].reg = (uint8_t)((SIMPLEFOC_SAMD_PWM_TC_RESOLUTION-1) * dc);
while ( tc->COUNT8.STATUS.bit.SYNCBUSY == 1 );
}
Expand Down
63 changes: 38 additions & 25 deletions src/drivers/hardware_specific/samd51_mcu.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -7,6 +7,16 @@



// expected frequency on DPLL, since we don't configure it ourselves. Typically this is the CPU frequency.
// for custom boards or overclockers you can override it using this define.
#ifndef SIMPLEFOC_SAMD51_DPLL_FREQ
#define SIMPLEFOC_SAMD51_DPLL_FREQ 120000000
#endif





// TCC# Channels WO_NUM Counter size Fault Dithering Output matrix DTI SWAP Pattern generation
// 0 6 8 24-bit Yes Yes Yes Yes Yes Yes
// 1 4 8 24-bit Yes Yes Yes Yes Yes Yes
Expand All @@ -17,7 +27,6 @@

#define NUM_WO_ASSOCIATIONS 72


struct wo_association WO_associations[] = {

{ PORTB, 9, TC4_CH1, 1, NOT_ON_TIMER, 0, NOT_ON_TIMER, 0},
Expand Down Expand Up @@ -112,7 +121,7 @@ struct wo_association& getWOAssociation(EPortType port, uint32_t pin) {


EPioType getPeripheralOfPermutation(int permutation, int pin_position) {
return ((permutation>>pin_position)&0x01)==0x1?PIO_TIMER_ALT:PIO_TIMER;
return ((permutation>>pin_position)&0x01)==0x1?PIO_TCC_PDEC:PIO_TIMER_ALT;
}


Expand All @@ -124,24 +133,17 @@ void syncTCC(Tcc* TCCx) {



void writeSAMDDutyCycle(int chaninfo, float dc) {
uint8_t tccn = GetTCNumber(chaninfo);
uint8_t chan = GetTCChannelNumber(chaninfo);
void writeSAMDDutyCycle(tccConfiguration* info, float dc) {
uint8_t tccn = GetTCNumber(info->tcc.chaninfo);
uint8_t chan = GetTCChannelNumber(info->tcc.chaninfo);
if (tccn<TCC_INST_NUM) {
Tcc* tcc = (Tcc*)GetTC(chaninfo);
Tcc* tcc = (Tcc*)GetTC(info->tcc.chaninfo);
// set via CCBUF
while ( (tcc->SYNCBUSY.vec.CC & (0x1<<chan)) > 0 );
tcc->CCBUF[chan].reg = (uint32_t)((SIMPLEFOC_SAMD_PWM_RESOLUTION-1) * dc); // TODO pwm frequency!
// tcc->STATUS.vec.CCBUFV |= (0x1<<chan);
// while ( tcc->SYNCBUSY.bit.STATUS > 0 );
// tcc->CTRLBSET.reg |= TCC_CTRLBSET_CMD(TCC_CTRLBSET_CMD_UPDATE_Val);
// while ( tcc->SYNCBUSY.bit.CTRLB > 0 );
// while ( (tcc->SYNCBUSY.vec.CC & (0x1<<chan)) > 0 );
tcc->CCBUF[chan].reg = (uint32_t)((info->pwm_res-1) * dc); // TODO pwm frequency!
}
else {
// Tc* tc = (Tc*)GetTC(chaninfo);
// //tc->COUNT16.CC[chan].reg = (uint32_t)((SIMPLEFOC_SAMD_PWM_RESOLUTION-1) * dc);
// tc->COUNT8.CC[chan].reg = (uint8_t)((SIMPLEFOC_SAMD_PWM_TC_RESOLUTION-1) * dc);
// while ( tc->COUNT8.STATUS.bit.SYNCBUSY == 1 );
else {
// we don't support the TC channels on SAMD51, isn't worth it.
}
}

Expand Down Expand Up @@ -183,8 +185,8 @@ void configureSAMDClock() {
while (GCLK->SYNCBUSY.vec.GENCTRL&(0x1<<PWM_CLOCK_NUM));

GCLK->GENCTRL[PWM_CLOCK_NUM].reg = GCLK_GENCTRL_GENEN | GCLK_GENCTRL_DIV(1) | GCLK_GENCTRL_IDC
| GCLK_GENCTRL_SRC(GCLK_GENCTRL_SRC_DFLL_Val);
//| GCLK_GENCTRL_SRC(GCLK_GENCTRL_SRC_DPLL0_Val);
//| GCLK_GENCTRL_SRC(GCLK_GENCTRL_SRC_DFLL_Val);
| GCLK_GENCTRL_SRC(GCLK_GENCTRL_SRC_DPLL0_Val);
while (GCLK->SYNCBUSY.vec.GENCTRL&(0x1<<PWM_CLOCK_NUM));

#ifdef SIMPLEFOC_SAMD_DEBUG
Expand Down Expand Up @@ -221,18 +223,27 @@ void configureTCC(tccConfiguration& tccConfig, long pwm_frequency, bool negate,
tcc->DRVCTRL.vec.INVEN = (tcc->DRVCTRL.vec.INVEN&invenMask)|invenVal;
syncTCC(tcc); // wait for sync

// work out pwm resolution for desired frequency and constrain to max/min values
long pwm_resolution = (SIMPLEFOC_SAMD51_DPLL_FREQ/2) / pwm_frequency;
if (pwm_resolution>SIMPLEFOC_SAMD_MAX_PWM_RESOLUTION)
pwm_resolution = SIMPLEFOC_SAMD_MAX_PWM_RESOLUTION;
if (pwm_resolution<SIMPLEFOC_SAMD_MIN_PWM_RESOLUTION)
pwm_resolution = SIMPLEFOC_SAMD_MIN_PWM_RESOLUTION;
// store for later use
tccConfig.pwm_res = pwm_resolution;

if (hw6pwm>0.0) {
tcc->WEXCTRL.vec.DTIEN |= (1<<tccConfig.tcc.chan);
tcc->WEXCTRL.bit.DTLS = hw6pwm*(SIMPLEFOC_SAMD_PWM_RESOLUTION-1);
tcc->WEXCTRL.bit.DTHS = hw6pwm*(SIMPLEFOC_SAMD_PWM_RESOLUTION-1);
tcc->WEXCTRL.bit.DTLS = hw6pwm*(pwm_resolution-1);
tcc->WEXCTRL.bit.DTHS = hw6pwm*(pwm_resolution-1);
syncTCC(tcc); // wait for sync
}

if (!tccConfigured[tccConfig.tcc.tccn]) {
tcc->WAVE.reg |= TCC_WAVE_POL(0xF)|TCC_WAVE_WAVEGEN_DSTOP; // Set wave form configuration - TODO check this... why set like this?
while ( tcc->SYNCBUSY.bit.WAVE == 1 ); // wait for sync

tcc->PER.reg = SIMPLEFOC_SAMD_PWM_RESOLUTION - 1; // Set counter Top using the PER register
tcc->PER.reg = pwm_resolution - 1; // Set counter Top using the PER register
while ( tcc->SYNCBUSY.bit.PER == 1 ); // wait for sync

// set all channels to 0%
Expand All @@ -254,11 +265,12 @@ void configureTCC(tccConfiguration& tccConfig, long pwm_frequency, bool negate,
SIMPLEFOC_SAMD_DEBUG_SERIAL.print(tccConfig.tcc.chan);
SIMPLEFOC_SAMD_DEBUG_SERIAL.print("[");
SIMPLEFOC_SAMD_DEBUG_SERIAL.print(tccConfig.wo);
SIMPLEFOC_SAMD_DEBUG_SERIAL.println("]");
SIMPLEFOC_SAMD_DEBUG_SERIAL.print("] pwm res ");
SIMPLEFOC_SAMD_DEBUG_SERIAL.println(pwm_resolution);
#endif
}
else if (tccConfig.tcc.tccn>=TCC_INST_NUM) {
Tc* tc = (Tc*)GetTC(tccConfig.tcc.chaninfo);
//Tc* tc = (Tc*)GetTC(tccConfig.tcc.chaninfo);

// disable
// tc->COUNT8.CTRLA.bit.ENABLE = 0;
Expand All @@ -280,8 +292,9 @@ void configureTCC(tccConfiguration& tccConfig, long pwm_frequency, bool negate,
// while ( tc->COUNT8.STATUS.bit.SYNCBUSY == 1 );

#ifdef SIMPLEFOC_SAMD_DEBUG
SIMPLEFOC_SAMD_DEBUG_SERIAL.print("Initialized TC ");
SIMPLEFOC_SAMD_DEBUG_SERIAL.print("Not initialized: TC ");
SIMPLEFOC_SAMD_DEBUG_SERIAL.println(tccConfig.tcc.tccn);
SIMPLEFOC_SAMD_DEBUG_SERIAL.print("TC units not supported on SAMD51");
#endif
}

Expand Down
Loading