Skip to content

Commit 93bcfe0

Browse files
committed
use current sensing only if mpcpwm used and force LEDC for now
1 parent 83b606b commit 93bcfe0

File tree

7 files changed

+63
-57
lines changed

7 files changed

+63
-57
lines changed

src/current_sense/hardware_specific/esp32/esp32_adc_driver.cpp

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -1,6 +1,6 @@
11
#include "esp32_adc_driver.h"
22

3-
#if defined(ESP_H) && defined(ARDUINO_ARCH_ESP32) && defined(SOC_MCPWM_SUPPORTED) && !defined(CONFIG_IDF_TARGET_ESP32S2) && !defined(CONFIG_IDF_TARGET_ESP32S3)
3+
#if defined(ESP_H) && defined(ARDUINO_ARCH_ESP32) && defined(SOC_MCPWM_SUPPORTED) && !defined(CONFIG_IDF_TARGET_ESP32S2) && !defined(CONFIG_IDF_TARGET_ESP32S3) && !defined(SIMPLEFOC_ESP32_USELEDC)
44

55
#include "freertos/FreeRTOS.h"
66
#include "freertos/task.h"

src/current_sense/hardware_specific/esp32/esp32_adc_driver.h

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -5,7 +5,7 @@
55

66
#include "Arduino.h"
77

8-
#if defined(ESP_H) && defined(ARDUINO_ARCH_ESP32) && defined(SOC_MCPWM_SUPPORTED)
8+
#if defined(ESP_H) && defined(ARDUINO_ARCH_ESP32) && defined(SOC_MCPWM_SUPPORTED) && !defined(SIMPLEFOC_ESP32_USELEDC)
99
/*
1010
* Get ADC value for pin
1111
* */

src/current_sense/hardware_specific/esp32/esp32_ledc_mcu.cpp

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -1,7 +1,7 @@
11
#include "../../hardware_api.h"
22
#include "../../../drivers/hardware_api.h"
33

4-
#if defined(ESP_H) && defined(ARDUINO_ARCH_ESP32) && !defined(SOC_MCPWM_SUPPORTED)
4+
#if defined(ESP_H) && defined(ARDUINO_ARCH_ESP32) && (!defined(SOC_MCPWM_SUPPORTED) || defined(SIMPLEFOC_ESP32_USELEDC))
55

66
#include "esp32_adc_driver.h"
77

src/current_sense/hardware_specific/esp32/esp32_mcu.cpp

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -2,7 +2,7 @@
22
#include "../../../drivers/hardware_api.h"
33
#include "../../../drivers/hardware_specific/esp32/esp32_driver_mcpwm.h"
44

5-
#if defined(ESP_H) && defined(ARDUINO_ARCH_ESP32) && defined(SOC_MCPWM_SUPPORTED) && !defined(SIMPLEFOC_ESP32_USELEDC)
5+
#if defined(ESP_H) && defined(ARDUINO_ARCH_ESP32) && defined(SOC_MCPWM_SUPPORTED) && !defined(SIMPLEFOC_ESP32_USELEDC)
66

77
#include "esp32_adc_driver.h"
88

src/current_sense/hardware_specific/esp32/esp32s_adc_driver.cpp

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -1,6 +1,6 @@
11
#include "esp32_adc_driver.h"
22

3-
#if defined(ESP_H) && defined(ARDUINO_ARCH_ESP32) && defined(SOC_MCPWM_SUPPORTED) && (defined(CONFIG_IDF_TARGET_ESP32S2) || defined(CONFIG_IDF_TARGET_ESP32S3))
3+
#if defined(ESP_H) && defined(ARDUINO_ARCH_ESP32) && defined(SOC_MCPWM_SUPPORTED) && (defined(CONFIG_IDF_TARGET_ESP32S2) || defined(CONFIG_IDF_TARGET_ESP32S3)) && !defined(SIMPLEFOC_ESP32_USELEDC)
44

55
#include "freertos/FreeRTOS.h"
66
#include "freertos/task.h"

src/drivers/hardware_api.h

Lines changed: 1 addition & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -27,6 +27,7 @@
2727

2828

2929

30+
#define SIMPLEFOC_ESP32_USELEDC
3031

3132
// flag returned if driver init fails
3233
#define SIMPLEFOC_DRIVER_INIT_FAILED ((void*)-1)
Lines changed: 57 additions & 52 deletions
Original file line numberDiff line numberDiff line change
@@ -1,5 +1,18 @@
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+
316
#if defined(ESP_H) && defined(ARDUINO_ARCH_ESP32) && ( !defined(SOC_MCPWM_SUPPORTED) || defined(SIMPLEFOC_ESP32_USELEDC) )
417

518
#pragma message("")
@@ -11,14 +24,10 @@
1124
#define _PWM_FREQUENCY 25000 // 25khz
1225
#define _PWM_FREQUENCY_MAX 38000 // 38khz max to be able to have 10 bit pwm resolution
1326
#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
1528

1629

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
2231
// esp32 - 2x8=16
2332
// esp32s2 - 8
2433
// esp32c3 - 6
@@ -30,18 +39,16 @@
3039
#endif
3140

3241

33-
// current channel stack index
42+
// currently used ledc channels
3443
// support for multiple motors
3544
// esp32 has 16 channels
3645
// esp32s2 has 8 channels
3746
// esp32c3 has 6 channels
38-
int channel_index = 0;
39-
40-
47+
int channels_used = 0;
4148

4249

4350
typedef struct ESP32LEDCDriverParams {
44-
int channels[6];
51+
int pins[6];
4552
long pwm_frequency;
4653
} ESP32LEDCDriverParams;
4754

@@ -50,9 +57,11 @@ typedef struct ESP32LEDCDriverParams {
5057

5158

5259
// 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);
5665
}
5766

5867

@@ -65,13 +74,14 @@ void* _configure1PWM(long pwm_frequency, const int pinA) {
6574
else pwm_frequency = _constrain(pwm_frequency, 0, _PWM_FREQUENCY_MAX); // constrain to 50kHz max
6675

6776
// 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++;
6979

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;
7282

7383
ESP32LEDCDriverParams* params = new ESP32LEDCDriverParams {
74-
.channels = { ch1 },
84+
.pins = { pinA },
7585
.pwm_frequency = pwm_frequency
7686
};
7787
return params;
@@ -89,15 +99,15 @@ void* _configure2PWM(long pwm_frequency, const int pinA, const int pinB) {
8999
else pwm_frequency = _constrain(pwm_frequency, 0, _PWM_FREQUENCY_MAX); // constrain to 50kHz max
90100

91101
// 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;
93104

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;
98108

99109
ESP32LEDCDriverParams* params = new ESP32LEDCDriverParams {
100-
.channels = { ch1, ch2 },
110+
.pins = { pinA, pinB },
101111
.pwm_frequency = pwm_frequency
102112
};
103113
return params;
@@ -110,17 +120,15 @@ void* _configure3PWM(long pwm_frequency,const int pinA, const int pinB, const in
110120
else pwm_frequency = _constrain(pwm_frequency, 0, _PWM_FREQUENCY_MAX); // constrain to 50kHz max
111121

112122
// 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;
114125

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;
121129

122130
ESP32LEDCDriverParams* params = new ESP32LEDCDriverParams {
123-
.channels = { ch1, ch2, ch3 },
131+
.pins = { pinA, pinB, pinC },
124132
.pwm_frequency = pwm_frequency
125133
};
126134
return params;
@@ -133,19 +141,16 @@ void* _configure4PWM(long pwm_frequency,const int pinA, const int pinB, const in
133141
else pwm_frequency = _constrain(pwm_frequency, 0, _PWM_FREQUENCY_MAX); // constrain to 50kHz max
134142

135143
// 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;
137146

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;
146151

147152
ESP32LEDCDriverParams* params = new ESP32LEDCDriverParams {
148-
.channels = { ch1, ch2, ch3, ch4 },
153+
.pins = { pinA, pinB, pinC, pinD },
149154
.pwm_frequency = pwm_frequency
150155
};
151156
return params;
@@ -155,31 +160,31 @@ void* _configure4PWM(long pwm_frequency,const int pinA, const int pinB, const in
155160

156161

157162
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));
159164
}
160165

161166

162167

163168
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));
166171
}
167172

168173

169174

170175
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));
174179
}
175180

176181

177182

178183
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));
183188
}
184189

185190
#endif

0 commit comments

Comments
 (0)