Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Fix SAMD51 WO_associations #93

Merged
merged 3 commits into from Jul 20, 2021
Merged

Fix SAMD51 WO_associations #93

merged 3 commits into from Jul 20, 2021

Conversation

runger1101001
Copy link
Member

Fixes the WO_associations for SAMD51/SAME51, which had erroneously used only 4 channels of TCC0 (which has 6).

Also this patch adds the enable_active_high setting to the 3-PWM driver, in the same way as we have it for the 6-PWM driver.

@askuric
Copy link
Member

askuric commented Jun 10, 2021

Hey Richhard,

This actually does not resolve the problem for me.

I still cannot use pins 3,4 and 11 to set the pwm on them.

I think this has something to do with the way the code choses whether to use TC or TCC.
Here is the debugging output:

Pin 00  PA23  E= TC9-1[1]  F=TCC1-3[7]  G=TCC 0-3[3]
Pin 01  PA22  E= TC9-0[0]  F=TCC1-2[6]  G=TCC 0-2[2]
Pin 02  PB17  E= TC11-1[1] F=TCC3-1[1]  G=TCC 0-5[5]
Pin 03  PB16  E= TC11-0[0] F=TCC3-0[0]  G=TCC 0-4[4]
Pin 04  PB13  E= TC9-1[1]  F=TCC3-1[1]  G=TCC 0-1[1]
Pin 05  PB14  E= TC10-0[0] F=TCC4-0[0]  G=TCC 0-2[2]
Pin 06  PB15  E= TC10-1[1] F=TCC4-1[1]  G=TCC 0-3[3]
Pin 07  PB12  E= TC9-0[0]  F=TCC3-0[0]  G=TCC 0-0[0]
Pin 08  PA21  E= TC12-1[1] F=TCC1-1[5]  G=TCC 0-1[1]
Pin 09  PA20  E= TC12-0[0] F=TCC1-0[4]  G=TCC 0-0[0]
Pin 10  PA18  E= TC8-0[0]  F=TCC1-2[2]  G=TCC 0-0[6]
Pin 11  PA19  E= TC8-1[1]  F=TCC1-3[3]  G=TCC 0-1[7]
Pin 12  PA17  E= TC7-1[1]  F=TCC1-1[1]  G=TCC 0-5[5]
Pin 13  PA16  E= TC7-0[0]  F=TCC1-0[0]  G=TCC 0-4[4]
Pin 14  PA02  E=  None     F=  None     G=  None 
Pin 15  PA05  E= TC5-1[1]  F=  None     G=  None 
Pin 16  PA06  E= TC6-0[0]  F=  None     G=  None 
Pin 17  PA04  E= TC5-0[0]  F=  None     G=  None 
Pin 18  PB08  E=  None     F=  None     G=  None 
Pin 19  PB09  E= TC9-1[1]  F=  None     G=  None 
Pin 20  PB02  E= TC11-0[0] F=TCC2-2[2]  G=  None 
Pin 21  PB03  E=  None     F=  None     G=  None 
Pin 22  PB02  E= TC11-0[0] F=TCC2-2[2]  G=  None 
Pin 23  PB03  E=  None     F=  None     G=  None 
Pin 24  PA14  E= TC8-0[0]  F=TCC2-0[0]  G=TCC 1-2[2]
Pin 25  PA13  E= TC7-1[1]  F=TCC0-1[7]  G=TCC 1-3[3]

Found configuration: (score=2)
4: TCC Peripheral F 3-1[1]
9:  TC Peripheral E 12-0[0]
11: TCC Peripheral F 1-3[3]
Attached pins...
Configured clock...
(Re-)Initialized TCC 3-1[1]
Initialized TC 12
(Re-)Initialized TCC 1-3[3]

I've seen in the code that the TC is commented out but it seems to me that for SAMD51 the code can still select it:
Should this function be chnaged:

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

I've tried to dig into the code few times so far, but I am really having trouble understanding the functions:
scorePermutation, checkPermutations, getPeripheralOfPermutation.
Also I don't sure the choices you have made about should one motor be on one TCC or it can share more of them or how it works exactly?

This is the output for 3, 9, 11:

Pin 00  PA23  E= TC9-1[1]  F=TCC1-3[7]  G=TCC 0-3[3]
Pin 01  PA22  E= TC9-0[0]  F=TCC1-2[6]  G=TCC 0-2[2]
Pin 02  PB17  E= TC11-1[1] F=TCC3-1[1]  G=TCC 0-5[5]
Pin 03  PB16  E= TC11-0[0] F=TCC3-0[0]  G=TCC 0-4[4]
Pin 04  PB13  E= TC9-1[1]  F=TCC3-1[1]  G=TCC 0-1[1]
Pin 05  PB14  E= TC10-0[0] F=TCC4-0[0]  G=TCC 0-2[2]
Pin 06  PB15  E= TC10-1[1] F=TCC4-1[1]  G=TCC 0-3[3]
Pin 07  PB12  E= TC9-0[0]  F=TCC3-0[0]  G=TCC 0-0[0]
Pin 08  PA21  E= TC12-1[1] F=TCC1-1[5]  G=TCC 0-1[1]
Pin 09  PA20  E= TC12-0[0] F=TCC1-0[4]  G=TCC 0-0[0]
Pin 10  PA18  E= TC8-0[0]  F=TCC1-2[2]  G=TCC 0-0[6]
Pin 11  PA19  E= TC8-1[1]  F=TCC1-3[3]  G=TCC 0-1[7]
Pin 12  PA17  E= TC7-1[1]  F=TCC1-1[1]  G=TCC 0-5[5]
Pin 13  PA16  E= TC7-0[0]  F=TCC1-0[0]  G=TCC 0-4[4]
Pin 14  PA02  E=  None     F=  None     G=  None 
Pin 15  PA05  E= TC5-1[1]  F=  None     G=  None 
Pin 16  PA06  E= TC6-0[0]  F=  None     G=  None 
Pin 17  PA04  E= TC5-0[0]  F=  None     G=  None 
Pin 18  PB08  E=  None     F=  None     G=  None 
Pin 19  PB09  E= TC9-1[1]  F=  None     G=  None 
Pin 20  PB02  E= TC11-0[0] F=TCC2-2[2]  G=  None 
Pin 21  PB03  E=  None     F=  None     G=  None 
Pin 22  PB02  E= TC11-0[0] F=TCC2-2[2]  G=  None 
Pin 23  PB03  E=  None     F=  None     G=  None 
Pin 24  PA14  E= TC8-0[0]  F=TCC2-0[0]  G=TCC 1-2[2]
Pin 25  PA13  E= TC7-1[1]  F=TCC0-1[7]  G=TCC 1-3[3]

Found configuration: (score=1)
3:  TC Peripheral E 11-0[0]
9:  TC Peripheral E 12-0[0]
11: TCC Peripheral F 1-3[3]

@runger1101001
Copy link
Member Author

Hey Antun!

I will look at it again.
I actually saw a similar thing, with TC12 being selected on pin 9 in my test with the feather board. But when I did a make clean, and rebuild it disappeared, so I assumed it was due to old code. But I will try to check this again now more in-depth.

Regarding your question:

  • assigning the TCCs to the pins is a major headache in SAMD architecture. On SAMD51, each pin has up to 3 timer peripherals: Peripheral E - TC Units, Peripheral F - TCC, or peripheral G - TCC.
  • Since almost all pins have TCC units on SAMD51, and the TC units are so much crappier at motor control, I didn't bother with the TC-Units for SAMD51. Not worth it. On SAMD21 I use them, because there are only 2 timer peripherals per pin, and many pins don't have TCC units.
  • For 3-PWM it doesn't matter which timers are used. For 6-PWM, high and low for each phase should come from the same TCC unit. If they additionally use complementary WOs (waveform outputs) then HW-dead time can be used
  • So finding a compatible configuration of timers is a small optimisation problem: best would be if all pins are from the same TCC with high and low on complementary WOs. Next best is all pins on the same TCC. Next best is all pins on TCCs. Fewer TCCs is better than more. etc....
  • So there is a function which tests all the different permutations of assigning peripherals to pins and scores each one, selecting the best scoring configuration as the one that is used in the end.
  • Of course if multiple motors are involved the code has to take into account that some of the TCC-channels might already be used (on another pin, since they typically have multiple pins assigned).
  • That's what the functions scorePermutation, checkPermutations, getPeripheralOfPermutation are used for, they do this optimisation problem.

I'll go over it again, and simply remove the TC-units from the SAMD51 side of things altogether. To be honest, it is a bug that it assigns the TC-Units in the first place, since I didn't write the code to configure them.

@askuric askuric merged commit 9114ecd into simplefoc:dev Jul 20, 2021
@runger1101001
Copy link
Member Author

I think the above is now solved in PR #134

Sign up for free to join this conversation on GitHub. Already have an account? Sign in to comment
Labels
None yet
Projects
None yet
Development

Successfully merging this pull request may close these issues.

None yet

2 participants