Skip to content

1-PWM support for some MCUs and SAMD21 bug fix for ItsyBitsy M4 #218

New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Merged
merged 6 commits into from
Sep 19, 2022
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
23 changes: 23 additions & 0 deletions src/drivers/hardware_specific/atmega2560_mcu.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -25,6 +25,21 @@ void _pinHighFrequency(const int pin){
}


// function setting the high pwm frequency to the supplied pins
// - Stepper motor - 2PWM setting
// - hardware speciffic
void* _configure1PWM(long pwm_frequency,const int pinA) {
// High PWM frequency
// - always max 32kHz
_pinHighFrequency(pinA);
GenericDriverParams* params = new GenericDriverParams {
.pins = { pinA },
.pwm_frequency = pwm_frequency
};
return params;
}


// function setting the high pwm frequency to the supplied pins
// - Stepper motor - 2PWM setting
// - hardware speciffic
Expand Down Expand Up @@ -56,6 +71,14 @@ void* _configure3PWM(long pwm_frequency,const int pinA, const int pinB, const in
return params;
}

// function setting the pwm duty cycle to the hardware
// - Stepper motor - 2PWM setting
// - hardware speciffic
void _writeDutyCycle1PWM(float dc_a, void* params){
// transform duty cycle from [0,1] to [0,255]
analogWrite(((GenericDriverParams*)params)->pins[0], 255.0f*dc_a);
}

// function setting the pwm duty cycle to the hardware
// - Stepper motor - 2PWM setting
// - hardware speciffic
Expand Down
26 changes: 26 additions & 0 deletions src/drivers/hardware_specific/atmega328_mcu.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -17,6 +17,20 @@ void _pinHighFrequency(const int pin){

}

// function setting the high pwm frequency to the supplied pins
// - Stepper motor - 2PWM setting
// - hardware speciffic
// supports Arudino/ATmega328
void* _configure1PWM(long pwm_frequency,const int pinA) {
// High PWM frequency
// - always max 32kHz
_pinHighFrequency(pinA);
GenericDriverParams* params = new GenericDriverParams {
.pins = { pinA },
.pwm_frequency = pwm_frequency
};
return params;
}
// function setting the high pwm frequency to the supplied pins
// - Stepper motor - 2PWM setting
// - hardware speciffic
Expand Down Expand Up @@ -50,6 +64,18 @@ void* _configure3PWM(long pwm_frequency,const int pinA, const int pinB, const in
return params;
}




// function setting the pwm duty cycle to the hardware
// - Stepper motor - 2PWM setting
// - hardware speciffic
void _writeDutyCycle1PWM(float dc_a, void* params){
// transform duty cycle from [0,1] to [0,255]
analogWrite(((GenericDriverParams*)params)->pins[0], 255.0f*dc_a);
}


// function setting the pwm duty cycle to the hardware
// - Stepper motor - 2PWM setting
// - hardware speciffic
Expand Down
25 changes: 25 additions & 0 deletions src/drivers/hardware_specific/atmega32u4_mcu.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -28,6 +28,20 @@ void _pinHighFrequency(const int pin){
}


// function setting the high pwm frequency to the supplied pins
// - Stepper motor - 2PWM setting
// - hardware speciffic
void* _configure1PWM(long pwm_frequency,const int pinA) {
// High PWM frequency
// - always max 32kHz
_pinHighFrequency(pinA);
GenericDriverParams* params = new GenericDriverParams {
.pins = { pinA },
.pwm_frequency = pwm_frequency
};
return params;
}

// function setting the high pwm frequency to the supplied pins
// - Stepper motor - 2PWM setting
// - hardware speciffic
Expand Down Expand Up @@ -59,6 +73,17 @@ void* _configure3PWM(long pwm_frequency,const int pinA, const int pinB, const in
return params;
}



// function setting the pwm duty cycle to the hardware
// - Stepper motor - 2PWM setting
// - hardware speciffic
void _writeDutyCycle1PWM(float dc_a, void* params){
// transform duty cycle from [0,1] to [0,255]
analogWrite(((GenericDriverParams*)params)->pins[0], 255.0f*dc_a);
}


// function setting the pwm duty cycle to the hardware
// - Stepper motor - 2PWM setting
// - hardware speciffic
Expand Down
33 changes: 33 additions & 0 deletions src/drivers/hardware_specific/esp32_ledc_mcu.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -53,6 +53,33 @@ void _setHighFrequency(const long freq, const int pin, const int channel){






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

// check if enough channels available
if ( channel_index + 1 >= LEDC_CHANNELS ) return SIMPLEFOC_DRIVER_INIT_FAILED;

int ch1 = channel_index++;
_setHighFrequency(pwm_frequency, pinA, ch1);

ESP32LEDCDriverParams* params = new ESP32LEDCDriverParams {
.channels = { ch1 },
.pwm_frequency = pwm_frequency
};
return params;
}








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
Expand Down Expand Up @@ -123,6 +150,12 @@ void* _configure4PWM(long pwm_frequency,const int pinA, const int pinB, const in



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



void _writeDutyCycle2PWM(float dc_a, float dc_b, void* params){
ledcWrite(((ESP32LEDCDriverParams*)params)->channels[0], _constrain(_PWM_RES*dc_a, 0, _PWM_RES));
ledcWrite(((ESP32LEDCDriverParams*)params)->channels[1], _constrain(_PWM_RES*dc_b, 0, _PWM_RES));
Expand Down
23 changes: 23 additions & 0 deletions src/drivers/hardware_specific/esp8266_mcu.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -12,6 +12,22 @@ void _setHighFrequency(const long freq, const int pin){
}


// function setting the high pwm frequency to the supplied pins
// - Stepper motor - 2PWM setting
// - hardware speciffic
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
_setHighFrequency(pwm_frequency, pinA);
GenericDriverParams* params = new GenericDriverParams {
.pins = { pinA },
.pwm_frequency = pwm_frequency
};
return params;
}



// function setting the high pwm frequency to the supplied pins
// - Stepper motor - 2PWM setting
// - hardware speciffic
Expand Down Expand Up @@ -60,6 +76,13 @@ void* _configure4PWM(long pwm_frequency,const int pinA, const int pinB, const in
return params;
}

// function setting the pwm duty cycle to the hardware
// - Stepper motor - 2PWM setting
// - hardware speciffic
void _writeDutyCycle1PWM(float dc_a, void* params){
// transform duty cycle from [0,1] to [0,255]
analogWrite(((GenericDriverParams*)params)->pins[0], 255.0f*dc_a);
}
// function setting the pwm duty cycle to the hardware
// - Stepper motor - 2PWM setting
// - hardware speciffic
Expand Down
19 changes: 19 additions & 0 deletions src/drivers/hardware_specific/rp2040_mcu.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -95,6 +95,19 @@ void syncSlices() {
}



void* _configure1PWM(long pwm_frequency, const int pinA) {
RP2040DriverParams* params = new RP2040DriverParams();
if( !pwm_frequency || !_isset(pwm_frequency) ) pwm_frequency = _PWM_FREQUENCY;
else pwm_frequency = _constrain(pwm_frequency, _PWM_FREQUENCY_MIN, _PWM_FREQUENCY_MAX);
params->pwm_frequency = pwm_frequency;
setupPWM(pinA, pwm_frequency, !SIMPLEFOC_PWM_ACTIVE_HIGH, params, 0);
syncSlices();
return params;
}



void* _configure2PWM(long pwm_frequency, const int pinA, const int pinB) {
RP2040DriverParams* params = new RP2040DriverParams();
if( !pwm_frequency || !_isset(pwm_frequency) ) pwm_frequency = _PWM_FREQUENCY;
Expand Down Expand Up @@ -165,6 +178,12 @@ void writeDutyCycle(float val, uint slice, uint chan) {



void _writeDutyCycle1PWM(float dc_a, void* params) {
writeDutyCycle(dc_a, ((RP2040DriverParams*)params)->slice[0], ((RP2040DriverParams*)params)->chan[0]);
}




void _writeDutyCycle2PWM(float dc_a, float dc_b, void* params) {
writeDutyCycle(dc_a, ((RP2040DriverParams*)params)->slice[0], ((RP2040DriverParams*)params)->chan[0]);
Expand Down
35 changes: 35 additions & 0 deletions src/drivers/hardware_specific/samd51_mcu.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -14,6 +14,36 @@
#endif


#ifndef TCC3_CH0
#define TCC3_CH0 NOT_ON_TIMER
#define TCC3_CH1 NOT_ON_TIMER
#endif

#ifndef TCC4_CH0
#define TCC4_CH0 NOT_ON_TIMER
#define TCC4_CH1 NOT_ON_TIMER
#endif


#ifndef TC4_CH0
#define TC4_CH0 NOT_ON_TIMER
#define TC4_CH1 NOT_ON_TIMER
#endif

#ifndef TC5_CH0
#define TC5_CH0 NOT_ON_TIMER
#define TC5_CH1 NOT_ON_TIMER
#endif

#ifndef TC6_CH0
#define TC6_CH0 NOT_ON_TIMER
#define TC6_CH1 NOT_ON_TIMER
#endif

#ifndef TC7_CH0
#define TC7_CH0 NOT_ON_TIMER
#define TC7_CH1 NOT_ON_TIMER
#endif



Expand Down Expand Up @@ -109,7 +139,12 @@ struct wo_association WO_associations[] = {

wo_association ASSOCIATION_NOT_FOUND = { NOT_A_PORT, 0, NOT_ON_TIMER, 0, NOT_ON_TIMER, 0, NOT_ON_TIMER, 0};

#ifndef TCC3_CC_NUM
uint8_t TCC_CHANNEL_COUNT[] = { TCC0_CC_NUM, TCC1_CC_NUM, TCC2_CC_NUM };
#else
uint8_t TCC_CHANNEL_COUNT[] = { TCC0_CC_NUM, TCC1_CC_NUM, TCC2_CC_NUM, TCC3_CC_NUM, TCC4_CC_NUM };
#endif


struct wo_association& getWOAssociation(EPortType port, uint32_t pin) {
for (int i=0;i<NUM_WO_ASSOCIATIONS;i++) {
Expand Down
28 changes: 28 additions & 0 deletions src/drivers/hardware_specific/teensy_mcu.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -12,6 +12,21 @@ void _setHighFrequency(const long freq, const int pin){
}


// function setting the high pwm frequency to the supplied pins
// - Stepper motor - 2PWM setting
// - hardware speciffic
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
_setHighFrequency(pwm_frequency, pinA);
GenericDriverParams* params = new GenericDriverParams {
.pins = { pinA },
.pwm_frequency = pwm_frequency
};
return params;
}


// function setting the high pwm frequency to the supplied pins
// - Stepper motor - 2PWM setting
// - hardware speciffic
Expand Down Expand Up @@ -60,6 +75,17 @@ void* _configure4PWM(long pwm_frequency, const int pinA, const int pinB, const i
return params;
}



// function setting the pwm duty cycle to the hardware
// - Stepper motor - 2PWM setting
// - hardware speciffic
void _writeDutyCycle1PWM(float dc_a, void* params) {
// transform duty cycle from [0,1] to [0,255]
analogWrite(((GenericDriverParams*)params)->pins[0], 255.0f*dc_a);
}


// function setting the pwm duty cycle to the hardware
// - Stepper motor - 2PWM setting
// - hardware speciffic
Expand All @@ -68,6 +94,8 @@ void _writeDutyCycle2PWM(float dc_a, float dc_b, void* params) {
analogWrite(((GenericDriverParams*)params)->pins[0], 255.0f*dc_a);
analogWrite(((GenericDriverParams*)params)->pins[1], 255.0f*dc_b);
}


// function setting the pwm duty cycle to the hardware
// - BLDC motor - 3PWM setting
// - hardware speciffic
Expand Down