Skip to content

Commit a94c7dd

Browse files
Merge pull request simplefoc#218 from runger1101001/dev
1-PWM support for some MCUs and SAMD21 bug fix for ItsyBitsy M4
2 parents 940e2d6 + 44e4c4a commit a94c7dd

File tree

8 files changed

+212
-0
lines changed

8 files changed

+212
-0
lines changed

src/drivers/hardware_specific/atmega2560_mcu.cpp

Lines changed: 23 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -25,6 +25,21 @@ void _pinHighFrequency(const int pin){
2525
}
2626

2727

28+
// function setting the high pwm frequency to the supplied pins
29+
// - Stepper motor - 2PWM setting
30+
// - hardware speciffic
31+
void* _configure1PWM(long pwm_frequency,const int pinA) {
32+
// High PWM frequency
33+
// - always max 32kHz
34+
_pinHighFrequency(pinA);
35+
GenericDriverParams* params = new GenericDriverParams {
36+
.pins = { pinA },
37+
.pwm_frequency = pwm_frequency
38+
};
39+
return params;
40+
}
41+
42+
2843
// function setting the high pwm frequency to the supplied pins
2944
// - Stepper motor - 2PWM setting
3045
// - hardware speciffic
@@ -56,6 +71,14 @@ void* _configure3PWM(long pwm_frequency,const int pinA, const int pinB, const in
5671
return params;
5772
}
5873

74+
// function setting the pwm duty cycle to the hardware
75+
// - Stepper motor - 2PWM setting
76+
// - hardware speciffic
77+
void _writeDutyCycle1PWM(float dc_a, void* params){
78+
// transform duty cycle from [0,1] to [0,255]
79+
analogWrite(((GenericDriverParams*)params)->pins[0], 255.0f*dc_a);
80+
}
81+
5982
// function setting the pwm duty cycle to the hardware
6083
// - Stepper motor - 2PWM setting
6184
// - hardware speciffic

src/drivers/hardware_specific/atmega328_mcu.cpp

Lines changed: 26 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -17,6 +17,20 @@ void _pinHighFrequency(const int pin){
1717

1818
}
1919

20+
// function setting the high pwm frequency to the supplied pins
21+
// - Stepper motor - 2PWM setting
22+
// - hardware speciffic
23+
// supports Arudino/ATmega328
24+
void* _configure1PWM(long pwm_frequency,const int pinA) {
25+
// High PWM frequency
26+
// - always max 32kHz
27+
_pinHighFrequency(pinA);
28+
GenericDriverParams* params = new GenericDriverParams {
29+
.pins = { pinA },
30+
.pwm_frequency = pwm_frequency
31+
};
32+
return params;
33+
}
2034
// function setting the high pwm frequency to the supplied pins
2135
// - Stepper motor - 2PWM setting
2236
// - hardware speciffic
@@ -50,6 +64,18 @@ void* _configure3PWM(long pwm_frequency,const int pinA, const int pinB, const in
5064
return params;
5165
}
5266

67+
68+
69+
70+
// function setting the pwm duty cycle to the hardware
71+
// - Stepper motor - 2PWM setting
72+
// - hardware speciffic
73+
void _writeDutyCycle1PWM(float dc_a, void* params){
74+
// transform duty cycle from [0,1] to [0,255]
75+
analogWrite(((GenericDriverParams*)params)->pins[0], 255.0f*dc_a);
76+
}
77+
78+
5379
// function setting the pwm duty cycle to the hardware
5480
// - Stepper motor - 2PWM setting
5581
// - hardware speciffic

src/drivers/hardware_specific/atmega32u4_mcu.cpp

Lines changed: 25 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -28,6 +28,20 @@ void _pinHighFrequency(const int pin){
2828
}
2929

3030

31+
// function setting the high pwm frequency to the supplied pins
32+
// - Stepper motor - 2PWM setting
33+
// - hardware speciffic
34+
void* _configure1PWM(long pwm_frequency,const int pinA) {
35+
// High PWM frequency
36+
// - always max 32kHz
37+
_pinHighFrequency(pinA);
38+
GenericDriverParams* params = new GenericDriverParams {
39+
.pins = { pinA },
40+
.pwm_frequency = pwm_frequency
41+
};
42+
return params;
43+
}
44+
3145
// function setting the high pwm frequency to the supplied pins
3246
// - Stepper motor - 2PWM setting
3347
// - hardware speciffic
@@ -59,6 +73,17 @@ void* _configure3PWM(long pwm_frequency,const int pinA, const int pinB, const in
5973
return params;
6074
}
6175

76+
77+
78+
// function setting the pwm duty cycle to the hardware
79+
// - Stepper motor - 2PWM setting
80+
// - hardware speciffic
81+
void _writeDutyCycle1PWM(float dc_a, void* params){
82+
// transform duty cycle from [0,1] to [0,255]
83+
analogWrite(((GenericDriverParams*)params)->pins[0], 255.0f*dc_a);
84+
}
85+
86+
6287
// function setting the pwm duty cycle to the hardware
6388
// - Stepper motor - 2PWM setting
6489
// - hardware speciffic

src/drivers/hardware_specific/esp32_ledc_mcu.cpp

Lines changed: 33 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -53,6 +53,33 @@ void _setHighFrequency(const long freq, const int pin, const int channel){
5353

5454

5555

56+
57+
58+
59+
void* _configure1PWM(long pwm_frequency, const int pinA) {
60+
if(!pwm_frequency || !_isset(pwm_frequency) ) pwm_frequency = _PWM_FREQUENCY; // default frequency 25khz
61+
else pwm_frequency = _constrain(pwm_frequency, 0, _PWM_FREQUENCY_MAX); // constrain to 50kHz max
62+
63+
// check if enough channels available
64+
if ( channel_index + 1 >= LEDC_CHANNELS ) return SIMPLEFOC_DRIVER_INIT_FAILED;
65+
66+
int ch1 = channel_index++;
67+
_setHighFrequency(pwm_frequency, pinA, ch1);
68+
69+
ESP32LEDCDriverParams* params = new ESP32LEDCDriverParams {
70+
.channels = { ch1 },
71+
.pwm_frequency = pwm_frequency
72+
};
73+
return params;
74+
}
75+
76+
77+
78+
79+
80+
81+
82+
5683
void* _configure2PWM(long pwm_frequency, const int pinA, const int pinB) {
5784
if(!pwm_frequency || !_isset(pwm_frequency) ) pwm_frequency = _PWM_FREQUENCY; // default frequency 25khz
5885
else pwm_frequency = _constrain(pwm_frequency, 0, _PWM_FREQUENCY_MAX); // constrain to 50kHz max
@@ -123,6 +150,12 @@ void* _configure4PWM(long pwm_frequency,const int pinA, const int pinB, const in
123150

124151

125152

153+
void _writeDutyCycle1PWM(float dc_a, void* params){
154+
ledcWrite(((ESP32LEDCDriverParams*)params)->channels[0], _constrain(_PWM_RES*dc_a, 0, _PWM_RES));
155+
}
156+
157+
158+
126159
void _writeDutyCycle2PWM(float dc_a, float dc_b, void* params){
127160
ledcWrite(((ESP32LEDCDriverParams*)params)->channels[0], _constrain(_PWM_RES*dc_a, 0, _PWM_RES));
128161
ledcWrite(((ESP32LEDCDriverParams*)params)->channels[1], _constrain(_PWM_RES*dc_b, 0, _PWM_RES));

src/drivers/hardware_specific/esp8266_mcu.cpp

Lines changed: 23 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -12,6 +12,22 @@ void _setHighFrequency(const long freq, const int pin){
1212
}
1313

1414

15+
// function setting the high pwm frequency to the supplied pins
16+
// - Stepper motor - 2PWM setting
17+
// - hardware speciffic
18+
void* _configure1PWM(long pwm_frequency, const int pinA) {
19+
if(!pwm_frequency || !_isset(pwm_frequency) ) pwm_frequency = _PWM_FREQUENCY; // default frequency 25khz
20+
else pwm_frequency = _constrain(pwm_frequency, 0, _PWM_FREQUENCY_MAX); // constrain to 50kHz max
21+
_setHighFrequency(pwm_frequency, pinA);
22+
GenericDriverParams* params = new GenericDriverParams {
23+
.pins = { pinA },
24+
.pwm_frequency = pwm_frequency
25+
};
26+
return params;
27+
}
28+
29+
30+
1531
// function setting the high pwm frequency to the supplied pins
1632
// - Stepper motor - 2PWM setting
1733
// - hardware speciffic
@@ -60,6 +76,13 @@ void* _configure4PWM(long pwm_frequency,const int pinA, const int pinB, const in
6076
return params;
6177
}
6278

79+
// function setting the pwm duty cycle to the hardware
80+
// - Stepper motor - 2PWM setting
81+
// - hardware speciffic
82+
void _writeDutyCycle1PWM(float dc_a, void* params){
83+
// transform duty cycle from [0,1] to [0,255]
84+
analogWrite(((GenericDriverParams*)params)->pins[0], 255.0f*dc_a);
85+
}
6386
// function setting the pwm duty cycle to the hardware
6487
// - Stepper motor - 2PWM setting
6588
// - hardware speciffic

src/drivers/hardware_specific/rp2040_mcu.cpp

Lines changed: 19 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -95,6 +95,19 @@ void syncSlices() {
9595
}
9696

9797

98+
99+
void* _configure1PWM(long pwm_frequency, const int pinA) {
100+
RP2040DriverParams* params = new RP2040DriverParams();
101+
if( !pwm_frequency || !_isset(pwm_frequency) ) pwm_frequency = _PWM_FREQUENCY;
102+
else pwm_frequency = _constrain(pwm_frequency, _PWM_FREQUENCY_MIN, _PWM_FREQUENCY_MAX);
103+
params->pwm_frequency = pwm_frequency;
104+
setupPWM(pinA, pwm_frequency, !SIMPLEFOC_PWM_ACTIVE_HIGH, params, 0);
105+
syncSlices();
106+
return params;
107+
}
108+
109+
110+
98111
void* _configure2PWM(long pwm_frequency, const int pinA, const int pinB) {
99112
RP2040DriverParams* params = new RP2040DriverParams();
100113
if( !pwm_frequency || !_isset(pwm_frequency) ) pwm_frequency = _PWM_FREQUENCY;
@@ -165,6 +178,12 @@ void writeDutyCycle(float val, uint slice, uint chan) {
165178

166179

167180

181+
void _writeDutyCycle1PWM(float dc_a, void* params) {
182+
writeDutyCycle(dc_a, ((RP2040DriverParams*)params)->slice[0], ((RP2040DriverParams*)params)->chan[0]);
183+
}
184+
185+
186+
168187

169188
void _writeDutyCycle2PWM(float dc_a, float dc_b, void* params) {
170189
writeDutyCycle(dc_a, ((RP2040DriverParams*)params)->slice[0], ((RP2040DriverParams*)params)->chan[0]);

src/drivers/hardware_specific/samd51_mcu.cpp

Lines changed: 35 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -14,6 +14,36 @@
1414
#endif
1515

1616

17+
#ifndef TCC3_CH0
18+
#define TCC3_CH0 NOT_ON_TIMER
19+
#define TCC3_CH1 NOT_ON_TIMER
20+
#endif
21+
22+
#ifndef TCC4_CH0
23+
#define TCC4_CH0 NOT_ON_TIMER
24+
#define TCC4_CH1 NOT_ON_TIMER
25+
#endif
26+
27+
28+
#ifndef TC4_CH0
29+
#define TC4_CH0 NOT_ON_TIMER
30+
#define TC4_CH1 NOT_ON_TIMER
31+
#endif
32+
33+
#ifndef TC5_CH0
34+
#define TC5_CH0 NOT_ON_TIMER
35+
#define TC5_CH1 NOT_ON_TIMER
36+
#endif
37+
38+
#ifndef TC6_CH0
39+
#define TC6_CH0 NOT_ON_TIMER
40+
#define TC6_CH1 NOT_ON_TIMER
41+
#endif
42+
43+
#ifndef TC7_CH0
44+
#define TC7_CH0 NOT_ON_TIMER
45+
#define TC7_CH1 NOT_ON_TIMER
46+
#endif
1747

1848

1949

@@ -109,7 +139,12 @@ struct wo_association WO_associations[] = {
109139

110140
wo_association ASSOCIATION_NOT_FOUND = { NOT_A_PORT, 0, NOT_ON_TIMER, 0, NOT_ON_TIMER, 0, NOT_ON_TIMER, 0};
111141

142+
#ifndef TCC3_CC_NUM
143+
uint8_t TCC_CHANNEL_COUNT[] = { TCC0_CC_NUM, TCC1_CC_NUM, TCC2_CC_NUM };
144+
#else
112145
uint8_t TCC_CHANNEL_COUNT[] = { TCC0_CC_NUM, TCC1_CC_NUM, TCC2_CC_NUM, TCC3_CC_NUM, TCC4_CC_NUM };
146+
#endif
147+
113148

114149
struct wo_association& getWOAssociation(EPortType port, uint32_t pin) {
115150
for (int i=0;i<NUM_WO_ASSOCIATIONS;i++) {

src/drivers/hardware_specific/teensy_mcu.cpp

Lines changed: 28 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -12,6 +12,21 @@ void _setHighFrequency(const long freq, const int pin){
1212
}
1313

1414

15+
// function setting the high pwm frequency to the supplied pins
16+
// - Stepper motor - 2PWM setting
17+
// - hardware speciffic
18+
void* _configure1PWM(long pwm_frequency, const int pinA) {
19+
if(!pwm_frequency || !_isset(pwm_frequency) ) pwm_frequency = _PWM_FREQUENCY; // default frequency 25khz
20+
else pwm_frequency = _constrain(pwm_frequency, 0, _PWM_FREQUENCY_MAX); // constrain to 50kHz max
21+
_setHighFrequency(pwm_frequency, pinA);
22+
GenericDriverParams* params = new GenericDriverParams {
23+
.pins = { pinA },
24+
.pwm_frequency = pwm_frequency
25+
};
26+
return params;
27+
}
28+
29+
1530
// function setting the high pwm frequency to the supplied pins
1631
// - Stepper motor - 2PWM setting
1732
// - hardware speciffic
@@ -60,6 +75,17 @@ void* _configure4PWM(long pwm_frequency, const int pinA, const int pinB, const i
6075
return params;
6176
}
6277

78+
79+
80+
// function setting the pwm duty cycle to the hardware
81+
// - Stepper motor - 2PWM setting
82+
// - hardware speciffic
83+
void _writeDutyCycle1PWM(float dc_a, void* params) {
84+
// transform duty cycle from [0,1] to [0,255]
85+
analogWrite(((GenericDriverParams*)params)->pins[0], 255.0f*dc_a);
86+
}
87+
88+
6389
// function setting the pwm duty cycle to the hardware
6490
// - Stepper motor - 2PWM setting
6591
// - hardware speciffic
@@ -68,6 +94,8 @@ void _writeDutyCycle2PWM(float dc_a, float dc_b, void* params) {
6894
analogWrite(((GenericDriverParams*)params)->pins[0], 255.0f*dc_a);
6995
analogWrite(((GenericDriverParams*)params)->pins[1], 255.0f*dc_b);
7096
}
97+
98+
7199
// function setting the pwm duty cycle to the hardware
72100
// - BLDC motor - 3PWM setting
73101
// - hardware speciffic

0 commit comments

Comments
 (0)