6#if defined(_SAMD21_)||defined(_SAMD51_)||defined(_SAME51_)
13tccConfiguration tccPinConfigurations[SIMPLEFOC_SAMD_MAX_TCC_PINCONFIGURATIONS];
14uint8_t numTccPinConfigurations = 0;
15bool SAMDClockConfigured =
false;
16bool tccConfigured[TCC_INST_NUM+TC_INST_NUM];
25bool attachTCC(tccConfiguration& tccConfig) {
26 if (numTccPinConfigurations>=SIMPLEFOC_SAMD_MAX_TCC_PINCONFIGURATIONS)
28 pinMode(tccConfig.pin, OUTPUT);
30 pinPeripheral(tccConfig.pin, tccConfig.peripheral);
31 tccPinConfigurations[numTccPinConfigurations++] = tccConfig;
39int getPermutationNumber(
int pins) {
41 for (
int i=0;i<pins;i++)
42 num *= NUM_PIO_TIMER_PERIPHERALS;
52bool inUse(tccConfiguration& tccConfig) {
53 for (
int i=0;i<numTccPinConfigurations;i++) {
54 if (tccPinConfigurations[i].tcc.chaninfo==tccConfig.tcc.chaninfo)
61tccConfiguration* getTccPinConfiguration(uint8_t pin) {
62 for (
int i=0;i<numTccPinConfigurations;i++)
63 if (tccPinConfigurations[i].pin==pin)
64 return &tccPinConfigurations[i];
75tccConfiguration getTCCChannelNr(
int pin, EPioType peripheral) {
76 tccConfiguration result;
78 result.peripheral = peripheral;
81 const PinDescription& pinDesc = g_APinDescription[pin];
82 struct wo_association& association = getWOAssociation(pinDesc.ulPort, pinDesc.ulPin);
83 if (association.port==NOT_A_PORT)
85 if (peripheral==PIO_TIMER) {
86 result.tcc.chaninfo = association.tccE;
87 result.wo = association.woE;
89 else if (peripheral==PIO_TIMER_ALT) {
90 result.tcc.chaninfo = association.tccF;
91 result.wo = association.woF;
93#if defined(_SAMD51_)||defined(_SAME51_)
94 else if (peripheral==PIO_TCC_PDEC) {
95 result.tcc.chaninfo = association.tccG;
96 result.wo = association.woG;
106bool checkPeripheralPermutationSameTCC6(tccConfiguration& pinAh, tccConfiguration& pinAl, tccConfiguration& pinBh, tccConfiguration& pinBl, tccConfiguration& pinCh, tccConfiguration& pinCl) {
107 if (inUse(pinAh) || inUse(pinAl) || inUse(pinBh) || inUse(pinBl) || inUse(pinCh) || inUse(pinCl))
110 if (pinAh.tcc.tccn<0 || pinAh.tcc.tccn!=pinAl.tcc.tccn || pinAh.tcc.tccn!=pinBh.tcc.tccn || pinAh.tcc.tccn!=pinBl.tcc.tccn
111 || pinAh.tcc.tccn!=pinCh.tcc.tccn || pinAh.tcc.tccn!=pinCl.tcc.tccn || pinAh.tcc.tccn>=TCC_INST_NUM)
114 if (pinAh.tcc.chan==pinBh.tcc.chan || pinAh.tcc.chan==pinBl.tcc.chan || pinAh.tcc.chan==pinCh.tcc.chan || pinAh.tcc.chan==pinCl.tcc.chan)
116 if (pinBh.tcc.chan==pinCh.tcc.chan || pinBh.tcc.chan==pinCl.tcc.chan)
118 if (pinAl.tcc.chan==pinBh.tcc.chan || pinAl.tcc.chan==pinBl.tcc.chan || pinAl.tcc.chan==pinCh.tcc.chan || pinAl.tcc.chan==pinCl.tcc.chan)
120 if (pinBl.tcc.chan==pinCh.tcc.chan || pinBl.tcc.chan==pinCl.tcc.chan)
123 if (pinAh.tcc.chan!=pinAl.tcc.chan || pinBh.tcc.chan!=pinBl.tcc.chan || pinCh.tcc.chan!=pinCl.tcc.chan)
125 if (pinAh.wo==pinAl.wo || pinBh.wo==pinBl.wo || pinCh.wo!=pinCl.wo)
134bool checkPeripheralPermutationCompatible(tccConfiguration pins[], uint8_t num) {
135 for (
int i=0;i<num;i++)
136 if (pins[i].tcc.tccn<0)
138 for (
int i=0;i<num-1;i++)
139 for (
int j=i+1;j<num;j++)
140 if (pins[i].tcc.chaninfo==pins[j].tcc.chaninfo)
142 for (
int i=0;i<num;i++)
152bool checkPeripheralPermutationCompatible6(tccConfiguration& pinAh, tccConfiguration& pinAl, tccConfiguration& pinBh, tccConfiguration& pinBl, tccConfiguration& pinCh, tccConfiguration& pinCl) {
154 if (pinAh.tcc.tccn<0 || pinAl.tcc.tccn<0 || pinBh.tcc.tccn<0 || pinBl.tcc.tccn<0 || pinCh.tcc.tccn<0 || pinCl.tcc.tccn<0)
157 if (pinAh.tcc.tccn>=TCC_INST_NUM || pinAl.tcc.tccn>=TCC_INST_NUM || pinBh.tcc.tccn>=TCC_INST_NUM
158 || pinBl.tcc.tccn>=TCC_INST_NUM || pinCh.tcc.tccn>=TCC_INST_NUM || pinCl.tcc.tccn>=TCC_INST_NUM)
162 if (inUse(pinAh) || inUse(pinAl) || inUse(pinBh) || inUse(pinBl) || inUse(pinCh) || inUse(pinCl))
166 if (pinAh.tcc.chaninfo==pinBh.tcc.chaninfo || pinAh.tcc.chaninfo==pinBl.tcc.chaninfo || pinAh.tcc.chaninfo==pinCh.tcc.chaninfo || pinAh.tcc.chaninfo==pinCl.tcc.chaninfo)
168 if (pinAl.tcc.chaninfo==pinBh.tcc.chaninfo || pinAl.tcc.chaninfo==pinBl.tcc.chaninfo || pinAl.tcc.chaninfo==pinCh.tcc.chaninfo || pinAl.tcc.chaninfo==pinCl.tcc.chaninfo)
170 if (pinBh.tcc.chaninfo==pinCh.tcc.chaninfo || pinBh.tcc.chaninfo==pinCl.tcc.chaninfo)
172 if (pinBl.tcc.chaninfo==pinCh.tcc.chaninfo || pinBl.tcc.chaninfo==pinCl.tcc.chaninfo)
176 if (pinAh.tcc.tccn!=pinAl.tcc.tccn || pinBh.tcc.tccn!=pinBl.tcc.tccn || pinCh.tcc.tccn!=pinCl.tcc.tccn)
180 if (pinAh.wo==pinAl.wo || pinBh.wo==pinBl.wo || pinCh.wo==pinCl.wo)
191 for (
int i=0;i<64;i++) {
192 tccConfiguration pinAh = getTCCChannelNr(
pinA_h, getPeripheralOfPermutation(i, 0));
193 tccConfiguration pinAl = getTCCChannelNr(
pinA_l, getPeripheralOfPermutation(i, 1));
194 tccConfiguration pinBh = getTCCChannelNr(
pinB_h, getPeripheralOfPermutation(i, 2));
195 tccConfiguration pinBl = getTCCChannelNr(
pinB_l, getPeripheralOfPermutation(i, 3));
196 tccConfiguration pinCh = getTCCChannelNr(
pinC_h, getPeripheralOfPermutation(i, 4));
197 tccConfiguration pinCl = getTCCChannelNr(
pinC_l, getPeripheralOfPermutation(i, 5));
198 if (checkPeripheralPermutationSameTCC6(pinAh, pinAl, pinBh, pinBl, pinCh, pinCl))
208 for (
int i=0;i<64;i++) {
209 tccConfiguration pinAh = getTCCChannelNr(
pinA_h, getPeripheralOfPermutation(i, 0));
210 tccConfiguration pinAl = getTCCChannelNr(
pinA_l, getPeripheralOfPermutation(i, 1));
211 tccConfiguration pinBh = getTCCChannelNr(
pinB_h, getPeripheralOfPermutation(i, 2));
212 tccConfiguration pinBl = getTCCChannelNr(
pinB_l, getPeripheralOfPermutation(i, 3));
213 tccConfiguration pinCh = getTCCChannelNr(
pinC_h, getPeripheralOfPermutation(i, 4));
214 tccConfiguration pinCl = getTCCChannelNr(
pinC_l, getPeripheralOfPermutation(i, 5));
215 if (checkPeripheralPermutationCompatible6(pinAh, pinAl, pinBh, pinBl, pinCh, pinCl))
223int scorePermutation(tccConfiguration pins[], uint8_t num) {
224 uint32_t usedtccs = 0;
225 for (
int i=0;i<num;i++)
226 usedtccs |= (1<<pins[i].tcc.tccn);
228 for (
int i=0;i<TCC_INST_NUM;i++){
231 usedtccs = usedtccs>>1;
233 for (
int i=0;i<TC_INST_NUM;i++){
236 usedtccs = usedtccs>>1;
248int checkPermutations(uint8_t num,
int pins[],
bool (*checkFunc)(tccConfiguration[], uint8_t) ) {
249 tccConfiguration tccConfs[num];
251 int bestscore = 1000000;
252 for (
int i=0;i<(0x1<<num);i++) {
253 for (
int j=0;j<num;j++)
254 tccConfs[j] = getTCCChannelNr(pins[j], getPeripheralOfPermutation(i, j));
255 if (checkFunc(tccConfs, num)) {
256 int score = scorePermutation(tccConfs, num);
257 if (score<bestscore) {
282#ifdef SIMPLEFOC_SAMD_DEBUG
286 int compatibility = checkPermutations(2, pins, checkPeripheralPermutationCompatible);
287 if (compatibility<0) {
289#ifdef SIMPLEFOC_SAMD_DEBUG
295 tccConfiguration tccConfs[2] = { getTCCChannelNr(
pinA, getPeripheralOfPermutation(compatibility, 0)),
296 getTCCChannelNr(
pinB, getPeripheralOfPermutation(compatibility, 1)) };
299#ifdef SIMPLEFOC_SAMD_DEBUG
300 SIMPLEFOC_DEBUG(
"SAMD: Found configuration: score=", scorePermutation(tccConfs, 2));
301 printTCCConfiguration(tccConfs[0]);
302 printTCCConfiguration(tccConfs[1]);
306 attachTCC(tccConfs[0]);
307 attachTCC(tccConfs[1]);
308#ifdef SIMPLEFOC_SAMD_DEBUG
314 configureSAMDClock();
318 pwm_frequency = SIMPLEFOC_SAMD_DEFAULT_PWM_FREQUENCY_HZ;
322 configureTCC(tccConfs[0], pwm_frequency);
323 configureTCC(tccConfs[1], pwm_frequency);
324 getTccPinConfiguration(
pinA)->pwm_res = tccConfs[0].pwm_res;
325 getTccPinConfiguration(
pinB)->pwm_res = tccConfs[1].pwm_res;
326#ifdef SIMPLEFOC_SAMD_DEBUG
330 SAMDHardwareDriverParams*
params =
new SAMDHardwareDriverParams {
331 .tccPinConfigurations = { getTccPinConfiguration(
pinA), getTccPinConfiguration(
pinB) },
332 .pwm_frequency = (uint32_t)pwm_frequency
381#ifdef SIMPLEFOC_SAMD_DEBUG
385 int compatibility = checkPermutations(3, pins, checkPeripheralPermutationCompatible);
386 if (compatibility<0) {
388#ifdef SIMPLEFOC_SAMD_DEBUG
394 tccConfiguration tccConfs[3] = { getTCCChannelNr(
pinA, getPeripheralOfPermutation(compatibility, 0)),
395 getTCCChannelNr(
pinB, getPeripheralOfPermutation(compatibility, 1)),
396 getTCCChannelNr(
pinC, getPeripheralOfPermutation(compatibility, 2)) };
399#ifdef SIMPLEFOC_SAMD_DEBUG
400 SIMPLEFOC_DEBUG(
"SAMD: Found configuration: score=", scorePermutation(tccConfs, 3));
401 printTCCConfiguration(tccConfs[0]);
402 printTCCConfiguration(tccConfs[1]);
403 printTCCConfiguration(tccConfs[2]);
407 attachTCC(tccConfs[0]);
408 attachTCC(tccConfs[1]);
409 attachTCC(tccConfs[2]);
410#ifdef SIMPLEFOC_SAMD_DEBUG
416 configureSAMDClock();
420 pwm_frequency = SIMPLEFOC_SAMD_DEFAULT_PWM_FREQUENCY_HZ;
424 configureTCC(tccConfs[0], pwm_frequency);
425 configureTCC(tccConfs[1], pwm_frequency);
426 configureTCC(tccConfs[2], pwm_frequency);
427 getTccPinConfiguration(
pinA)->pwm_res = tccConfs[0].pwm_res;
428 getTccPinConfiguration(
pinB)->pwm_res = tccConfs[1].pwm_res;
429 getTccPinConfiguration(
pinC)->pwm_res = tccConfs[2].pwm_res;
430#ifdef SIMPLEFOC_SAMD_DEBUG
434 return new SAMDHardwareDriverParams {
435 .tccPinConfigurations = { getTccPinConfiguration(
pinA), getTccPinConfiguration(
pinB), getTccPinConfiguration(
pinC) },
436 .pwm_frequency = (uint32_t)pwm_frequency
460#ifdef SIMPLEFOC_SAMD_DEBUG
464 int compatibility = checkPermutations(4, pins, checkPeripheralPermutationCompatible);
465 if (compatibility<0) {
467#ifdef SIMPLEFOC_SAMD_DEBUG
473 tccConfiguration tccConfs[4] = { getTCCChannelNr(
pin1A, getPeripheralOfPermutation(compatibility, 0)),
474 getTCCChannelNr(
pin1B, getPeripheralOfPermutation(compatibility, 1)),
475 getTCCChannelNr(
pin2A, getPeripheralOfPermutation(compatibility, 2)),
476 getTCCChannelNr(
pin2B, getPeripheralOfPermutation(compatibility, 3)) };
479#ifdef SIMPLEFOC_SAMD_DEBUG
480 SIMPLEFOC_DEBUG(
"SAMD: Found configuration: score=", scorePermutation(tccConfs, 4));
481 printTCCConfiguration(tccConfs[0]);
482 printTCCConfiguration(tccConfs[1]);
483 printTCCConfiguration(tccConfs[2]);
484 printTCCConfiguration(tccConfs[3]);
488 attachTCC(tccConfs[0]);
489 attachTCC(tccConfs[1]);
490 attachTCC(tccConfs[2]);
491 attachTCC(tccConfs[3]);
492#ifdef SIMPLEFOC_SAMD_DEBUG
498 configureSAMDClock();
502 pwm_frequency = SIMPLEFOC_SAMD_DEFAULT_PWM_FREQUENCY_HZ;
506 configureTCC(tccConfs[0], pwm_frequency);
507 configureTCC(tccConfs[1], pwm_frequency);
508 configureTCC(tccConfs[2], pwm_frequency);
509 configureTCC(tccConfs[3], pwm_frequency);
510 getTccPinConfiguration(
pin1A)->pwm_res = tccConfs[0].pwm_res;
511 getTccPinConfiguration(
pin2A)->pwm_res = tccConfs[1].pwm_res;
512 getTccPinConfiguration(
pin1B)->pwm_res = tccConfs[2].pwm_res;
513 getTccPinConfiguration(
pin2B)->pwm_res = tccConfs[3].pwm_res;
514#ifdef SIMPLEFOC_SAMD_DEBUG
518 return new SAMDHardwareDriverParams {
519 .tccPinConfigurations = { getTccPinConfiguration(
pin1A), getTccPinConfiguration(
pin1B), getTccPinConfiguration(
pin2A), getTccPinConfiguration(
pin2B) },
520 .pwm_frequency = (uint32_t)pwm_frequency
563#ifdef SIMPLEFOC_SAMD_DEBUG
567 if (compatibility<0) {
569 if (compatibility<0) {
571#ifdef SIMPLEFOC_SAMD_DEBUG
578 tccConfiguration pinAh = getTCCChannelNr(
pinA_h, getPeripheralOfPermutation(compatibility, 0));
579 tccConfiguration pinAl = getTCCChannelNr(
pinA_l, getPeripheralOfPermutation(compatibility, 1));
580 tccConfiguration pinBh = getTCCChannelNr(
pinB_h, getPeripheralOfPermutation(compatibility, 2));
581 tccConfiguration pinBl = getTCCChannelNr(
pinB_l, getPeripheralOfPermutation(compatibility, 3));
582 tccConfiguration pinCh = getTCCChannelNr(
pinC_h, getPeripheralOfPermutation(compatibility, 4));
583 tccConfiguration pinCl = getTCCChannelNr(
pinC_l, getPeripheralOfPermutation(compatibility, 5));
585#ifdef SIMPLEFOC_SAMD_DEBUG
587 printTCCConfiguration(pinAh);
588 printTCCConfiguration(pinAl);
589 printTCCConfiguration(pinBh);
590 printTCCConfiguration(pinBl);
591 printTCCConfiguration(pinCh);
592 printTCCConfiguration(pinCl);
596 bool allAttached =
true;
597 allAttached |= attachTCC(pinAh);
598 allAttached |= attachTCC(pinAl);
599 allAttached |= attachTCC(pinBh);
600 allAttached |= attachTCC(pinBl);
601 allAttached |= attachTCC(pinCh);
602 allAttached |= attachTCC(pinCl);
605#ifdef SIMPLEFOC_SAMD_DEBUG
610 configureSAMDClock();
614 pwm_frequency = SIMPLEFOC_SAMD_DEFAULT_PWM_FREQUENCY_HZ;
618 configureTCC(pinAh, pwm_frequency,
false, (pinAh.tcc.chaninfo==pinAl.tcc.chaninfo)?
dead_zone:-1);
619 if ((pinAh.tcc.chaninfo!=pinAl.tcc.chaninfo))
620 configureTCC(pinAl, pwm_frequency,
true, -1.0);
621 configureTCC(pinBh, pwm_frequency,
false, (pinBh.tcc.chaninfo==pinBl.tcc.chaninfo)?
dead_zone:-1);
622 if ((pinBh.tcc.chaninfo!=pinBl.tcc.chaninfo))
623 configureTCC(pinBl, pwm_frequency,
true, -1.0);
624 configureTCC(pinCh, pwm_frequency,
false, (pinCh.tcc.chaninfo==pinCl.tcc.chaninfo)?
dead_zone:-1);
625 if ((pinCh.tcc.chaninfo!=pinCl.tcc.chaninfo))
626 configureTCC(pinCl, pwm_frequency,
true, -1.0);
627 getTccPinConfiguration(
pinA_h)->pwm_res = pinAh.pwm_res;
628 getTccPinConfiguration(
pinA_l)->pwm_res = pinAh.pwm_res;
629 getTccPinConfiguration(
pinB_h)->pwm_res = pinBh.pwm_res;
630 getTccPinConfiguration(
pinB_l)->pwm_res = pinBh.pwm_res;
631 getTccPinConfiguration(
pinC_h)->pwm_res = pinCh.pwm_res;
632 getTccPinConfiguration(
pinC_l)->pwm_res = pinCh.pwm_res;
633#ifdef SIMPLEFOC_SAMD_DEBUG
637 return new SAMDHardwareDriverParams {
638 .tccPinConfigurations = { getTccPinConfiguration(
pinA_h), getTccPinConfiguration(
pinA_l), getTccPinConfiguration(
pinB_h), getTccPinConfiguration(
pinB_l), getTccPinConfiguration(
pinC_h), getTccPinConfiguration(
pinC_l) },
639 .pwm_frequency = (uint32_t)pwm_frequency,
658 writeSAMDDutyCycle(((SAMDHardwareDriverParams*)
params)->tccPinConfigurations[0], dc_a);
659 writeSAMDDutyCycle(((SAMDHardwareDriverParams*)
params)->tccPinConfigurations[1],
dc_b);
680 writeSAMDDutyCycle(((SAMDHardwareDriverParams*)
params)->tccPinConfigurations[0], dc_a);
681 writeSAMDDutyCycle(((SAMDHardwareDriverParams*)
params)->tccPinConfigurations[1],
dc_b);
682 writeSAMDDutyCycle(((SAMDHardwareDriverParams*)
params)->tccPinConfigurations[2],
dc_c);
704 writeSAMDDutyCycle(((SAMDHardwareDriverParams*)
params)->tccPinConfigurations[0], dc_1a);
705 writeSAMDDutyCycle(((SAMDHardwareDriverParams*)
params)->tccPinConfigurations[1],
dc_1b);
706 writeSAMDDutyCycle(((SAMDHardwareDriverParams*)
params)->tccPinConfigurations[2],
dc_2a);
707 writeSAMDDutyCycle(((SAMDHardwareDriverParams*)
params)->tccPinConfigurations[3],
dc_2b);
738 SAMDHardwareDriverParams* p = (SAMDHardwareDriverParams*)
params;
739 tccConfiguration* tcc1 = p->tccPinConfigurations[0];
740 tccConfiguration* tcc2 = p->tccPinConfigurations[1];
741 uint32_t pwm_res =p->tccPinConfigurations[0]->pwm_res;
742 if (tcc1->tcc.chaninfo!=tcc2->tcc.chaninfo) {
744 float ls = dc_a+(p->dead_zone * (pwm_res-1));
745 if (ls>1.0) ls = 1.0f;
746 writeSAMDDutyCycle(tcc1, dc_a);
747 writeSAMDDutyCycle(tcc2, ls);
750 writeSAMDDutyCycle(tcc1, dc_a);
752 tcc1 = p->tccPinConfigurations[2];
753 tcc2 = p->tccPinConfigurations[3];
754 if (tcc1->tcc.chaninfo!=tcc2->tcc.chaninfo) {
755 float ls =
dc_b+(p->dead_zone * (pwm_res-1));
756 if (ls>1.0) ls = 1.0f;
757 writeSAMDDutyCycle(tcc1,
dc_b);
758 writeSAMDDutyCycle(tcc2, ls);
761 writeSAMDDutyCycle(tcc1,
dc_b);
763 tcc1 = p->tccPinConfigurations[4];
764 tcc2 = p->tccPinConfigurations[5];
765 if (tcc1->tcc.chaninfo!=tcc2->tcc.chaninfo) {
766 float ls =
dc_c+(p->dead_zone * (pwm_res-1));
767 if (ls>1.0) ls = 1.0f;
768 writeSAMDDutyCycle(tcc1,
dc_c);
769 writeSAMDDutyCycle(tcc2, ls);
772 writeSAMDDutyCycle(tcc1,
dc_c);
781#if defined(SIMPLEFOC_SAMD_DEBUG) && !defined(SIMPLEFOC_DISABLE_DEBUG)
788void printAllPinInfos() {
790 for (uint8_t pin=0;pin<PINS_COUNT;pin++) {
791 const PinDescription& pinDesc = g_APinDescription[pin];
792 wo_association& association = getWOAssociation(pinDesc.ulPort, pinDesc.ulPin);
796 switch (pinDesc.ulPort) {
801#if defined(_SAMD51_)||defined(_SAME51_)
809 if (association.tccE>=0) {
810 int tcn = GetTCNumber(association.tccE);
811 if (tcn>=TCC_INST_NUM){
831 if (association.tccF>=0) {
832 int tcn = GetTCNumber(association.tccF);
833 if (tcn>=TCC_INST_NUM){
852#if defined(_SAMD51_)||defined(_SAME51_)
854 if (association.tccG>=0) {
855 int tcn = GetTCNumber(association.tccG);
880void printTCCConfiguration(tccConfiguration& info) {
882 if (info.tcc.tccn>=TCC_INST_NUM)
886 switch (info.peripheral) {
891#if defined(_SAMD51_)||defined(_SAME51_)
898 if (info.tcc.tccn>=0) {
#define SIMPLEFOC_DEBUG(msg,...)
static void print(const char *msg)
const int const int const int pinC
GenericCurrentSenseParams * params
void * _configure4PWM(long pwm_frequency, const int pin1A, const int pin1B, const int pin2A, const int pin2B)
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)
void * _configure2PWM(long pwm_frequency, const int pinA, const int pinB)
void _writeDutyCycle2PWM(float dc_a, float dc_b, void *params)
#define SIMPLEFOC_DRIVER_INIT_FAILED
void _writeDutyCycle4PWM(float dc_1a, float dc_1b, float dc_2a, float dc_2b, void *params)
void * _configure3PWM(long pwm_frequency, const int pinA, const int pinB, const int pinC)
void _writeDutyCycle6PWM(float dc_a, float dc_b, float dc_c, PhaseState *phase_state, void *params)
void _writeDutyCycle3PWM(float dc_a, float dc_b, float dc_c, void *params)
float const int const int const int pinB_h
float const int const int const int const int pinB_l
const int const int pin1B
const int const int const int pin2A
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
const int const int const int const int pin2B