@@ -72,7 +72,7 @@ void _writeDutyCycle3PWM(float dc_a, float dc_b, float dc_c, void* params){
72
72
// function setting the high pwm frequency to the supplied pins
73
73
// - Stepper motor - 4PWM setting
74
74
// - hardware speciffic
75
- // supports Arudino /ATmega328
75
+ // supports Arduino /ATmega328
76
76
void * _configure4PWM (long pwm_frequency,const int pin1A, const int pin1B, const int pin2A, const int pin2B) {
77
77
// High PWM frequency
78
78
// - always max 32kHz
@@ -128,7 +128,7 @@ int _configureComplementaryPair(int pinH, int pinL) {
128
128
}
129
129
130
130
// Configuring PWM frequency, resolution and alignment
131
- // - BLDC driver - 6PWM setting
131
+ // - BLDC driver - setting
132
132
// - hardware specific
133
133
// supports Arudino/ATmega328
134
134
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) {
@@ -140,8 +140,8 @@ void* _configure6PWM(long pwm_frequency, float dead_zone, const int pinA_h, cons
140
140
ret_flag += _configureComplementaryPair (pinC_h, pinC_l);
141
141
if (ret_flag!=0 ) return SIMPLEFOC_DRIVER_INIT_FAILED;
142
142
GenericDriverParams* params = new GenericDriverParams {
143
- .pins = { pinA_h,, pinA_l, pinB_h, pinB_l, pinC_h, pinC_l },
144
- .pwm_frequency = pwm_frequency
143
+ .pins = { pinA_h, pinA_l, pinB_h, pinB_l, pinC_h, pinC_l },
144
+ .pwm_frequency = pwm_frequency,
145
145
.dead_zone = dead_zone
146
146
};
147
147
return params;
0 commit comments