1
1
#include " ../../hardware_api.h"
2
2
3
+ /*
4
+ For the moment the LEDC driver implements the simplest possible way to set the PWM on esp32 while enabling to set the frequency and resolution.
5
+
6
+ The pwm is not center aligned and moreover there are no guarantees on the proper alignement between the PWM signals.
7
+ Therefore this driver is not recommended for boards that have MCPWM.
8
+
9
+ There are however ways to improve the LEDC driver, by not using directly espressif sdk:
10
+ https://docs.espressif.com/projects/esp-idf/en/stable/esp32/api-reference/peripherals/ledc.html#ledc-api-change-pwm-signal
11
+ - We could potentially use the ledc_set_duty_with_hpoint function to set the duty cycle and the high time point to make the signals center-aligned
12
+ - We could force the use of the same ledc timer within one driver to ensure the alignement between the signals
13
+
14
+ */
15
+
3
16
#if defined(ESP_H) && defined(ARDUINO_ARCH_ESP32) && ( !defined(SOC_MCPWM_SUPPORTED) || defined(SIMPLEFOC_ESP32_USELEDC) )
4
17
5
18
#pragma message("")
11
24
#define _PWM_FREQUENCY 25000 // 25khz
12
25
#define _PWM_FREQUENCY_MAX 38000 // 38khz max to be able to have 10 bit pwm resolution
13
26
#define _PWM_RES_BIT 10 // 10 bir resolution
14
- #define _PWM_RES 1023 // 2^10-1 = 1023 -1
27
+ #define _PWM_RES 1023 // 2^10-1 = 1024 -1
15
28
16
29
17
- // empty motor slot
18
- #define _EMPTY_SLOT -20
19
- #define _TAKEN_SLOT -21
20
-
21
- // figure out how many ledc channels are avaible
30
+ // figure out how many ledc channels are available
22
31
// esp32 - 2x8=16
23
32
// esp32s2 - 8
24
33
// esp32c3 - 6
30
39
#endif
31
40
32
41
33
- // current channel stack index
42
+ // currently used ledc channels
34
43
// support for multiple motors
35
44
// esp32 has 16 channels
36
45
// esp32s2 has 8 channels
37
46
// esp32c3 has 6 channels
38
- int channel_index = 0 ;
39
-
40
-
47
+ int channels_used = 0 ;
41
48
42
49
43
50
typedef struct ESP32LEDCDriverParams {
44
- int channels [6 ];
51
+ int pins [6 ];
45
52
long pwm_frequency;
46
53
} ESP32LEDCDriverParams;
47
54
@@ -50,9 +57,11 @@ typedef struct ESP32LEDCDriverParams {
50
57
51
58
52
59
// configure High PWM frequency
53
- void _setHighFrequency (const long freq, const int pin, const int channel){
54
- ledcSetup (channel, freq, _PWM_RES_BIT );
55
- ledcAttachPin (pin, channel);
60
+ bool _setHighFrequency (const long freq, const int pin){
61
+ // sets up the pwm resolution and frequency on this pin
62
+ // https://docs.espressif.com/projects/arduino-esp32/en/latest/api/ledc.html
63
+ // from v5.x no more need to deal with channels
64
+ return ledcAttach (pin, freq, _PWM_RES_BIT);
56
65
}
57
66
58
67
@@ -65,13 +74,14 @@ void* _configure1PWM(long pwm_frequency, const int pinA) {
65
74
else pwm_frequency = _constrain (pwm_frequency, 0 , _PWM_FREQUENCY_MAX); // constrain to 50kHz max
66
75
67
76
// check if enough channels available
68
- if ( channel_index + 1 >= LEDC_CHANNELS ) return SIMPLEFOC_DRIVER_INIT_FAILED;
77
+ if ( channels_used + 1 >= LEDC_CHANNELS ) return SIMPLEFOC_DRIVER_INIT_FAILED;
78
+ channels_used++;
69
79
70
- int ch1 = channel_index++;
71
- _setHighFrequency (pwm_frequency, pinA, ch1) ;
80
+ // setup the channel
81
+ if (! _setHighFrequency (pwm_frequency, pinA)) return SIMPLEFOC_DRIVER_INIT_FAILED ;
72
82
73
83
ESP32LEDCDriverParams* params = new ESP32LEDCDriverParams {
74
- .channels = { ch1 },
84
+ .pins = { pinA },
75
85
.pwm_frequency = pwm_frequency
76
86
};
77
87
return params;
@@ -89,15 +99,15 @@ void* _configure2PWM(long pwm_frequency, const int pinA, const int pinB) {
89
99
else pwm_frequency = _constrain (pwm_frequency, 0 , _PWM_FREQUENCY_MAX); // constrain to 50kHz max
90
100
91
101
// check if enough channels available
92
- if ( channel_index + 2 >= LEDC_CHANNELS ) return SIMPLEFOC_DRIVER_INIT_FAILED;
102
+ if ( channels_used + 2 >= LEDC_CHANNELS ) return SIMPLEFOC_DRIVER_INIT_FAILED;
103
+ channels_used += 2 ;
93
104
94
- int ch1 = channel_index++;
95
- int ch2 = channel_index++;
96
- _setHighFrequency (pwm_frequency, pinA, ch1);
97
- _setHighFrequency (pwm_frequency, pinB, ch2);
105
+ // setup the channels
106
+ if (!_setHighFrequency (pwm_frequency, pinA) || !_setHighFrequency (pwm_frequency, pinB))
107
+ return SIMPLEFOC_DRIVER_INIT_FAILED;
98
108
99
109
ESP32LEDCDriverParams* params = new ESP32LEDCDriverParams {
100
- .channels = { ch1, ch2 },
110
+ .pins = { pinA, pinB },
101
111
.pwm_frequency = pwm_frequency
102
112
};
103
113
return params;
@@ -110,17 +120,15 @@ void* _configure3PWM(long pwm_frequency,const int pinA, const int pinB, const in
110
120
else pwm_frequency = _constrain (pwm_frequency, 0 , _PWM_FREQUENCY_MAX); // constrain to 50kHz max
111
121
112
122
// check if enough channels available
113
- if ( channel_index + 3 >= LEDC_CHANNELS ) return SIMPLEFOC_DRIVER_INIT_FAILED;
123
+ if ( channels_used + 3 >= LEDC_CHANNELS ) return SIMPLEFOC_DRIVER_INIT_FAILED;
124
+ channels_used += 3 ;
114
125
115
- int ch1 = channel_index++;
116
- int ch2 = channel_index++;
117
- int ch3 = channel_index++;
118
- _setHighFrequency (pwm_frequency, pinA, ch1);
119
- _setHighFrequency (pwm_frequency, pinB, ch2);
120
- _setHighFrequency (pwm_frequency, pinC, ch3);
126
+ // setup the channels
127
+ if (!_setHighFrequency (pwm_frequency, pinA) || !_setHighFrequency (pwm_frequency, pinB) || !_setHighFrequency (pwm_frequency, pinC))
128
+ return SIMPLEFOC_DRIVER_INIT_FAILED;
121
129
122
130
ESP32LEDCDriverParams* params = new ESP32LEDCDriverParams {
123
- .channels = { ch1, ch2, ch3 },
131
+ .pins = { pinA, pinB, pinC },
124
132
.pwm_frequency = pwm_frequency
125
133
};
126
134
return params;
@@ -133,19 +141,16 @@ void* _configure4PWM(long pwm_frequency,const int pinA, const int pinB, const in
133
141
else pwm_frequency = _constrain (pwm_frequency, 0 , _PWM_FREQUENCY_MAX); // constrain to 50kHz max
134
142
135
143
// check if enough channels available
136
- if ( channel_index + 4 >= LEDC_CHANNELS ) return SIMPLEFOC_DRIVER_INIT_FAILED;
144
+ if ( channels_used + 4 >= LEDC_CHANNELS ) return SIMPLEFOC_DRIVER_INIT_FAILED;
145
+ channels_used += 4 ;
137
146
138
- int ch1 = channel_index++;
139
- int ch2 = channel_index++;
140
- int ch3 = channel_index++;
141
- int ch4 = channel_index++;
142
- _setHighFrequency (pwm_frequency, pinA, ch1);
143
- _setHighFrequency (pwm_frequency, pinB, ch2);
144
- _setHighFrequency (pwm_frequency, pinC, ch3);
145
- _setHighFrequency (pwm_frequency, pinD, ch4);
147
+ // setup the channels
148
+ if (!_setHighFrequency (pwm_frequency, pinA) || !_setHighFrequency (pwm_frequency, pinB) ||
149
+ !_setHighFrequency (pwm_frequency, pinC)|| !_setHighFrequency (pwm_frequency, pinD))
150
+ return SIMPLEFOC_DRIVER_INIT_FAILED;
146
151
147
152
ESP32LEDCDriverParams* params = new ESP32LEDCDriverParams {
148
- .channels = { ch1, ch2, ch3, ch4 },
153
+ .pins = { pinA, pinB, pinC, pinD },
149
154
.pwm_frequency = pwm_frequency
150
155
};
151
156
return params;
@@ -155,31 +160,31 @@ void* _configure4PWM(long pwm_frequency,const int pinA, const int pinB, const in
155
160
156
161
157
162
void _writeDutyCycle1PWM (float dc_a, void * params){
158
- ledcWrite (((ESP32LEDCDriverParams*)params)->channels [0 ], _constrain (_PWM_RES*dc_a, 0 , _PWM_RES));
163
+ ledcWrite (((ESP32LEDCDriverParams*)params)->pins [0 ], _constrain (_PWM_RES*dc_a, 0 , _PWM_RES));
159
164
}
160
165
161
166
162
167
163
168
void _writeDutyCycle2PWM (float dc_a, float dc_b, void * params){
164
- ledcWrite (((ESP32LEDCDriverParams*)params)->channels [0 ], _constrain (_PWM_RES*dc_a, 0 , _PWM_RES));
165
- ledcWrite (((ESP32LEDCDriverParams*)params)->channels [1 ], _constrain (_PWM_RES*dc_b, 0 , _PWM_RES));
169
+ ledcWrite (((ESP32LEDCDriverParams*)params)->pins [0 ], _constrain (_PWM_RES*dc_a, 0 , _PWM_RES));
170
+ ledcWrite (((ESP32LEDCDriverParams*)params)->pins [1 ], _constrain (_PWM_RES*dc_b, 0 , _PWM_RES));
166
171
}
167
172
168
173
169
174
170
175
void _writeDutyCycle3PWM (float dc_a, float dc_b, float dc_c, void * params){
171
- ledcWrite (((ESP32LEDCDriverParams*)params)->channels [0 ], _constrain (_PWM_RES*dc_a, 0 , _PWM_RES));
172
- ledcWrite (((ESP32LEDCDriverParams*)params)->channels [1 ], _constrain (_PWM_RES*dc_b, 0 , _PWM_RES));
173
- ledcWrite (((ESP32LEDCDriverParams*)params)->channels [2 ], _constrain (_PWM_RES*dc_c, 0 , _PWM_RES));
176
+ ledcWrite (((ESP32LEDCDriverParams*)params)->pins [0 ], _constrain (_PWM_RES*dc_a, 0 , _PWM_RES));
177
+ ledcWrite (((ESP32LEDCDriverParams*)params)->pins [1 ], _constrain (_PWM_RES*dc_b, 0 , _PWM_RES));
178
+ ledcWrite (((ESP32LEDCDriverParams*)params)->pins [2 ], _constrain (_PWM_RES*dc_c, 0 , _PWM_RES));
174
179
}
175
180
176
181
177
182
178
183
void _writeDutyCycle4PWM (float dc_1a, float dc_1b, float dc_2a, float dc_2b, void * params){
179
- ledcWrite (((ESP32LEDCDriverParams*)params)->channels [0 ], _constrain (_PWM_RES*dc_1a, 0 , _PWM_RES));
180
- ledcWrite (((ESP32LEDCDriverParams*)params)->channels [1 ], _constrain (_PWM_RES*dc_1b, 0 , _PWM_RES));
181
- ledcWrite (((ESP32LEDCDriverParams*)params)->channels [2 ], _constrain (_PWM_RES*dc_2a, 0 , _PWM_RES));
182
- ledcWrite (((ESP32LEDCDriverParams*)params)->channels [3 ], _constrain (_PWM_RES*dc_2b, 0 , _PWM_RES));
184
+ ledcWrite (((ESP32LEDCDriverParams*)params)->pins [0 ], _constrain (_PWM_RES*dc_1a, 0 , _PWM_RES));
185
+ ledcWrite (((ESP32LEDCDriverParams*)params)->pins [1 ], _constrain (_PWM_RES*dc_1b, 0 , _PWM_RES));
186
+ ledcWrite (((ESP32LEDCDriverParams*)params)->pins [2 ], _constrain (_PWM_RES*dc_2a, 0 , _PWM_RES));
187
+ ledcWrite (((ESP32LEDCDriverParams*)params)->pins [3 ], _constrain (_PWM_RES*dc_2b, 0 , _PWM_RES));
183
188
}
184
189
185
190
#endif
0 commit comments