Skip to content

Commit

Permalink
Merge branch 'dev' of github.com:runger1101001/Arduino-FOC into dev
Browse files Browse the repository at this point in the history
  • Loading branch information
Richard Unger committed Sep 17, 2023
2 parents fb88707 + 132e7b0 commit e543cd2
Show file tree
Hide file tree
Showing 12 changed files with 88 additions and 23 deletions.
4 changes: 3 additions & 1 deletion README.md
Original file line number Diff line number Diff line change
Expand Up @@ -115,7 +115,9 @@ Please do not hesitate to leave an issue if you have problems/advices/suggestion

Pull requests are welcome, but let's first discuss them in [community forum](https://community.simplefoc.com)!

If you'd like to contribute to this porject but you are not very familiar with github, don't worry, let us know either by posting at the community forum , by posting a github issue or at our discord server.
If you'd like to contribute to this project but you are not very familiar with github, don't worry, let us know either by posting at the community forum , by posting a github issue or at our discord server.

If you are familiar, we accept pull requests to the dev branch!

## Arduino code example
This is a simple Arduino code example implementing the velocity control program of a BLDC motor with encoder.
Expand Down
1 change: 1 addition & 0 deletions src/common/foc_utils.h
Original file line number Diff line number Diff line change
Expand Up @@ -12,6 +12,7 @@
#define _sqrt(a) (_sqrtApprox(a))
#define _isset(a) ( (a) != (NOT_SET) )
#define _UNUSED(v) (void) (v)
#define _powtwo(x) (1 << (x))

// utility defines
#define _2_SQRT3 1.15470053838f
Expand Down
2 changes: 2 additions & 0 deletions src/current_sense/GenericCurrentSense.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -62,6 +62,8 @@ int GenericCurrentSense::driverAlign(float voltage){
int exit_flag = 1;
if(skip_align) return exit_flag;

if (!initialized) return 0;

// // set phase A active and phases B and C down
// driver->setPwm(voltage, 0, 0);
// _delay(200);
Expand Down
8 changes: 8 additions & 0 deletions src/current_sense/InlineCurrentSense.cpp
Original file line number Diff line number Diff line change
@@ -1,4 +1,5 @@
#include "InlineCurrentSense.h"
#include "communication/SimpleFOCDebug.h"
// InlineCurrentSensor constructor
// - shunt_resistor - shunt resistor value
// - gain - current-sense op-amp gain
Expand Down Expand Up @@ -93,6 +94,13 @@ int InlineCurrentSense::driverAlign(float voltage){
int exit_flag = 1;
if(skip_align) return exit_flag;

if (driver==nullptr) {
SIMPLEFOC_DEBUG("CUR: No driver linked!");
return 0;
}

if (!initialized) return 0;

if(_isset(pinA)){
// set phase A active and phases B and C down
driver->setPwm(voltage, 0, 0);
Expand Down
11 changes: 10 additions & 1 deletion src/current_sense/LowsideCurrentSense.cpp
Original file line number Diff line number Diff line change
@@ -1,4 +1,5 @@
#include "LowsideCurrentSense.h"
#include "communication/SimpleFOCDebug.h"
// LowsideCurrentSensor constructor
// - shunt_resistor - shunt resistor value
// - gain - current-sense op-amp gain
Expand Down Expand Up @@ -35,6 +36,12 @@ LowsideCurrentSense::LowsideCurrentSense(float _mVpA, int _pinA, int _pinB, int

// Lowside sensor init function
int LowsideCurrentSense::init(){

if (driver==nullptr) {
SIMPLEFOC_DEBUG("CUR: Driver not linked!");
return 0;
}

// configure ADC variables
params = _configureADCLowSide(driver->params,pinA,pinB,pinC);
// if init failed return fail
Expand Down Expand Up @@ -89,10 +96,12 @@ PhaseCurrent_s LowsideCurrentSense::getPhaseCurrents(){
// 3 - success but gains inverted
// 4 - success but pins reconfigured and gains inverted
int LowsideCurrentSense::driverAlign(float voltage){

int exit_flag = 1;
if(skip_align) return exit_flag;

if (!initialized) return 0;

if(_isset(pinA)){
// set phase A active and phases B and C down
driver->setPwm(voltage, 0, 0);
Expand Down
3 changes: 3 additions & 0 deletions src/current_sense/hardware_specific/rp2040/rp2040_mcu.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -25,6 +25,7 @@ float _readADCVoltageInline(const int pinA, const void* cs_params) {
// return readings from the same ADC conversion run. The ADC on RP2040 is anyway in round robin mode :-(
// like this we either have to block interrupts, or of course have the chance of reading across
// new ADC conversions, which probably won't improve the accuracy.
_UNUSED(cs_params);

if (pinA>=26 && pinA<=29 && engine.channelsEnabled[pinA-26]) {
return engine.lastResults.raw[pinA-26]*engine.adc_conv;
Expand All @@ -36,6 +37,8 @@ float _readADCVoltageInline(const int pinA, const void* cs_params) {


void* _configureADCInline(const void *driver_params, const int pinA, const int pinB, const int pinC) {
_UNUSED(driver_params);

if( _isset(pinA) )
engine.addPin(pinA);
if( _isset(pinB) )
Expand Down
1 change: 1 addition & 0 deletions src/drivers/hardware_specific/esp32/esp32_driver_mcpwm.h
Original file line number Diff line number Diff line change
Expand Up @@ -88,6 +88,7 @@ typedef struct ESP32MCPWMDriverParams {
mcpwm_unit_t mcpwm_unit;
mcpwm_operator_t mcpwm_operator1;
mcpwm_operator_t mcpwm_operator2;
float deadtime;
} ESP32MCPWMDriverParams;


Expand Down
64 changes: 50 additions & 14 deletions src/drivers/hardware_specific/esp32/esp32_mcu.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -2,6 +2,10 @@

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

#ifndef SIMPLEFOC_ESP32_HW_DEADTIME
#define SIMPLEFOC_ESP32_HW_DEADTIME true // TODO: Change to false when sw-deadtime & phase_state is approved ready for general use.
#endif

// define bldc motor slots array
bldc_3pwm_motor_slots_t esp32_bldc_3pwm_motor_slots[4] = {
{_EMPTY_SLOT, &MCPWM0, MCPWM_UNIT_0, MCPWM_OPR_A, MCPWM0A, MCPWM1A, MCPWM2A}, // 1st motor will be MCPWM0 channel A
Expand Down Expand Up @@ -41,18 +45,36 @@ void _configureTimerFrequency(long pwm_frequency, mcpwm_dev_t* mcpwm_num, mcpwm

mcpwm_config_t pwm_config;
pwm_config.counter_mode = MCPWM_UP_DOWN_COUNTER; // Up-down counter (triangle wave)
pwm_config.duty_mode = MCPWM_DUTY_MODE_0; // Active HIGH
pwm_config.duty_mode = (_isset(dead_zone) || SIMPLEFOC_PWM_ACTIVE_HIGH == true) ? MCPWM_DUTY_MODE_0 : MCPWM_DUTY_MODE_1; // Normally Active HIGH (MCPWM_DUTY_MODE_0)
pwm_config.frequency = 2*pwm_frequency; // set the desired freq - just a placeholder for now https://github.com/simplefoc/Arduino-FOC/issues/76
mcpwm_init(mcpwm_unit, MCPWM_TIMER_0, &pwm_config); //Configure PWM0A & PWM0B with above settings
mcpwm_init(mcpwm_unit, MCPWM_TIMER_1, &pwm_config); //Configure PWM1A & PWM1B with above settings
mcpwm_init(mcpwm_unit, MCPWM_TIMER_2, &pwm_config); //Configure PWM2A & PWM2B with above settings

if (_isset(dead_zone)){
// dead zone is configured
float dead_time = (float)(_MCPWM_FREQ / (pwm_frequency)) * dead_zone;
mcpwm_deadtime_enable(mcpwm_unit, MCPWM_TIMER_0, MCPWM_ACTIVE_HIGH_COMPLIMENT_MODE, dead_time/2.0, dead_time/2.0);
mcpwm_deadtime_enable(mcpwm_unit, MCPWM_TIMER_1, MCPWM_ACTIVE_HIGH_COMPLIMENT_MODE, dead_time/2.0, dead_time/2.0);
mcpwm_deadtime_enable(mcpwm_unit, MCPWM_TIMER_2, MCPWM_ACTIVE_HIGH_COMPLIMENT_MODE, dead_time/2.0, dead_time/2.0);

// When using hardware deadtime, setting the phase_state parameter is not supported.
#if SIMPLEFOC_ESP32_HW_DEADTIME == true
float dead_time = (float)(_MCPWM_FREQ / (pwm_frequency)) * dead_zone;
mcpwm_deadtime_type_t pwm_mode;
if ((SIMPLEFOC_PWM_HIGHSIDE_ACTIVE_HIGH == true) && (SIMPLEFOC_PWM_LOWSIDE_ACTIVE_HIGH == true)) {pwm_mode = MCPWM_ACTIVE_HIGH_COMPLIMENT_MODE;} // Normal, noninverting driver
else if ((SIMPLEFOC_PWM_HIGHSIDE_ACTIVE_HIGH == true) && (SIMPLEFOC_PWM_LOWSIDE_ACTIVE_HIGH == false)){pwm_mode = MCPWM_ACTIVE_HIGH_MODE;} // Inverted lowside driver
else if ((SIMPLEFOC_PWM_HIGHSIDE_ACTIVE_HIGH == false) && (SIMPLEFOC_PWM_LOWSIDE_ACTIVE_HIGH == true)) {pwm_mode = MCPWM_ACTIVE_LOW_MODE;} // Inverted highside driver
else if ((SIMPLEFOC_PWM_HIGHSIDE_ACTIVE_HIGH == false) && (SIMPLEFOC_PWM_LOWSIDE_ACTIVE_HIGH == false)){pwm_mode = MCPWM_ACTIVE_LOW_COMPLIMENT_MODE;} // Inverted low- & highside driver. Caution: This may short the FETs on reset of the ESP32, as both pins get pulled low!
mcpwm_deadtime_enable(mcpwm_unit, MCPWM_TIMER_0, pwm_mode, dead_time/2.0, dead_time/2.0);
mcpwm_deadtime_enable(mcpwm_unit, MCPWM_TIMER_1, pwm_mode, dead_time/2.0, dead_time/2.0);
mcpwm_deadtime_enable(mcpwm_unit, MCPWM_TIMER_2, pwm_mode, dead_time/2.0, dead_time/2.0);
#else // Software deadtime
for (int i = 0; i < 3; i++){
if (SIMPLEFOC_PWM_HIGHSIDE_ACTIVE_HIGH == true) {mcpwm_set_duty_type(mcpwm_unit, (mcpwm_timer_t) i, MCPWM_GEN_A, MCPWM_DUTY_MODE_0);} // Normal, noninverted highside
else if (SIMPLEFOC_PWM_HIGHSIDE_ACTIVE_HIGH == false) {mcpwm_set_duty_type(mcpwm_unit, (mcpwm_timer_t) i, MCPWM_GEN_A, MCPWM_DUTY_MODE_1);} // Inverted highside driver

if (SIMPLEFOC_PWM_LOWSIDE_ACTIVE_HIGH == true) {mcpwm_set_duty_type(mcpwm_unit, (mcpwm_timer_t) i, MCPWM_GEN_B, MCPWM_DUTY_MODE_1);} // Normal, complementary lowside
else if (SIMPLEFOC_PWM_LOWSIDE_ACTIVE_HIGH == false) {mcpwm_set_duty_type(mcpwm_unit, (mcpwm_timer_t) i, MCPWM_GEN_B, MCPWM_DUTY_MODE_0);} // Inverted lowside driver
}
#endif

}
_delay(100);

Expand Down Expand Up @@ -369,7 +391,10 @@ void* _configure6PWM(long pwm_frequency, float dead_zone, const int pinA_h, cons
ESP32MCPWMDriverParams* params = new ESP32MCPWMDriverParams {
.pwm_frequency = pwm_frequency,
.mcpwm_dev = m_slot.mcpwm_num,
.mcpwm_unit = m_slot.mcpwm_unit
.mcpwm_unit = m_slot.mcpwm_unit,
.mcpwm_operator1 = m_slot.mcpwm_operator1,
.mcpwm_operator2 = m_slot.mcpwm_operator2,
.deadtime = _isset(dead_zone) ? dead_zone : 0
};
return params;
}
Expand All @@ -381,15 +406,26 @@ void* _configure6PWM(long pwm_frequency, float dead_zone, const int pinA_h, cons
// - BLDC driver - 6PWM setting
// - hardware specific
void _writeDutyCycle6PWM(float dc_a, float dc_b, float dc_c, PhaseState *phase_state, void* params){
// se the PWM on the slot timers
// set the PWM on the slot timers
// transform duty cycle from [0,1] to [0,100.0]
mcpwm_set_duty(((ESP32MCPWMDriverParams*)params)->mcpwm_unit, MCPWM_TIMER_0, MCPWM_OPR_A, dc_a*100.0);
mcpwm_set_duty(((ESP32MCPWMDriverParams*)params)->mcpwm_unit, MCPWM_TIMER_0, MCPWM_OPR_B, dc_a*100.0);
mcpwm_set_duty(((ESP32MCPWMDriverParams*)params)->mcpwm_unit, MCPWM_TIMER_1, MCPWM_OPR_A, dc_b*100.0);
mcpwm_set_duty(((ESP32MCPWMDriverParams*)params)->mcpwm_unit, MCPWM_TIMER_1, MCPWM_OPR_B, dc_b*100.0);
mcpwm_set_duty(((ESP32MCPWMDriverParams*)params)->mcpwm_unit, MCPWM_TIMER_2, MCPWM_OPR_A, dc_c*100.0);
mcpwm_set_duty(((ESP32MCPWMDriverParams*)params)->mcpwm_unit, MCPWM_TIMER_2, MCPWM_OPR_B, dc_c*100.0);
_UNUSED(phase_state);
#if SIMPLEFOC_ESP32_HW_DEADTIME == true
// Hardware deadtime does deadtime insertion internally
mcpwm_set_duty(((ESP32MCPWMDriverParams*)params)->mcpwm_unit, MCPWM_TIMER_0, MCPWM_OPR_A, dc_a*100.0f);
mcpwm_set_duty(((ESP32MCPWMDriverParams*)params)->mcpwm_unit, MCPWM_TIMER_0, MCPWM_OPR_B, dc_a*100.0f);
mcpwm_set_duty(((ESP32MCPWMDriverParams*)params)->mcpwm_unit, MCPWM_TIMER_1, MCPWM_OPR_A, dc_b*100.0f);
mcpwm_set_duty(((ESP32MCPWMDriverParams*)params)->mcpwm_unit, MCPWM_TIMER_1, MCPWM_OPR_B, dc_b*100.0f);
mcpwm_set_duty(((ESP32MCPWMDriverParams*)params)->mcpwm_unit, MCPWM_TIMER_2, MCPWM_OPR_A, dc_c*100.0f);
mcpwm_set_duty(((ESP32MCPWMDriverParams*)params)->mcpwm_unit, MCPWM_TIMER_2, MCPWM_OPR_B, dc_c*100.0f);
_UNUSED(phase_state);
#else
float deadtime = 0.5f*((ESP32MCPWMDriverParams*)params)->deadtime;
mcpwm_set_duty(((ESP32MCPWMDriverParams*)params)->mcpwm_unit, MCPWM_TIMER_0, MCPWM_OPR_A, (phase_state[0] == PHASE_ON || phase_state[0] == PHASE_HI) ? _constrain(dc_a-deadtime, 0.0f, 1.0f) * 100.0f : 0);
mcpwm_set_duty(((ESP32MCPWMDriverParams*)params)->mcpwm_unit, MCPWM_TIMER_0, MCPWM_OPR_B, (phase_state[0] == PHASE_ON || phase_state[0] == PHASE_LO) ? _constrain(dc_a+deadtime, 0.0f, 1.0f) * 100.0f : 100.0f);
mcpwm_set_duty(((ESP32MCPWMDriverParams*)params)->mcpwm_unit, MCPWM_TIMER_1, MCPWM_OPR_A, (phase_state[1] == PHASE_ON || phase_state[1] == PHASE_HI) ? _constrain(dc_b-deadtime, 0.0f, 1.0f) * 100.0f : 0);
mcpwm_set_duty(((ESP32MCPWMDriverParams*)params)->mcpwm_unit, MCPWM_TIMER_1, MCPWM_OPR_B, (phase_state[1] == PHASE_ON || phase_state[1] == PHASE_LO) ? _constrain(dc_b+deadtime, 0.0f, 1.0f) * 100.0f : 100.0f);
mcpwm_set_duty(((ESP32MCPWMDriverParams*)params)->mcpwm_unit, MCPWM_TIMER_2, MCPWM_OPR_A, (phase_state[2] == PHASE_ON || phase_state[2] == PHASE_HI) ? _constrain(dc_c-deadtime, 0.0f, 1.0f) * 100.0f : 0);
mcpwm_set_duty(((ESP32MCPWMDriverParams*)params)->mcpwm_unit, MCPWM_TIMER_2, MCPWM_OPR_B, (phase_state[2] == PHASE_ON || phase_state[2] == PHASE_LO) ? _constrain(dc_c+deadtime, 0.0f, 1.0f) * 100.0f : 100.0f);
#endif
}

#endif
6 changes: 3 additions & 3 deletions src/sensors/MagneticSensorI2C.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -28,7 +28,7 @@ MagneticSensorI2C::MagneticSensorI2C(uint8_t _chip_address, int _bit_resolution,
// angle read register of the magnetic sensor
angle_register_msb = _angle_register_msb;
// register maximum value (counts per revolution)
cpr = pow(2, _bit_resolution);
cpr = _powtwo(_bit_resolution);

// depending on the sensor architecture there are different combinations of
// LSB and MSB register used bits
Expand All @@ -48,7 +48,7 @@ MagneticSensorI2C::MagneticSensorI2C(MagneticSensorI2CConfig_s config){
// angle read register of the magnetic sensor
angle_register_msb = config.angle_register;
// register maximum value (counts per revolution)
cpr = pow(2, config.bit_resolution);
cpr = _powtwo(config.bit_resolution);

int bits_used_msb = config.data_start_bit - 7;
lsb_used = config.bit_resolution - bits_used_msb;
Expand Down Expand Up @@ -95,7 +95,7 @@ int MagneticSensorI2C::read(uint8_t angle_reg_msb) {
// notify the device that is aboout to be read
wire->beginTransmission(chip_address);
wire->write(angle_reg_msb);
wire->endTransmission(false);
currWireError = wire->endTransmission(false);

// read the data msb and lsb
wire->requestFrom(chip_address, (uint8_t)2);
Expand Down
3 changes: 3 additions & 0 deletions src/sensors/MagneticSensorI2C.h
Original file line number Diff line number Diff line change
Expand Up @@ -51,6 +51,9 @@ class MagneticSensorI2C: public Sensor{
/** experimental function to check and fix SDA locked LOW issues */
int checkBus(byte sda_pin , byte scl_pin );

/** current error code from Wire endTransmission() call **/
uint8_t currWireError = 0;

private:
float cpr; //!< Maximum range of the magnetic sensor
uint16_t lsb_used; //!< Number of bits used in LSB register
Expand Down
6 changes: 3 additions & 3 deletions src/sensors/MagneticSensorSPI.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -31,13 +31,13 @@ MagneticSensorSPIConfig_s MA730_SPI = {
// cs - SPI chip select pin
// _bit_resolution sensor resolution bit number
// _angle_register - (optional) angle read register - default 0x3FFF
MagneticSensorSPI::MagneticSensorSPI(int cs, float _bit_resolution, int _angle_register){
MagneticSensorSPI::MagneticSensorSPI(int cs, int _bit_resolution, int _angle_register){

chip_select_pin = cs;
// angle read register of the magnetic sensor
angle_register = _angle_register ? _angle_register : DEF_ANGLE_REGISTER;
// register maximum value (counts per revolution)
cpr = pow(2,_bit_resolution);
cpr = _powtwo(_bit_resolution);
spi_mode = SPI_MODE1;
clock_speed = 1000000;
bit_resolution = _bit_resolution;
Expand All @@ -52,7 +52,7 @@ MagneticSensorSPI::MagneticSensorSPI(MagneticSensorSPIConfig_s config, int cs){
// angle read register of the magnetic sensor
angle_register = config.angle_register ? config.angle_register : DEF_ANGLE_REGISTER;
// register maximum value (counts per revolution)
cpr = pow(2, config.bit_resolution);
cpr = _powtwo(config.bit_resolution);
spi_mode = config.spi_mode;
clock_speed = config.clock_speed;
bit_resolution = config.bit_resolution;
Expand Down
2 changes: 1 addition & 1 deletion src/sensors/MagneticSensorSPI.h
Original file line number Diff line number Diff line change
Expand Up @@ -30,7 +30,7 @@ class MagneticSensorSPI: public Sensor{
* @param bit_resolution sensor resolution bit number
* @param angle_register (optional) angle read register - default 0x3FFF
*/
MagneticSensorSPI(int cs, float bit_resolution, int angle_register = 0);
MagneticSensorSPI(int cs, int bit_resolution, int angle_register = 0);
/**
* MagneticSensorSPI class constructor
* @param config SPI config
Expand Down

0 comments on commit e543cd2

Please sign in to comment.