Skip to content

Commit

Permalink
adde the center-aligend ledc driver - enables 6pwm
Browse files Browse the repository at this point in the history
  • Loading branch information
askuric committed Jun 7, 2024
1 parent 93bcfe0 commit 8e8ffb2
Show file tree
Hide file tree
Showing 2 changed files with 186 additions and 72 deletions.
16 changes: 8 additions & 8 deletions src/drivers/hardware_specific/esp32/esp32_driver_mcpwm.h
Original file line number Diff line number Diff line change
Expand Up @@ -40,7 +40,7 @@ typedef struct {
int pinA;
mcpwm_dev_t* mcpwm_num;
mcpwm_unit_t mcpwm_unit;
mcpwm_operator_t mcpwm_operator;
mcpwm_operator_t mcpwm_operator;
mcpwm_io_signals_t mcpwm_a;
mcpwm_io_signals_t mcpwm_b;
mcpwm_io_signals_t mcpwm_c;
Expand All @@ -50,8 +50,8 @@ typedef struct {
int pin1A;
mcpwm_dev_t* mcpwm_num;
mcpwm_unit_t mcpwm_unit;
mcpwm_operator_t mcpwm_operator1;
mcpwm_operator_t mcpwm_operator2;
mcpwm_operator_t mcpwm_operator1;
mcpwm_operator_t mcpwm_operator2;
mcpwm_io_signals_t mcpwm_1a;
mcpwm_io_signals_t mcpwm_1b;
mcpwm_io_signals_t mcpwm_2a;
Expand All @@ -62,7 +62,7 @@ typedef struct {
int pin1pwm;
mcpwm_dev_t* mcpwm_num;
mcpwm_unit_t mcpwm_unit;
mcpwm_operator_t mcpwm_operator;
mcpwm_operator_t mcpwm_operator;
mcpwm_io_signals_t mcpwm_a;
mcpwm_io_signals_t mcpwm_b;
} stepper_2pwm_motor_slots_t;
Expand All @@ -71,8 +71,8 @@ typedef struct {
int pinAH;
mcpwm_dev_t* mcpwm_num;
mcpwm_unit_t mcpwm_unit;
mcpwm_operator_t mcpwm_operator1;
mcpwm_operator_t mcpwm_operator2;
mcpwm_operator_t mcpwm_operator1;
mcpwm_operator_t mcpwm_operator2;
mcpwm_io_signals_t mcpwm_ah;
mcpwm_io_signals_t mcpwm_bh;
mcpwm_io_signals_t mcpwm_ch;
Expand All @@ -86,8 +86,8 @@ typedef struct ESP32MCPWMDriverParams {
long pwm_frequency;
mcpwm_dev_t* mcpwm_dev;
mcpwm_unit_t mcpwm_unit;
mcpwm_operator_t mcpwm_operator1;
mcpwm_operator_t mcpwm_operator2;
mcpwm_operator_t mcpwm_operator1;
mcpwm_operator_t mcpwm_operator2;
float deadtime;
} ESP32MCPWMDriverParams;

Expand Down
242 changes: 178 additions & 64 deletions src/drivers/hardware_specific/esp32/esp32_ledc_mcu.cpp
Original file line number Diff line number Diff line change
@@ -1,18 +1,5 @@
#include "../../hardware_api.h"

/*
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.
The pwm is not center aligned and moreover there are no guarantees on the proper alignement between the PWM signals.
Therefore this driver is not recommended for boards that have MCPWM.
There are however ways to improve the LEDC driver, by not using directly espressif sdk:
https://docs.espressif.com/projects/esp-idf/en/stable/esp32/api-reference/peripherals/ledc.html#ledc-api-change-pwm-signal
- 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
- We could force the use of the same ledc timer within one driver to ensure the alignement between the signals
*/

#if defined(ESP_H) && defined(ARDUINO_ARCH_ESP32) && ( !defined(SOC_MCPWM_SUPPORTED) || defined(SIMPLEFOC_ESP32_USELEDC) )

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

#define LEDC_CHANNELS_GROUP0 (LEDC_CHANNELS < 8 ? LEDC_CHANNELS : 8)
#define LEDC_CHANNELS_GROUP1 (LEDC_CHANNELS < 8 ? 0 : LEDC_CHANNELS - 8)


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


typedef struct ESP32LEDCDriverParams {
int pins[6];
ledc_channel_t channels[6];
ledc_mode_t groups[6];
long pwm_frequency;
float dead_zone;
} ESP32LEDCDriverParams;





// configure High PWM frequency
bool _setHighFrequency(const long freq, const int pin){
// sets up the pwm resolution and frequency on this pin
// https://docs.espressif.com/projects/arduino-esp32/en/latest/api/ledc.html
// from v5.x no more need to deal with channels
return ledcAttach(pin, freq, _PWM_RES_BIT);
/*
Function to attach a channel to a pin with advanced settings
- freq - pwm frequency
- resolution - pwm resolution
- channel - ledc channel
- inverted - output inverted
- group - ledc group
This function is a workaround for the ledcAttachPin function that is not available in the ESP32 Arduino core, in which the
PWM signals are synchronized in pairs, while the simplefoc requires a bit more flexible configuration.
This function sets also allows configuring a channel as inverted, which is not possible with the ledcAttachPin function.
Function returns true if the channel was successfully attached, false otherwise.
*/
bool _ledcAttachChannelAdvanced(uint8_t pin, int _channel, int _group, uint32_t freq, uint8_t resolution, bool inverted) {


ledc_channel_t channel = static_cast<ledc_channel_t>(_channel);
ledc_mode_t group = static_cast<ledc_mode_t>(_group);

ledc_timer_bit_t res = static_cast<ledc_timer_bit_t>(resolution);
ledc_timer_config_t ledc_timer;
ledc_timer.speed_mode = group;
ledc_timer.timer_num = LEDC_TIMER_0;
ledc_timer.duty_resolution = res;
ledc_timer.freq_hz = freq;
ledc_timer.clk_cfg = LEDC_AUTO_CLK;
if (ledc_timer_config(&ledc_timer) != ESP_OK) {
return false;
}

// if active high is false invert
int pin_high_level = SIMPLEFOC_PWM_ACTIVE_HIGH ? 1 : 0;
if (inverted) pin_high_level = !pin_high_level;

uint32_t duty = ledc_get_duty(group, channel);
ledc_channel_config_t ledc_channel;
ledc_channel.speed_mode = group;
ledc_channel.channel = channel;
ledc_channel.timer_sel = LEDC_TIMER_0;
ledc_channel.intr_type = LEDC_INTR_DISABLE;
ledc_channel.gpio_num = pin;
ledc_channel.duty = duty;
ledc_channel.hpoint = 0;
ledc_channel.flags.output_invert = pin_high_level;
if (ledc_channel_config(&ledc_channel)!= ESP_OK) {
return false;
}

return true;
}




// returns the number of the group that has enough channels available
// returns -1 if no group has enough channels
//
// NOT IMPLEMENTED BUT COULD BE USEFUL
// returns 2 if no group has enough channels but combined they do
int _findGroupWithChannelsAvailable(int no_channels){
if (group_channels_used[0] + no_channels < LEDC_CHANNELS_GROUP0){
return 0;
}else if (group_channels_used[1] + no_channels < LEDC_CHANNELS_GROUP1){
return 1;
}
// else if (group_channels_used[0] + group_channels_used[1] + no_channels < LEDC_CHANNELS){
// return 2;
// }
return -1;
}


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

SIMPLEFOC_DEBUG("EP32-DRV: Configuring 1PWM");
// check if enough channels available
if ( channels_used + 1 >= LEDC_CHANNELS ) return SIMPLEFOC_DRIVER_INIT_FAILED;
channels_used++;

// setup the channel
if (!_setHighFrequency(pwm_frequency, pinA)) return SIMPLEFOC_DRIVER_INIT_FAILED;
int group = _findGroupWithChannelsAvailable(1);
if (group < 0){
SIMPLEFOC_DEBUG("EP32-DRV: ERROR - Not enough channels available!");
return SIMPLEFOC_DRIVER_INIT_FAILED;
}
SIMPLEFOC_DEBUG("EP32-DRV: 1PWM setup in group: ", (group));

// configure the channel
group_channels_used[group] += 1;
if(!_ledcAttachChannelAdvanced(pinA, group_channels_used[group], group, pwm_frequency, _PWM_RES_BIT, false)) {
SIMPLEFOC_DEBUG("EP32-DRV: ERROR - Failed to attach channel:", group_channels_used[group]);
return SIMPLEFOC_DRIVER_INIT_FAILED;
}

ESP32LEDCDriverParams* params = new ESP32LEDCDriverParams {
.pins = { pinA },
.channels = { static_cast<ledc_channel_t>(group_channels_used[group]) },
.groups = { (ledc_mode_t)group },
.pwm_frequency = pwm_frequency
};
SIMPLEFOC_DEBUG("EP32-DRV: 1PWM setup successful in group: ", (group));
return params;
}

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

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

// setup the channels
if(!_setHighFrequency(pwm_frequency, pinA) || !_setHighFrequency(pwm_frequency, pinB))
// check if enough channels available
int group = _findGroupWithChannelsAvailable(2);
if (group < 0) {
SIMPLEFOC_DEBUG("EP32-DRV: ERROR - Not enough channels available!");
return SIMPLEFOC_DRIVER_INIT_FAILED;
}
SIMPLEFOC_DEBUG("EP32-DRV: 2PWM setup in group: ", (group));

ESP32LEDCDriverParams* params = new ESP32LEDCDriverParams {
.pins = { pinA, pinB },
.channels = { static_cast<ledc_channel_t>(0)},
.groups = { (ledc_mode_t)0 },
.pwm_frequency = pwm_frequency
};

int pins[2] = {pinA, pinB};
for(int i = 0; i < 2; i++){
group_channels_used[group]++;
if(!_ledcAttachChannelAdvanced(pins[i], group_channels_used[group], group, pwm_frequency, _PWM_RES_BIT, false)){
SIMPLEFOC_DEBUG("EP32-DRV: ERROR - Failed to attach channel:", group_channels_used[group]);
return SIMPLEFOC_DRIVER_INIT_FAILED;
}
params->channels[i] = static_cast<ledc_channel_t>(group_channels_used[group]);
params->groups[i] = (ledc_mode_t)group;
}
SIMPLEFOC_DEBUG("EP32-DRV: 2PWM setup successful in group: ", (group));
return params;
}

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

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

// setup the channels
if(!_setHighFrequency(pwm_frequency, pinA) || !_setHighFrequency(pwm_frequency, pinB) || !_setHighFrequency(pwm_frequency, pinC))
// check if enough channels available
int group = _findGroupWithChannelsAvailable(3);
if (group < 0) {
SIMPLEFOC_DEBUG("EP32-DRV: ERROR - Not enough channels available!");
return SIMPLEFOC_DRIVER_INIT_FAILED;
}
SIMPLEFOC_DEBUG("EP32-DRV: 3PWM setup in group: ", (group));

ESP32LEDCDriverParams* params = new ESP32LEDCDriverParams {
.pins = { pinA, pinB, pinC },
.channels = { static_cast<ledc_channel_t>(0)},
.groups = { (ledc_mode_t)0 },
.pwm_frequency = pwm_frequency
};

int pins[3] = {pinA, pinB, pinC};
for(int i = 0; i < 3; i++){
group_channels_used[group]++;
if(!_ledcAttachChannelAdvanced(pins[i], group_channels_used[group], group, pwm_frequency, _PWM_RES_BIT, false)){
SIMPLEFOC_DEBUG("EP32-DRV: ERROR - Failed to attach channel:", group_channels_used[group]);
return SIMPLEFOC_DRIVER_INIT_FAILED;
}
params->channels[i] = static_cast<ledc_channel_t>(group_channels_used[group]);
params->groups[i] = (ledc_mode_t)group;
}
SIMPLEFOC_DEBUG("EP32-DRV: 3PWM setup successful in group: ", (group));
return params;
}

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

SIMPLEFOC_DEBUG("EP32-DRV: Configuring 4PWM");
// check if enough channels available
if ( channels_used + 4 >= LEDC_CHANNELS ) return SIMPLEFOC_DRIVER_INIT_FAILED;
channels_used += 4;

// setup the channels
if(!_setHighFrequency(pwm_frequency, pinA) || !_setHighFrequency(pwm_frequency, pinB) ||
!_setHighFrequency(pwm_frequency, pinC)|| !_setHighFrequency(pwm_frequency, pinD))
int group = _findGroupWithChannelsAvailable(4);
if (group < 0){
SIMPLEFOC_DEBUG("EP32-DRV: ERROR - Not enough channels available!");
return SIMPLEFOC_DRIVER_INIT_FAILED;

}
SIMPLEFOC_DEBUG("EP32-DRV: 4PWM setup in group: ", (group));
ESP32LEDCDriverParams* params = new ESP32LEDCDriverParams {
.pins = { pinA, pinB, pinC, pinD },
.channels = { static_cast<ledc_channel_t>(0)},
.groups = { (ledc_mode_t)0 },
.pwm_frequency = pwm_frequency
};

int pins[4] = {pinA, pinB, pinC, pinD};
for(int i = 0; i < 4; i++){
group_channels_used[group]++;
if(!_ledcAttachChannelAdvanced(pins[i], group_channels_used[group], group, pwm_frequency, _PWM_RES_BIT, false)){
SIMPLEFOC_DEBUG("EP32-DRV: ERROR - Failed to attach channel:", group_channels_used[group]);
return SIMPLEFOC_DRIVER_INIT_FAILED;
}
params->channels[i] = static_cast<ledc_channel_t>(group_channels_used[group]);
params->groups[i] = (ledc_mode_t)group;
}
SIMPLEFOC_DEBUG("EP32-DRV: 4PWM setup successful in group: ", (group));
return params;
}



void _writeDutyCycle(float dc, void* params, int index){
ledc_set_duty_with_hpoint(((ESP32LEDCDriverParams*)params)->groups[index],((ESP32LEDCDriverParams*)params)->channels[index], _PWM_RES*dc, _PWM_RES/2.0*(1.0-dc));
ledc_update_duty(((ESP32LEDCDriverParams*)params)->groups[index],((ESP32LEDCDriverParams*)params)->channels[index]);
}

void _writeDutyCycle1PWM(float dc_a, void* params){
ledcWrite(((ESP32LEDCDriverParams*)params)->pins[0], _constrain(_PWM_RES*dc_a, 0, _PWM_RES));
_writeDutyCycle(dc_a, params, 0);
}



void _writeDutyCycle2PWM(float dc_a, float dc_b, void* params){
ledcWrite(((ESP32LEDCDriverParams*)params)->pins[0], _constrain(_PWM_RES*dc_a, 0, _PWM_RES));
ledcWrite(((ESP32LEDCDriverParams*)params)->pins[1], _constrain(_PWM_RES*dc_b, 0, _PWM_RES));
_writeDutyCycle(dc_a, params, 0);
_writeDutyCycle(dc_b, params, 1);
}



void _writeDutyCycle3PWM(float dc_a, float dc_b, float dc_c, void* params){
ledcWrite(((ESP32LEDCDriverParams*)params)->pins[0], _constrain(_PWM_RES*dc_a, 0, _PWM_RES));
ledcWrite(((ESP32LEDCDriverParams*)params)->pins[1], _constrain(_PWM_RES*dc_b, 0, _PWM_RES));
ledcWrite(((ESP32LEDCDriverParams*)params)->pins[2], _constrain(_PWM_RES*dc_c, 0, _PWM_RES));
_writeDutyCycle(dc_a, params, 0);
_writeDutyCycle(dc_b, params, 1);
_writeDutyCycle(dc_c, params, 2);
}



void _writeDutyCycle4PWM(float dc_1a, float dc_1b, float dc_2a, float dc_2b, void* params){
ledcWrite(((ESP32LEDCDriverParams*)params)->pins[0], _constrain(_PWM_RES*dc_1a, 0, _PWM_RES));
ledcWrite(((ESP32LEDCDriverParams*)params)->pins[1], _constrain(_PWM_RES*dc_1b, 0, _PWM_RES));
ledcWrite(((ESP32LEDCDriverParams*)params)->pins[2], _constrain(_PWM_RES*dc_2a, 0, _PWM_RES));
ledcWrite(((ESP32LEDCDriverParams*)params)->pins[3], _constrain(_PWM_RES*dc_2b, 0, _PWM_RES));
_writeDutyCycle(dc_1a, params, 0);
_writeDutyCycle(dc_1b, params, 1);
_writeDutyCycle(dc_2a, params, 2);
_writeDutyCycle(dc_2b, params, 3);
}


// TODO - implement 6PWM
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){
SIMPLEFOC_DEBUG("EP32-DRV: 6PWM will be implemented soon for LEDC driver!");
return SIMPLEFOC_DRIVER_INIT_FAILED;
}
void _writeDutyCycle6PWM(float dc_a, float dc_b, float dc_c, void* params) {
SIMPLEFOC_DEBUG("EP32-DRV: 6PWM not supported");
}

#endif

0 comments on commit 8e8ffb2

Please sign in to comment.