Skip to content

Commit

Permalink
an initial implementation of the lowside and inline current sense wit…
Browse files Browse the repository at this point in the history
…h the new esp32 api
  • Loading branch information
askuric committed Jun 15, 2024
1 parent e221e06 commit a7ed4ba
Show file tree
Hide file tree
Showing 13 changed files with 128 additions and 112 deletions.
Original file line number Diff line number Diff line change
@@ -1,6 +1,6 @@
#include "esp32_adc_driver.h"

#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) && 0
#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)

#include "freertos/FreeRTOS.h"
#include "freertos/task.h"
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -5,7 +5,7 @@

#include "Arduino.h"

#if defined(ESP_H) && defined(ARDUINO_ARCH_ESP32) && defined(SOC_MCPWM_SUPPORTED) && !defined(SIMPLEFOC_ESP32_USELEDC) && 0
#if defined(ESP_H) && defined(ARDUINO_ARCH_ESP32) && defined(SOC_MCPWM_SUPPORTED) && !defined(SIMPLEFOC_ESP32_USELEDC)
/*
* Get ADC value for pin
* */
Expand Down
162 changes: 66 additions & 96 deletions src/current_sense/hardware_specific/esp32/esp32_mcu.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -2,26 +2,26 @@
#include "../../../drivers/hardware_api.h"
#include "../../../drivers/hardware_specific/esp32/esp32_driver_mcpwm.h"

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

#include "esp32_adc_driver.h"

#include "driver/mcpwm.h"
#include "driver/mcpwm_prelude.h"
#include "soc/mcpwm_reg.h"
#include "soc/mcpwm_struct.h"

#include <soc/sens_reg.h>
#include <soc/sens_struct.h>

#define _ADC_VOLTAGE 3.3f
#define _ADC_RESOLUTION 4095.0f

// set the pin 19 in high during the adc interrupt
// #define SIMPLEFOC_ESP32_INTERRUPT_DEBUG

typedef struct ESP32MCPWMCurrentSenseParams {
int pins[3];
float adc_voltage_conv;
mcpwm_unit_t mcpwm_unit;
int buffer_index;
int adc_buffer[3] = {};
int buffer_index = 0;
int no_adc_channels = 0;
} ESP32MCPWMCurrentSenseParams;


Expand All @@ -36,8 +36,8 @@ float _readADCVoltageInline(const int pinA, const void* cs_params){

// function reading an ADC value and returning the read voltage
void* _configureADCInline(const void* driver_params, const int pinA, const int pinB, const int pinC){
_UNUSED(driver_params);

SIMPLEFOC_DEBUG("ESP32-CS: Configuring ADC inline");
if( _isset(pinA) ) pinMode(pinA, INPUT);
if( _isset(pinB) ) pinMode(pinB, INPUT);
if( _isset(pinC) ) pinMode(pinC, INPUT);
Expand All @@ -51,30 +51,15 @@ void* _configureADCInline(const void* driver_params, const int pinA, const int p
}



/**
* Low side adc reading implementation
*/

static void IRAM_ATTR mcpwm0_isr_handler(void*);
static void IRAM_ATTR mcpwm1_isr_handler(void*);
byte currentState = 1;
// two mcpwm units
// - max 2 motors per mcpwm unit (6 adc channels)
int adc_pins[2][6]={0};
int adc_pin_count[2]={0};
uint32_t adc_buffer[2][6]={0};
int adc_read_index[2]={0};

// function reading an ADC value and returning the read voltage
float _readADCVoltageLowSide(const int pin, const void* cs_params){
mcpwm_unit_t unit = ((ESP32MCPWMCurrentSenseParams*)cs_params)->mcpwm_unit;
int buffer_index = ((ESP32MCPWMCurrentSenseParams*)cs_params)->buffer_index;
float adc_voltage_conv = ((ESP32MCPWMCurrentSenseParams*)cs_params)->adc_voltage_conv;

for(int i=0; i < adc_pin_count[unit]; i++){
if( pin == ((ESP32MCPWMCurrentSenseParams*)cs_params)->pins[i]) // found in the buffer
return adc_buffer[unit][buffer_index + i] * adc_voltage_conv;
ESP32MCPWMCurrentSenseParams* p = (ESP32MCPWMCurrentSenseParams*)cs_params;
int no_channel = 0;
for(int i=0; i < 3; i++){
if(!_isset(p->pins[i])) continue;
if(pin == p->pins[i]) // found in the buffer
return p->adc_buffer[no_channel] * p->adc_voltage_conv;
else no_channel++;
}
// not found
return 0;
Expand All @@ -83,83 +68,68 @@ float _readADCVoltageLowSide(const int pin, const void* cs_params){
// function configuring low-side current sensing
void* _configureADCLowSide(const void* driver_params, const int pinA,const int pinB,const int pinC){

mcpwm_unit_t unit = ((ESP32MCPWMDriverParams*)driver_params)->mcpwm_unit;
int index_start = adc_pin_count[unit];
if( _isset(pinA) ) adc_pins[unit][adc_pin_count[unit]++] = pinA;
if( _isset(pinB) ) adc_pins[unit][adc_pin_count[unit]++] = pinB;
if( _isset(pinC) ) adc_pins[unit][adc_pin_count[unit]++] = pinC;
SIMPLEFOC_DEBUG("ESP32-CS: Configuring ADC low-side");
// check if driver timer is already running
// fail if it is
// the easiest way that I've found to check if timer is running
// is to start it and stop it
ESP32MCPWMDriverParams *p = (ESP32MCPWMDriverParams*)driver_params;
if(mcpwm_timer_start_stop(p->timers[0], MCPWM_TIMER_START_NO_STOP) != ESP_ERR_INVALID_STATE){
// if we get the invalid state error it means that the timer is not enabled
// that means that we can configure it for low-side current sensing
SIMPLEFOC_DEBUG("ESP32-CS: ERR - The timer is already enabled. Cannot be configured for low-side current sensing.");
return SIMPLEFOC_CURRENT_SENSE_INIT_FAILED;
}

if( _isset(pinA) ) pinMode(pinA, INPUT);
if( _isset(pinB) ) pinMode(pinB, INPUT);
if( _isset(pinC) ) pinMode(pinC, INPUT);

ESP32MCPWMCurrentSenseParams* params = new ESP32MCPWMCurrentSenseParams {
.pins = { pinA, pinB, pinC },
.adc_voltage_conv = (_ADC_VOLTAGE)/(_ADC_RESOLUTION),
.mcpwm_unit = unit,
.buffer_index = index_start
};
ESP32MCPWMCurrentSenseParams* params = new ESP32MCPWMCurrentSenseParams{};
int no_adc_channels = 0;
if( _isset(pinA) ){
pinMode(pinA, INPUT);
params->pins[no_adc_channels++] = pinA;
}
if( _isset(pinB) ){
pinMode(pinB, INPUT);
params->pins[no_adc_channels++] = pinB;
}
if( _isset(pinC) ){
pinMode(pinC, INPUT);
params->pins[no_adc_channels++] = pinC;
}

params->adc_voltage_conv = (_ADC_VOLTAGE)/(_ADC_RESOLUTION);
params->no_adc_channels = no_adc_channels;
return params;
}


void _driverSyncLowSide(void* driver_params, void* cs_params){

mcpwm_dev_t* mcpwm_dev = ((ESP32MCPWMDriverParams*)driver_params)->mcpwm_dev;
mcpwm_unit_t mcpwm_unit = ((ESP32MCPWMDriverParams*)driver_params)->mcpwm_unit;

// low-side register enable interrupt
mcpwm_dev->int_ena.timer0_tep_int_ena = true;//A PWM timer 0 TEP event will trigger this interrupt
// high side registers enable interrupt
//mcpwm_dev->int_ena.timer0_tep_int_ena = true;//A PWM timer 0 TEZ event will trigger this interrupt

// register interrupts (mcpwm number, interrupt handler, handler argument = NULL, interrupt signal/flag, return handler = NULL)
if(mcpwm_unit == MCPWM_UNIT_0)
mcpwm_isr_register(mcpwm_unit, mcpwm0_isr_handler, NULL, ESP_INTR_FLAG_IRAM, NULL); //Set ISR Handler
else
mcpwm_isr_register(mcpwm_unit, mcpwm1_isr_handler, NULL, ESP_INTR_FLAG_IRAM, NULL); //Set ISR Handler
}

static void IRAM_ATTR mcpwm0_isr_handler(void*) __attribute__ ((unused));

// Read currents when interrupt is triggered
static void IRAM_ATTR mcpwm0_isr_handler(void*){
// // high side
// uint32_t mcpwm_intr_status = MCPWM0.int_st.timer0_tez_int_st;
#ifdef SIMPLEFOC_ESP32_INTERRUPT_DEBUG
pinMode(19, OUTPUT);
#endif
ESP32MCPWMDriverParams *p = (ESP32MCPWMDriverParams*)driver_params;

// low side
uint32_t mcpwm_intr_status = MCPWM0.int_st.timer0_tep_int_st;
if(mcpwm_intr_status){
adc_buffer[0][adc_read_index[0]] = adcRead(adc_pins[0][adc_read_index[0]]);
adc_read_index[0]++;
if(adc_read_index[0] == adc_pin_count[0]) adc_read_index[0] = 0;
}
// low side
MCPWM0.int_clr.timer0_tep_int_clr = mcpwm_intr_status;
// high side
// MCPWM0.int_clr.timer0_tez_int_clr = mcpwm_intr_status_0;
mcpwm_timer_event_callbacks_t cbs_timer = {
.on_full = [](mcpwm_timer_handle_t tim, const mcpwm_timer_event_data_t* edata, void* user_data){
ESP32MCPWMCurrentSenseParams *p = (ESP32MCPWMCurrentSenseParams*)user_data;
#ifdef SIMPLEFOC_ESP32_INTERRUPT_DEBUG
digitalWrite(19, HIGH);
#endif
// increment buffer index
p->buffer_index = (p->buffer_index + 1) % p->no_adc_channels;
// sample the phase currents one at a time
p->adc_buffer[p->buffer_index] = adcRead(p->pins[p->buffer_index]);
#ifdef SIMPLEFOC_ESP32_INTERRUPT_DEBUG
digitalWrite(19, LOW);
#endif
return true;
}
};
if(mcpwm_timer_register_event_callbacks(p->timers[0], &cbs_timer, cs_params) != ESP_OK){
SIMPLEFOC_DEBUG("ESP32-CS: ERR - Failed to sync ADC and driver");
}
}

static void IRAM_ATTR mcpwm1_isr_handler(void*) __attribute__ ((unused));

// Read currents when interrupt is triggered
static void IRAM_ATTR mcpwm1_isr_handler(void*){
// // high side
// uint32_t mcpwm_intr_status = MCPWM1.int_st.timer0_tez_int_st;

// low side
uint32_t mcpwm_intr_status = MCPWM1.int_st.timer0_tep_int_st;
if(mcpwm_intr_status){
adc_buffer[1][adc_read_index[1]] = adcRead(adc_pins[1][adc_read_index[1]]);
adc_read_index[1]++;
if(adc_read_index[1] == adc_pin_count[1]) adc_read_index[1] = 0;
}
// low side
MCPWM1.int_clr.timer0_tep_int_clr = mcpwm_intr_status;
// high side
// MCPWM1.int_clr.timer0_tez_int_clr = mcpwm_intr_status_0;
}


#endif
Original file line number Diff line number Diff line change
@@ -1,6 +1,6 @@
#include "esp32_adc_driver.h"

#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) && 0
#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)

#include "freertos/FreeRTOS.h"
#include "freertos/task.h"
Expand Down
2 changes: 2 additions & 0 deletions src/drivers/BLDCDriver3PWM.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -20,6 +20,8 @@ BLDCDriver3PWM::BLDCDriver3PWM(int phA, int phB, int phC, int en1, int en2, int

// enable motor driver
void BLDCDriver3PWM::enable(){
// enable hardware if available
_enablePWM(params);
// enable_pin the driver - if enable_pin pin available
if ( _isset(enableA_pin) ) digitalWrite(enableA_pin, enable_active_high);
if ( _isset(enableB_pin) ) digitalWrite(enableB_pin, enable_active_high);
Expand Down
2 changes: 2 additions & 0 deletions src/drivers/BLDCDriver6PWM.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -24,6 +24,8 @@ BLDCDriver6PWM::BLDCDriver6PWM(int phA_h,int phA_l,int phB_h,int phB_l,int phC_h

// enable motor driver
void BLDCDriver6PWM::enable(){
// enable hardware if available
_enablePWM(params);
// enable_pin the driver - if enable_pin pin available
if ( _isset(enable_pin) ) digitalWrite(enable_pin, enable_active_high);
// set phase state enabled
Expand Down
2 changes: 2 additions & 0 deletions src/drivers/StepperDriver2PWM.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -43,6 +43,8 @@ StepperDriver2PWM::StepperDriver2PWM(int _pwm1, int _dir1, int _pwm2, int _dir2,

// enable motor driver
void StepperDriver2PWM::enable(){
// enable hardware if available
_enablePWM(params);
// enable_pin the driver - if enable_pin pin available
if ( _isset(enable_pin1) ) digitalWrite(enable_pin1, HIGH);
if ( _isset(enable_pin2) ) digitalWrite(enable_pin2, HIGH);
Expand Down
2 changes: 2 additions & 0 deletions src/drivers/StepperDriver4PWM.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -20,6 +20,8 @@ StepperDriver4PWM::StepperDriver4PWM(int ph1A,int ph1B,int ph2A,int ph2B,int en1

// enable motor driver
void StepperDriver4PWM::enable(){
// enable hardware if available
_enablePWM(params);
// enable_pin the driver - if enable_pin pin available
if ( _isset(enable_pin1) ) digitalWrite(enable_pin1, HIGH);
if ( _isset(enable_pin2) ) digitalWrite(enable_pin2, HIGH);
Expand Down
11 changes: 11 additions & 0 deletions src/drivers/hardware_api.h
Original file line number Diff line number Diff line change
Expand Up @@ -27,6 +27,7 @@

// flag returned if driver init fails
#define SIMPLEFOC_DRIVER_INIT_FAILED ((void*)-1)
#define SIMPLEFOC_DRIVER_INIT_SUCCESS ((void*)1)

// generic implementation of the hardware specific structure
// containing all the necessary driver parameters
Expand Down Expand Up @@ -173,5 +174,15 @@ void _writeDutyCycle4PWM(float dc_1a, float dc_1b, float dc_2a, float dc_2b, vo
*/
void _writeDutyCycle6PWM(float dc_a, float dc_b, float dc_c, PhaseState *phase_state, void* params);

/**
* Function enabling the PWM outputs
* - hardware specific
*
* @param params the driver parameters
*
* @return the pointer to the driver parameters if successful, -1 if failed
*/
void* _enablePWM(void* params);


#endif
26 changes: 13 additions & 13 deletions src/drivers/hardware_specific/esp32/esp32_driver_mcpwm.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -320,10 +320,6 @@ void* _configure6PWMPinsMCPWM(long pwm_frequency, int mcpwm_group, int timer_no,
_configureCenterAlign(params->generator[2*i+1],params->comparator[2*i+1], SIMPLEFOC_PWM_LOWSIDE_ACTIVE_HIGH);
}
#endif
SIMPLEFOC_ESP32_DEBUG("Enabling the timer: "+String(timer_no));
// Enable and start timer
CHECK_ERR(mcpwm_timer_enable(params->timers[0]), "Failed to enable timer!");
CHECK_ERR(mcpwm_timer_start_stop(params->timers[0], MCPWM_TIMER_START_NO_STOP), "Failed to start the timer!");

_delay(1);
SIMPLEFOC_ESP32_DEBUG("MCPWM configured!");
Expand Down Expand Up @@ -424,12 +420,6 @@ void* _configurePinsMCPWM(long pwm_frequency, int mcpwm_group, int timer_no, int
_configureCenterAlign(params->generator[i],params->comparator[i], !SIMPLEFOC_PWM_ACTIVE_HIGH);
}

SIMPLEFOC_ESP32_DEBUG("Enabling the timer: "+String(timer_no));
// Enable and start timer if not shared
if (!shared_timer) CHECK_ERR(mcpwm_timer_enable(params->timers[0]), "Failed to enable timer!");
// start the timer
CHECK_ERR(mcpwm_timer_start_stop(params->timers[0], MCPWM_TIMER_START_NO_STOP), "Failed to start the timer!");

_delay(1);
SIMPLEFOC_ESP32_DEBUG("MCPWM configured!");
// save the configuration variables for later
Expand All @@ -439,9 +429,19 @@ void* _configurePinsMCPWM(long pwm_frequency, int mcpwm_group, int timer_no, int
}

// function setting the duty cycle to the MCPWM pin
void _setDutyCycle(mcpwm_cmpr_handle_t cmpr, uint32_t mcpwm_period, float duty_cycle){
float duty = constrain(duty_cycle, 0.0, 1.0);
mcpwm_comparator_set_compare_value(cmpr, (uint32_t)(mcpwm_period*duty));
bool _enableTimer(mcpwm_timer_handle_t timer){
int ret = mcpwm_timer_enable(timer); // enable the timer
if (ret == ESP_ERR_INVALID_STATE){ // if already enabled
SIMPLEFOC_ESP32_DEBUG("Timer already enabled: "+String(i));
}else if(ret != ESP_OK){
SIMPLEFOC_ESP32_DEBUG("Failed to enable timer!"); // if failed
return false;
}
if(mcpwm_timer_start_stop(timer, MCPWM_TIMER_START_NO_STOP)!=ESP_OK){
SIMPLEFOC_ESP32_DEBUG("Failed to start the timer!");
return false;
}
}


#endif
8 changes: 8 additions & 0 deletions src/drivers/hardware_specific/esp32/esp32_driver_mcpwm.h
Original file line number Diff line number Diff line change
Expand Up @@ -143,5 +143,13 @@ void* _configurePinsMCPWM(long pwm_frequency, int mcpwm_group, int timer_no, int
*/
void _setDutyCycle(mcpwm_cmpr_handle_t cmpr, uint32_t mcpwm_period, float duty_cycle);

/**
* Function checking if timer is enabled
* @param timer - mcpwm timer handle
*
* @returns true if timer is enabled, false otherwise
*/
bool _enableTimer(mcpwm_timer_handle_t timer);

#endif
#endif
13 changes: 13 additions & 0 deletions src/drivers/hardware_specific/esp32/esp32_mcu.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -218,4 +218,17 @@ void _writeDutyCycle6PWM(float dc_a, float dc_b, float dc_c, PhaseState *phase_
_setDutyCycle(((ESP32MCPWMDriverParams*)params)->comparator[5], period, (phase_state[2] == PHASE_ON || phase_state[2] == PHASE_LO) ? dc_c+dead_zone : 1.0f);
#endif
}

void* _enablePWM(void* params){
SIMPLEFOC_ESP32_DEBUG("Enabling timers.");
ESP32MCPWMDriverParams* p = (ESP32MCPWMDriverParams*)params;
for (int i=0; i<2; i++){
if (p->timers[i] == nullptr) continue; // if only one timer
if(!_enableTimer(p->timers[i])){
return SIMPLEFOC_DRIVER_INIT_FAILED;
}
}
return params;
}

#endif
6 changes: 6 additions & 0 deletions src/drivers/hardware_specific/generic_mcu.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -122,4 +122,10 @@ __attribute__((weak)) void _writeDutyCycle6PWM(float dc_a, float dc_b, float dc
_UNUSED(dc_c);
_UNUSED(phase_state);
_UNUSED(params);
}

// function enabling the power stage
// - hardware specific
__attribute__((weak)) void* _enablePWM(void* params){
return params;
}

0 comments on commit a7ed4ba

Please sign in to comment.