Skip to content

Commit 9220ead

Browse files
committed
division by zero issue fix #76 + defines for default pwm freq
1 parent 5e6dc72 commit 9220ead

File tree

2 files changed

+23
-18
lines changed

2 files changed

+23
-18
lines changed

src/drivers/hardware_specific/esp32_mcu.cpp

Lines changed: 14 additions & 12 deletions
Original file line numberDiff line numberDiff line change
@@ -20,6 +20,9 @@
2020
#define _PWM_RES_MIN 1500
2121
// max resolution
2222
#define _PWM_RES_MAX 3000
23+
// pwm frequency
24+
#define _PWM_FREQUENCY 25000 // default
25+
#define _PWM_FREQUENCY_MAX 50000 // mqx
2326

2427
// structure containing motor slot configuration
2528
// this library supports up to 4 motors
@@ -102,9 +105,10 @@ void _configureTimerFrequency(long pwm_frequency, mcpwm_dev_t* mcpwm_num, mcpwm
102105
mcpwm_config_t pwm_config;
103106
pwm_config.counter_mode = MCPWM_UP_DOWN_COUNTER; // Up-down counter (triangle wave)
104107
pwm_config.duty_mode = MCPWM_DUTY_MODE_0; // Active HIGH
108+
pwm_config.frequency = 2*pwm_frequency; // set the desired freq - just a placeholder for now https://github.com/simplefoc/Arduino-FOC/issues/76
105109
mcpwm_init(mcpwm_unit, MCPWM_TIMER_0, &pwm_config); //Configure PWM0A & PWM0B with above settings
106-
mcpwm_init(mcpwm_unit, MCPWM_TIMER_1, &pwm_config); //Configure PWM0A & PWM0B with above settings
107-
mcpwm_init(mcpwm_unit, MCPWM_TIMER_2, &pwm_config); //Configure PWM0A & PWM0B with above settings
110+
mcpwm_init(mcpwm_unit, MCPWM_TIMER_1, &pwm_config); //Configure PWM1A & PWM1B with above settings
111+
mcpwm_init(mcpwm_unit, MCPWM_TIMER_2, &pwm_config); //Configure PWM2A & PWM2B with above settings
108112

109113
if (_isset(dead_zone)){
110114
// dead zone is configured
@@ -149,6 +153,7 @@ void _configureTimerFrequency(long pwm_frequency, mcpwm_dev_t* mcpwm_num, mcpwm
149153
mcpwm_num->timer[1].period.upmethod = 0;
150154
mcpwm_num->timer[2].period.upmethod = 0;
151155
_delay(1);
156+
// _delay(1);
152157
//restart the timers
153158
mcpwm_start(mcpwm_unit, MCPWM_TIMER_0);
154159
mcpwm_start(mcpwm_unit, MCPWM_TIMER_1);
@@ -171,9 +176,8 @@ void _configureTimerFrequency(long pwm_frequency, mcpwm_dev_t* mcpwm_num, mcpwm
171176
// - hardware speciffic
172177
// supports Arudino/ATmega328, STM32 and ESP32
173178
void _configure2PWM(long pwm_frequency,const int pinA, const int pinB) {
174-
175-
if(!pwm_frequency || !_isset(pwm_frequency) ) pwm_frequency = 20000; // default frequency 20khz - centered pwm has twice lower frequency
176-
else pwm_frequency = _constrain(pwm_frequency, 0, 40000); // constrain to 40kHz max - centered pwm has twice lower frequency
179+
if(!pwm_frequency || !_isset(pwm_frequency) ) pwm_frequency = _PWM_FREQUENCY; // default frequency 25hz
180+
else pwm_frequency = _constrain(pwm_frequency, 0, _PWM_FREQUENCY_MAX); // constrain to 40kHz max
177181

178182
stepper_2pwm_motor_slots_t m_slot = {};
179183

@@ -217,9 +221,8 @@ void _configure2PWM(long pwm_frequency,const int pinA, const int pinB) {
217221
// - hardware speciffic
218222
// supports Arudino/ATmega328, STM32 and ESP32
219223
void _configure3PWM(long pwm_frequency,const int pinA, const int pinB, const int pinC) {
220-
221-
if(!pwm_frequency || !_isset(pwm_frequency) ) pwm_frequency = 20000; // default frequency 20khz - centered pwm has twice lower frequency
222-
else pwm_frequency = _constrain(pwm_frequency, 0, 40000); // constrain to 40kHz max - centered pwm has twice lower frequency
224+
if(!pwm_frequency || !_isset(pwm_frequency) ) pwm_frequency = _PWM_FREQUENCY; // default frequency 25hz
225+
else pwm_frequency = _constrain(pwm_frequency, 0, _PWM_FREQUENCY_MAX); // constrain to 40kHz max
223226

224227
bldc_3pwm_motor_slots_t m_slot = {};
225228

@@ -262,9 +265,8 @@ void _configure3PWM(long pwm_frequency,const int pinA, const int pinB, const int
262265
// - Stepper motor - 4PWM setting
263266
// - hardware speciffic
264267
void _configure4PWM(long pwm_frequency,const int pinA, const int pinB, const int pinC, const int pinD) {
265-
266-
if(!pwm_frequency || !_isset(pwm_frequency) ) pwm_frequency = 20000; // default frequency 20khz - centered pwm has twice lower frequency
267-
else pwm_frequency = _constrain(pwm_frequency, 0, 40000); // constrain to 50kHz max - centered pwm has twice lower frequency
268+
if(!pwm_frequency || !_isset(pwm_frequency) ) pwm_frequency = _PWM_FREQUENCY; // default frequency 25hz
269+
else pwm_frequency = _constrain(pwm_frequency, 0, _PWM_FREQUENCY_MAX); // constrain to 40kHz max
268270
stepper_4pwm_motor_slots_t m_slot = {};
269271
// determine which motor are we connecting
270272
// and set the appropriate configuration parameters
@@ -367,7 +369,7 @@ void _writeDutyCycle4PWM(float dc_1a, float dc_1b, float dc_2a, float dc_2b, in
367369
int _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){
368370

369371
if(!pwm_frequency || !_isset(pwm_frequency) ) pwm_frequency = 20000; // default frequency 20khz - centered pwm has twice lower frequency
370-
else pwm_frequency = _constrain(pwm_frequency, 0, 40000); // constrain to 40kHz max - centered pwm has twice lower frequency
372+
else pwm_frequency = _constrain(pwm_frequency, 0, _PWM_FREQUENCY_MAX); // constrain to 40kHz max - centered pwm has twice lower frequency
371373
bldc_6pwm_motor_slots_t m_slot = {};
372374
// determine which motor are we connecting
373375
// and set the appropriate configuration parameters

src/drivers/hardware_specific/teensy_mcu.cpp

Lines changed: 9 additions & 6 deletions
Original file line numberDiff line numberDiff line change
@@ -2,6 +2,9 @@
22

33
#if defined(__arm__) && defined(CORE_TEENSY)
44

5+
#define _PWM_FREQUENCY 25000 // 25khz
6+
#define _PWM_FREQUENCY_MAX 50000 // 50khz
7+
58
// configure High PWM frequency
69
void _setHighFrequency(const long freq, const int pin){
710
analogWrite(pin, 0);
@@ -13,8 +16,8 @@ void _setHighFrequency(const long freq, const int pin){
1316
// - Stepper motor - 2PWM setting
1417
// - hardware speciffic
1518
void _configure2PWM(long pwm_frequency, const int pinA, const int pinB) {
16-
if(!pwm_frequency || !_isset(pwm_frequency) ) pwm_frequency = 50000; // default frequency 50khz
17-
else pwm_frequency = _constrain(pwm_frequency, 0, 50000); // constrain to 50kHz max
19+
if(!pwm_frequency || !_isset(pwm_frequency) ) pwm_frequency = _PWM_FREQUENCY; // default frequency 25khz
20+
else pwm_frequency = _constrain(pwm_frequency, 0, _PWM_FREQUENCY_MAX); // constrain to 50kHz max
1821
_setHighFrequency(pwm_frequency, pinA);
1922
_setHighFrequency(pwm_frequency, pinB);
2023
}
@@ -23,8 +26,8 @@ void _configure2PWM(long pwm_frequency, const int pinA, const int pinB) {
2326
// - BLDC motor - 3PWM setting
2427
// - hardware speciffic
2528
void _configure3PWM(long pwm_frequency,const int pinA, const int pinB, const int pinC) {
26-
if(!pwm_frequency || !_isset(pwm_frequency) ) pwm_frequency = 50000; // default frequency 50khz
27-
else pwm_frequency = _constrain(pwm_frequency, 0, 50000); // constrain to 50kHz max
29+
if(!pwm_frequency || !_isset(pwm_frequency) ) pwm_frequency = _PWM_FREQUENCY; // default frequency 25khz
30+
else pwm_frequency = _constrain(pwm_frequency, 0, _PWM_FREQUENCY_MAX); // constrain to 50kHz max
2831
_setHighFrequency(pwm_frequency, pinA);
2932
_setHighFrequency(pwm_frequency, pinB);
3033
_setHighFrequency(pwm_frequency, pinC);
@@ -34,8 +37,8 @@ void _configure3PWM(long pwm_frequency,const int pinA, const int pinB, const int
3437
// - Stepper motor - 4PWM setting
3538
// - hardware speciffic
3639
void _configure4PWM(long pwm_frequency,const int pinA, const int pinB, const int pinC, const int pinD) {
37-
if(!pwm_frequency || !_isset(pwm_frequency) ) pwm_frequency = 50000; // default frequency 50khz
38-
else pwm_frequency = _constrain(pwm_frequency, 0, 50000); // constrain to 50kHz max
40+
if(!pwm_frequency || !_isset(pwm_frequency) ) pwm_frequency = _PWM_FREQUENCY; // default frequency 25khz
41+
else pwm_frequency = _constrain(pwm_frequency, 0, _PWM_FREQUENCY_MAX); // constrain to 50kHz max
3942
_setHighFrequency(pwm_frequency, pinA);
4043
_setHighFrequency(pwm_frequency, pinB);
4144
_setHighFrequency(pwm_frequency, pinC);

0 commit comments

Comments
 (0)