Skip to content

Commit 8e8ffb2

Browse files
committed
adde the center-aligend ledc driver - enables 6pwm
1 parent 93bcfe0 commit 8e8ffb2

File tree

2 files changed

+186
-72
lines changed

2 files changed

+186
-72
lines changed

src/drivers/hardware_specific/esp32/esp32_driver_mcpwm.h

Lines changed: 8 additions & 8 deletions
Original file line numberDiff line numberDiff line change
@@ -40,7 +40,7 @@ typedef struct {
4040
int pinA;
4141
mcpwm_dev_t* mcpwm_num;
4242
mcpwm_unit_t mcpwm_unit;
43-
mcpwm_operator_t mcpwm_operator;
43+
mcpwm_operator_t mcpwm_operator;
4444
mcpwm_io_signals_t mcpwm_a;
4545
mcpwm_io_signals_t mcpwm_b;
4646
mcpwm_io_signals_t mcpwm_c;
@@ -50,8 +50,8 @@ typedef struct {
5050
int pin1A;
5151
mcpwm_dev_t* mcpwm_num;
5252
mcpwm_unit_t mcpwm_unit;
53-
mcpwm_operator_t mcpwm_operator1;
54-
mcpwm_operator_t mcpwm_operator2;
53+
mcpwm_operator_t mcpwm_operator1;
54+
mcpwm_operator_t mcpwm_operator2;
5555
mcpwm_io_signals_t mcpwm_1a;
5656
mcpwm_io_signals_t mcpwm_1b;
5757
mcpwm_io_signals_t mcpwm_2a;
@@ -62,7 +62,7 @@ typedef struct {
6262
int pin1pwm;
6363
mcpwm_dev_t* mcpwm_num;
6464
mcpwm_unit_t mcpwm_unit;
65-
mcpwm_operator_t mcpwm_operator;
65+
mcpwm_operator_t mcpwm_operator;
6666
mcpwm_io_signals_t mcpwm_a;
6767
mcpwm_io_signals_t mcpwm_b;
6868
} stepper_2pwm_motor_slots_t;
@@ -71,8 +71,8 @@ typedef struct {
7171
int pinAH;
7272
mcpwm_dev_t* mcpwm_num;
7373
mcpwm_unit_t mcpwm_unit;
74-
mcpwm_operator_t mcpwm_operator1;
75-
mcpwm_operator_t mcpwm_operator2;
74+
mcpwm_operator_t mcpwm_operator1;
75+
mcpwm_operator_t mcpwm_operator2;
7676
mcpwm_io_signals_t mcpwm_ah;
7777
mcpwm_io_signals_t mcpwm_bh;
7878
mcpwm_io_signals_t mcpwm_ch;
@@ -86,8 +86,8 @@ typedef struct ESP32MCPWMDriverParams {
8686
long pwm_frequency;
8787
mcpwm_dev_t* mcpwm_dev;
8888
mcpwm_unit_t mcpwm_unit;
89-
mcpwm_operator_t mcpwm_operator1;
90-
mcpwm_operator_t mcpwm_operator2;
89+
mcpwm_operator_t mcpwm_operator1;
90+
mcpwm_operator_t mcpwm_operator2;
9191
float deadtime;
9292
} ESP32MCPWMDriverParams;
9393

Lines changed: 178 additions & 64 deletions
Original file line numberDiff line numberDiff line change
@@ -1,18 +1,5 @@
11
#include "../../hardware_api.h"
22

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-
163
#if defined(ESP_H) && defined(ARDUINO_ARCH_ESP32) && ( !defined(SOC_MCPWM_SUPPORTED) || defined(SIMPLEFOC_ESP32_USELEDC) )
174

185
#pragma message("")
@@ -38,52 +25,124 @@ There are however ways to improve the LEDC driver, by not using directly espress
3825
#define LEDC_CHANNELS (SOC_LEDC_CHANNEL_NUM)
3926
#endif
4027

28+
#define LEDC_CHANNELS_GROUP0 (LEDC_CHANNELS < 8 ? LEDC_CHANNELS : 8)
29+
#define LEDC_CHANNELS_GROUP1 (LEDC_CHANNELS < 8 ? 0 : LEDC_CHANNELS - 8)
30+
4131

4232
// currently used ledc channels
4333
// support for multiple motors
4434
// esp32 has 16 channels
4535
// esp32s2 has 8 channels
4636
// esp32c3 has 6 channels
47-
int channels_used = 0;
37+
// channels from 0-7 are in group 0 and 8-15 in group 1
38+
// - only esp32 as of mid 2024 has the second group, all the s versions don't
39+
int group_channels_used[2] = {0};
4840

4941

5042
typedef struct ESP32LEDCDriverParams {
51-
int pins[6];
43+
ledc_channel_t channels[6];
44+
ledc_mode_t groups[6];
5245
long pwm_frequency;
46+
float dead_zone;
5347
} ESP32LEDCDriverParams;
5448

5549

56-
57-
58-
59-
// configure High PWM frequency
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);
50+
/*
51+
Function to attach a channel to a pin with advanced settings
52+
- freq - pwm frequency
53+
- resolution - pwm resolution
54+
- channel - ledc channel
55+
- inverted - output inverted
56+
- group - ledc group
57+
58+
This function is a workaround for the ledcAttachPin function that is not available in the ESP32 Arduino core, in which the
59+
PWM signals are synchronized in pairs, while the simplefoc requires a bit more flexible configuration.
60+
This function sets also allows configuring a channel as inverted, which is not possible with the ledcAttachPin function.
61+
62+
Function returns true if the channel was successfully attached, false otherwise.
63+
*/
64+
bool _ledcAttachChannelAdvanced(uint8_t pin, int _channel, int _group, uint32_t freq, uint8_t resolution, bool inverted) {
65+
66+
67+
ledc_channel_t channel = static_cast<ledc_channel_t>(_channel);
68+
ledc_mode_t group = static_cast<ledc_mode_t>(_group);
69+
70+
ledc_timer_bit_t res = static_cast<ledc_timer_bit_t>(resolution);
71+
ledc_timer_config_t ledc_timer;
72+
ledc_timer.speed_mode = group;
73+
ledc_timer.timer_num = LEDC_TIMER_0;
74+
ledc_timer.duty_resolution = res;
75+
ledc_timer.freq_hz = freq;
76+
ledc_timer.clk_cfg = LEDC_AUTO_CLK;
77+
if (ledc_timer_config(&ledc_timer) != ESP_OK) {
78+
return false;
79+
}
80+
81+
// if active high is false invert
82+
int pin_high_level = SIMPLEFOC_PWM_ACTIVE_HIGH ? 1 : 0;
83+
if (inverted) pin_high_level = !pin_high_level;
84+
85+
uint32_t duty = ledc_get_duty(group, channel);
86+
ledc_channel_config_t ledc_channel;
87+
ledc_channel.speed_mode = group;
88+
ledc_channel.channel = channel;
89+
ledc_channel.timer_sel = LEDC_TIMER_0;
90+
ledc_channel.intr_type = LEDC_INTR_DISABLE;
91+
ledc_channel.gpio_num = pin;
92+
ledc_channel.duty = duty;
93+
ledc_channel.hpoint = 0;
94+
ledc_channel.flags.output_invert = pin_high_level;
95+
if (ledc_channel_config(&ledc_channel)!= ESP_OK) {
96+
return false;
97+
}
98+
99+
return true;
65100
}
66101

67-
68-
69-
102+
// returns the number of the group that has enough channels available
103+
// returns -1 if no group has enough channels
104+
//
105+
// NOT IMPLEMENTED BUT COULD BE USEFUL
106+
// returns 2 if no group has enough channels but combined they do
107+
int _findGroupWithChannelsAvailable(int no_channels){
108+
if (group_channels_used[0] + no_channels < LEDC_CHANNELS_GROUP0){
109+
return 0;
110+
}else if (group_channels_used[1] + no_channels < LEDC_CHANNELS_GROUP1){
111+
return 1;
112+
}
113+
// else if (group_channels_used[0] + group_channels_used[1] + no_channels < LEDC_CHANNELS){
114+
// return 2;
115+
// }
116+
return -1;
117+
}
70118

71119

72120
void* _configure1PWM(long pwm_frequency, const int pinA) {
73121
if(!pwm_frequency || !_isset(pwm_frequency) ) pwm_frequency = _PWM_FREQUENCY; // default frequency 25khz
74122
else pwm_frequency = _constrain(pwm_frequency, 0, _PWM_FREQUENCY_MAX); // constrain to 50kHz max
75123

124+
SIMPLEFOC_DEBUG("EP32-DRV: Configuring 1PWM");
76125
// check if enough channels available
77-
if ( channels_used + 1 >= LEDC_CHANNELS ) return SIMPLEFOC_DRIVER_INIT_FAILED;
78-
channels_used++;
79-
80-
// setup the channel
81-
if (!_setHighFrequency(pwm_frequency, pinA)) return SIMPLEFOC_DRIVER_INIT_FAILED;
126+
int group = _findGroupWithChannelsAvailable(1);
127+
if (group < 0){
128+
SIMPLEFOC_DEBUG("EP32-DRV: ERROR - Not enough channels available!");
129+
return SIMPLEFOC_DRIVER_INIT_FAILED;
130+
}
131+
SIMPLEFOC_DEBUG("EP32-DRV: 1PWM setup in group: ", (group));
82132

133+
// configure the channel
134+
group_channels_used[group] += 1;
135+
if(!_ledcAttachChannelAdvanced(pinA, group_channels_used[group], group, pwm_frequency, _PWM_RES_BIT, false)) {
136+
SIMPLEFOC_DEBUG("EP32-DRV: ERROR - Failed to attach channel:", group_channels_used[group]);
137+
return SIMPLEFOC_DRIVER_INIT_FAILED;
138+
}
139+
83140
ESP32LEDCDriverParams* params = new ESP32LEDCDriverParams {
84-
.pins = { pinA },
141+
.channels = { static_cast<ledc_channel_t>(group_channels_used[group]) },
142+
.groups = { (ledc_mode_t)group },
85143
.pwm_frequency = pwm_frequency
86144
};
145+
SIMPLEFOC_DEBUG("EP32-DRV: 1PWM setup successful in group: ", (group));
87146
return params;
88147
}
89148

@@ -98,18 +157,33 @@ void* _configure2PWM(long pwm_frequency, const int pinA, const int pinB) {
98157
if(!pwm_frequency || !_isset(pwm_frequency) ) pwm_frequency = _PWM_FREQUENCY; // default frequency 25khz
99158
else pwm_frequency = _constrain(pwm_frequency, 0, _PWM_FREQUENCY_MAX); // constrain to 50kHz max
100159

101-
// check if enough channels available
102-
if ( channels_used + 2 >= LEDC_CHANNELS ) return SIMPLEFOC_DRIVER_INIT_FAILED;
103-
channels_used += 2;
160+
SIMPLEFOC_DEBUG("EP32-DRV: Configuring 2PWM");
104161

105-
// setup the channels
106-
if(!_setHighFrequency(pwm_frequency, pinA) || !_setHighFrequency(pwm_frequency, pinB))
162+
// check if enough channels available
163+
int group = _findGroupWithChannelsAvailable(2);
164+
if (group < 0) {
165+
SIMPLEFOC_DEBUG("EP32-DRV: ERROR - Not enough channels available!");
107166
return SIMPLEFOC_DRIVER_INIT_FAILED;
167+
}
168+
SIMPLEFOC_DEBUG("EP32-DRV: 2PWM setup in group: ", (group));
108169

109170
ESP32LEDCDriverParams* params = new ESP32LEDCDriverParams {
110-
.pins = { pinA, pinB },
171+
.channels = { static_cast<ledc_channel_t>(0)},
172+
.groups = { (ledc_mode_t)0 },
111173
.pwm_frequency = pwm_frequency
112174
};
175+
176+
int pins[2] = {pinA, pinB};
177+
for(int i = 0; i < 2; i++){
178+
group_channels_used[group]++;
179+
if(!_ledcAttachChannelAdvanced(pins[i], group_channels_used[group], group, pwm_frequency, _PWM_RES_BIT, false)){
180+
SIMPLEFOC_DEBUG("EP32-DRV: ERROR - Failed to attach channel:", group_channels_used[group]);
181+
return SIMPLEFOC_DRIVER_INIT_FAILED;
182+
}
183+
params->channels[i] = static_cast<ledc_channel_t>(group_channels_used[group]);
184+
params->groups[i] = (ledc_mode_t)group;
185+
}
186+
SIMPLEFOC_DEBUG("EP32-DRV: 2PWM setup successful in group: ", (group));
113187
return params;
114188
}
115189

@@ -119,18 +193,33 @@ void* _configure3PWM(long pwm_frequency,const int pinA, const int pinB, const in
119193
if(!pwm_frequency || !_isset(pwm_frequency) ) pwm_frequency = _PWM_FREQUENCY; // default frequency 25khz
120194
else pwm_frequency = _constrain(pwm_frequency, 0, _PWM_FREQUENCY_MAX); // constrain to 50kHz max
121195

122-
// check if enough channels available
123-
if ( channels_used + 3 >= LEDC_CHANNELS ) return SIMPLEFOC_DRIVER_INIT_FAILED;
124-
channels_used += 3;
196+
SIMPLEFOC_DEBUG("EP32-DRV: Configuring 3PWM");
125197

126-
// setup the channels
127-
if(!_setHighFrequency(pwm_frequency, pinA) || !_setHighFrequency(pwm_frequency, pinB) || !_setHighFrequency(pwm_frequency, pinC))
198+
// check if enough channels available
199+
int group = _findGroupWithChannelsAvailable(3);
200+
if (group < 0) {
201+
SIMPLEFOC_DEBUG("EP32-DRV: ERROR - Not enough channels available!");
128202
return SIMPLEFOC_DRIVER_INIT_FAILED;
203+
}
204+
SIMPLEFOC_DEBUG("EP32-DRV: 3PWM setup in group: ", (group));
129205

130206
ESP32LEDCDriverParams* params = new ESP32LEDCDriverParams {
131-
.pins = { pinA, pinB, pinC },
207+
.channels = { static_cast<ledc_channel_t>(0)},
208+
.groups = { (ledc_mode_t)0 },
132209
.pwm_frequency = pwm_frequency
133210
};
211+
212+
int pins[3] = {pinA, pinB, pinC};
213+
for(int i = 0; i < 3; i++){
214+
group_channels_used[group]++;
215+
if(!_ledcAttachChannelAdvanced(pins[i], group_channels_used[group], group, pwm_frequency, _PWM_RES_BIT, false)){
216+
SIMPLEFOC_DEBUG("EP32-DRV: ERROR - Failed to attach channel:", group_channels_used[group]);
217+
return SIMPLEFOC_DRIVER_INIT_FAILED;
218+
}
219+
params->channels[i] = static_cast<ledc_channel_t>(group_channels_used[group]);
220+
params->groups[i] = (ledc_mode_t)group;
221+
}
222+
SIMPLEFOC_DEBUG("EP32-DRV: 3PWM setup successful in group: ", (group));
134223
return params;
135224
}
136225

@@ -140,51 +229,76 @@ void* _configure4PWM(long pwm_frequency,const int pinA, const int pinB, const in
140229
if(!pwm_frequency || !_isset(pwm_frequency) ) pwm_frequency = _PWM_FREQUENCY; // default frequency 25khz
141230
else pwm_frequency = _constrain(pwm_frequency, 0, _PWM_FREQUENCY_MAX); // constrain to 50kHz max
142231

232+
SIMPLEFOC_DEBUG("EP32-DRV: Configuring 4PWM");
143233
// check if enough channels available
144-
if ( channels_used + 4 >= LEDC_CHANNELS ) return SIMPLEFOC_DRIVER_INIT_FAILED;
145-
channels_used += 4;
146-
147-
// setup the channels
148-
if(!_setHighFrequency(pwm_frequency, pinA) || !_setHighFrequency(pwm_frequency, pinB) ||
149-
!_setHighFrequency(pwm_frequency, pinC)|| !_setHighFrequency(pwm_frequency, pinD))
234+
int group = _findGroupWithChannelsAvailable(4);
235+
if (group < 0){
236+
SIMPLEFOC_DEBUG("EP32-DRV: ERROR - Not enough channels available!");
150237
return SIMPLEFOC_DRIVER_INIT_FAILED;
151-
238+
}
239+
SIMPLEFOC_DEBUG("EP32-DRV: 4PWM setup in group: ", (group));
152240
ESP32LEDCDriverParams* params = new ESP32LEDCDriverParams {
153-
.pins = { pinA, pinB, pinC, pinD },
241+
.channels = { static_cast<ledc_channel_t>(0)},
242+
.groups = { (ledc_mode_t)0 },
154243
.pwm_frequency = pwm_frequency
155244
};
245+
246+
int pins[4] = {pinA, pinB, pinC, pinD};
247+
for(int i = 0; i < 4; i++){
248+
group_channels_used[group]++;
249+
if(!_ledcAttachChannelAdvanced(pins[i], group_channels_used[group], group, pwm_frequency, _PWM_RES_BIT, false)){
250+
SIMPLEFOC_DEBUG("EP32-DRV: ERROR - Failed to attach channel:", group_channels_used[group]);
251+
return SIMPLEFOC_DRIVER_INIT_FAILED;
252+
}
253+
params->channels[i] = static_cast<ledc_channel_t>(group_channels_used[group]);
254+
params->groups[i] = (ledc_mode_t)group;
255+
}
256+
SIMPLEFOC_DEBUG("EP32-DRV: 4PWM setup successful in group: ", (group));
156257
return params;
157258
}
158259

159260

160-
261+
void _writeDutyCycle(float dc, void* params, int index){
262+
ledc_set_duty_with_hpoint(((ESP32LEDCDriverParams*)params)->groups[index],((ESP32LEDCDriverParams*)params)->channels[index], _PWM_RES*dc, _PWM_RES/2.0*(1.0-dc));
263+
ledc_update_duty(((ESP32LEDCDriverParams*)params)->groups[index],((ESP32LEDCDriverParams*)params)->channels[index]);
264+
}
161265

162266
void _writeDutyCycle1PWM(float dc_a, void* params){
163-
ledcWrite(((ESP32LEDCDriverParams*)params)->pins[0], _constrain(_PWM_RES*dc_a, 0, _PWM_RES));
267+
_writeDutyCycle(dc_a, params, 0);
164268
}
165269

166270

167271

168272
void _writeDutyCycle2PWM(float dc_a, float dc_b, void* params){
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));
273+
_writeDutyCycle(dc_a, params, 0);
274+
_writeDutyCycle(dc_b, params, 1);
171275
}
172276

173277

174278

175279
void _writeDutyCycle3PWM(float dc_a, float dc_b, float dc_c, void* params){
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));
280+
_writeDutyCycle(dc_a, params, 0);
281+
_writeDutyCycle(dc_b, params, 1);
282+
_writeDutyCycle(dc_c, params, 2);
179283
}
180284

181285

182286

183287
void _writeDutyCycle4PWM(float dc_1a, float dc_1b, float dc_2a, float dc_2b, void* params){
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));
288+
_writeDutyCycle(dc_1a, params, 0);
289+
_writeDutyCycle(dc_1b, params, 1);
290+
_writeDutyCycle(dc_2a, params, 2);
291+
_writeDutyCycle(dc_2b, params, 3);
292+
}
293+
294+
295+
// TODO - implement 6PWM
296+
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){
297+
SIMPLEFOC_DEBUG("EP32-DRV: 6PWM will be implemented soon for LEDC driver!");
298+
return SIMPLEFOC_DRIVER_INIT_FAILED;
299+
}
300+
void _writeDutyCycle6PWM(float dc_a, float dc_b, float dc_c, void* params) {
301+
SIMPLEFOC_DEBUG("EP32-DRV: 6PWM not supported");
188302
}
189303

190304
#endif

0 commit comments

Comments
 (0)