14
14
#define _ERROR_6PWM -1
15
15
16
16
17
+
18
+ typedef struct STM32DriverParams {
19
+ HardwareTimer* timers[6 ];
20
+ uint32_t channels[6 ];
21
+ long pwm_frequency;
22
+ float dead_zone;
23
+ uint8_t interface_type;
24
+ } STM32DriverParams;
25
+
26
+
27
+
28
+
29
+
17
30
// setting pwm to hardware pin - instead analogWrite()
18
- void _setPwm (int ulPin , uint32_t value, int resolution)
31
+ void _setPwm (HardwareTimer *HT, uint32_t channel , uint32_t value, int resolution)
19
32
{
20
- PinName pin = digitalPinToPinName (ulPin);
21
- TIM_TypeDef *Instance = (TIM_TypeDef *)pinmap_peripheral (pin, PinMap_PWM);
22
- uint32_t index = get_timer_index (Instance);
23
- HardwareTimer *HT = (HardwareTimer *)(HardwareTimer_Handle[index]->__this );
33
+ // PinName pin = digitalPinToPinName(ulPin);
34
+ // TIM_TypeDef *Instance = (TIM_TypeDef *)pinmap_peripheral(pin, PinMap_PWM);
35
+ // uint32_t index = get_timer_index(Instance);
36
+ // HardwareTimer *HT = (HardwareTimer *)(HardwareTimer_Handle[index]->__this);
24
37
25
- uint32_t channel = STM_PIN_CHANNEL (pinmap_function (pin, PinMap_PWM));
38
+ // uint32_t channel = STM_PIN_CHANNEL(pinmap_function(pin, PinMap_PWM));
26
39
HT->setCaptureCompare (channel, value, (TimerCompareFormat_t)resolution);
27
40
}
28
41
@@ -129,7 +142,7 @@ void _alignPWMTimers(HardwareTimer *HT1,HardwareTimer *HT2,HardwareTimer *HT3,Ha
129
142
}
130
143
131
144
// configure hardware 6pwm interface only one timer with inverted channels
132
- HardwareTimer * _initHardware6PWMInterface (uint32_t PWM_freq, float dead_zone, int pinA_h, int pinA_l, int pinB_h, int pinB_l, int pinC_h, int pinC_l)
145
+ STM32DriverParams * _initHardware6PWMInterface (uint32_t PWM_freq, float dead_zone, int pinA_h, int pinA_l, int pinB_h, int pinB_l, int pinC_h, int pinC_l)
133
146
{
134
147
135
148
#if !defined(STM32L0xx) // L0 boards dont have hardware 6pwm interface
@@ -139,6 +152,12 @@ HardwareTimer* _initHardware6PWMInterface(uint32_t PWM_freq, float dead_zone, in
139
152
PinName vlPinName = digitalPinToPinName (pinB_l);
140
153
PinName whPinName = digitalPinToPinName (pinC_h);
141
154
PinName wlPinName = digitalPinToPinName (pinC_l);
155
+ uint32_t channel1 = STM_PIN_CHANNEL (pinmap_function (uhPinName, PinMap_PWM));
156
+ uint32_t channel2 = STM_PIN_CHANNEL (pinmap_function (ulPinName, PinMap_PWM));
157
+ uint32_t channel3 = STM_PIN_CHANNEL (pinmap_function (vhPinName, PinMap_PWM));
158
+ uint32_t channel4 = STM_PIN_CHANNEL (pinmap_function (vlPinName, PinMap_PWM));
159
+ uint32_t channel5 = STM_PIN_CHANNEL (pinmap_function (whPinName, PinMap_PWM));
160
+ uint32_t channel6 = STM_PIN_CHANNEL (pinmap_function (wlPinName, PinMap_PWM));
142
161
143
162
TIM_TypeDef *Instance = (TIM_TypeDef *)pinmap_peripheral (uhPinName, PinMap_PWM);
144
163
@@ -153,12 +172,12 @@ HardwareTimer* _initHardware6PWMInterface(uint32_t PWM_freq, float dead_zone, in
153
172
}
154
173
HardwareTimer *HT = (HardwareTimer *)(HardwareTimer_Handle[index]->__this );
155
174
156
- HT->setMode (STM_PIN_CHANNEL ( pinmap_function (uhPinName, PinMap_PWM)) , TIMER_OUTPUT_COMPARE_PWM1, uhPinName);
157
- HT->setMode (STM_PIN_CHANNEL ( pinmap_function (ulPinName, PinMap_PWM)) , TIMER_OUTPUT_COMPARE_PWM1, ulPinName);
158
- HT->setMode (STM_PIN_CHANNEL ( pinmap_function (vhPinName, PinMap_PWM)) , TIMER_OUTPUT_COMPARE_PWM1, vhPinName);
159
- HT->setMode (STM_PIN_CHANNEL ( pinmap_function (vlPinName, PinMap_PWM)) , TIMER_OUTPUT_COMPARE_PWM1, vlPinName);
160
- HT->setMode (STM_PIN_CHANNEL ( pinmap_function (whPinName, PinMap_PWM)) , TIMER_OUTPUT_COMPARE_PWM1, whPinName);
161
- HT->setMode (STM_PIN_CHANNEL ( pinmap_function (wlPinName, PinMap_PWM)) , TIMER_OUTPUT_COMPARE_PWM1, wlPinName);
175
+ HT->setMode (channel1 , TIMER_OUTPUT_COMPARE_PWM1, uhPinName);
176
+ HT->setMode (channel2 , TIMER_OUTPUT_COMPARE_PWM1, ulPinName);
177
+ HT->setMode (channel3 , TIMER_OUTPUT_COMPARE_PWM1, vhPinName);
178
+ HT->setMode (channel4 , TIMER_OUTPUT_COMPARE_PWM1, vlPinName);
179
+ HT->setMode (channel5 , TIMER_OUTPUT_COMPARE_PWM1, whPinName);
180
+ HT->setMode (channel6 , TIMER_OUTPUT_COMPARE_PWM1, wlPinName);
162
181
163
182
// dead time is set in nanoseconds
164
183
uint32_t dead_time_ns = (float )(1e9f/PWM_freq)*dead_zone;
@@ -177,9 +196,18 @@ HardwareTimer* _initHardware6PWMInterface(uint32_t PWM_freq, float dead_zone, in
177
196
HT->getHandle ()->Instance ->CNT = TIM1->ARR ;
178
197
179
198
HT->resume ();
180
- return HT;
199
+
200
+ STM32DriverParams* params = new STM32DriverParams {
201
+ .timers = { HT },
202
+ .channels = { channel1, channel3, channel5 },
203
+ .pwm_frequency = PWM_freq,
204
+ .dead_zone = dead_zone,
205
+ .interface_type = _HARDWARE_6PWM
206
+ };
207
+
208
+ return params;
181
209
#else
182
- return nullptr ; // return nothing
210
+ return SIMPLEFOC_DRIVER_INIT_FAILED ; // return nothing
183
211
#endif
184
212
}
185
213
@@ -223,7 +251,7 @@ int _interfaceType(const int pinA_h, const int pinA_l, const int pinB_h, const
223
251
// function setting the high pwm frequency to the supplied pins
224
252
// - Stepper motor - 2PWM setting
225
253
// - hardware speciffic
226
- void _configure2PWM (long pwm_frequency,const int pinA, const int pinB) {
254
+ void * _configure2PWM (long pwm_frequency,const int pinA, const int pinB) {
227
255
if ( !pwm_frequency || !_isset (pwm_frequency) ) pwm_frequency = _PWM_FREQUENCY; // default frequency 25khz
228
256
else pwm_frequency = _constrain (pwm_frequency, 0 , _PWM_FREQUENCY_MAX); // constrain to 50kHz max
229
257
// center-aligned frequency is uses two periods
@@ -233,13 +261,24 @@ void _configure2PWM(long pwm_frequency,const int pinA, const int pinB) {
233
261
HardwareTimer* HT2 = _initPinPWM (pwm_frequency, pinB);
234
262
// allign the timers
235
263
_alignPWMTimers (HT1, HT2, HT2);
264
+
265
+ uint32_t channel1 = STM_PIN_CHANNEL (pinmap_function (digitalPinToPinName (pinA), PinMap_PWM));
266
+ uint32_t channel2 = STM_PIN_CHANNEL (pinmap_function (digitalPinToPinName (pinB), PinMap_PWM));
267
+
268
+ STM32DriverParams* params = new STM32DriverParams {
269
+ .timers = { HT1, HT2 },
270
+ .channels = { channel1, channel2 },
271
+ .pwm_frequency = pwm_frequency
272
+ };
273
+ return params;
236
274
}
237
275
238
276
277
+
239
278
// function setting the high pwm frequency to the supplied pins
240
279
// - BLDC motor - 3PWM setting
241
280
// - hardware speciffic
242
- void _configure3PWM (long pwm_frequency,const int pinA, const int pinB, const int pinC) {
281
+ void * _configure3PWM (long pwm_frequency,const int pinA, const int pinB, const int pinC) {
243
282
if ( !pwm_frequency || !_isset (pwm_frequency) ) pwm_frequency = _PWM_FREQUENCY; // default frequency 25khz
244
283
else pwm_frequency = _constrain (pwm_frequency, 0 , _PWM_FREQUENCY_MAX); // constrain to 50kHz max
245
284
// center-aligned frequency is uses two periods
@@ -250,12 +289,25 @@ void _configure3PWM(long pwm_frequency,const int pinA, const int pinB, const int
250
289
HardwareTimer* HT3 = _initPinPWM (pwm_frequency, pinC);
251
290
// allign the timers
252
291
_alignPWMTimers (HT1, HT2, HT3);
292
+
293
+ uint32_t channel1 = STM_PIN_CHANNEL (pinmap_function (digitalPinToPinName (pinA), PinMap_PWM));
294
+ uint32_t channel2 = STM_PIN_CHANNEL (pinmap_function (digitalPinToPinName (pinB), PinMap_PWM));
295
+ uint32_t channel3 = STM_PIN_CHANNEL (pinmap_function (digitalPinToPinName (pinC), PinMap_PWM));
296
+
297
+ STM32DriverParams* params = new STM32DriverParams {
298
+ .timers = { HT1, HT2, HT3 },
299
+ .channels = { channel1, channel2, channel3 },
300
+ .pwm_frequency = pwm_frequency
301
+ };
302
+ return params;
253
303
}
254
304
305
+
306
+
255
307
// function setting the high pwm frequency to the supplied pins
256
308
// - Stepper motor - 4PWM setting
257
309
// - hardware speciffic
258
- void _configure4PWM (long pwm_frequency,const int pinA, const int pinB, const int pinC, const int pinD) {
310
+ void * _configure4PWM (long pwm_frequency,const int pinA, const int pinB, const int pinC, const int pinD) {
259
311
if ( !pwm_frequency || !_isset (pwm_frequency) ) pwm_frequency = _PWM_FREQUENCY; // default frequency 25khz
260
312
else pwm_frequency = _constrain (pwm_frequency, 0 , _PWM_FREQUENCY_MAX); // constrain to 50kHz max
261
313
// center-aligned frequency is uses two periods
@@ -267,37 +319,51 @@ void _configure4PWM(long pwm_frequency,const int pinA, const int pinB, const int
267
319
HardwareTimer* HT4 = _initPinPWM (pwm_frequency, pinD);
268
320
// allign the timers
269
321
_alignPWMTimers (HT1, HT2, HT3, HT4);
322
+
323
+ uint32_t channel1 = STM_PIN_CHANNEL (pinmap_function (digitalPinToPinName (pinA), PinMap_PWM));
324
+ uint32_t channel2 = STM_PIN_CHANNEL (pinmap_function (digitalPinToPinName (pinB), PinMap_PWM));
325
+ uint32_t channel3 = STM_PIN_CHANNEL (pinmap_function (digitalPinToPinName (pinC), PinMap_PWM));
326
+ uint32_t channel4 = STM_PIN_CHANNEL (pinmap_function (digitalPinToPinName (pinD), PinMap_PWM));
327
+
328
+ STM32DriverParams* params = new STM32DriverParams {
329
+ .timers = { HT1, HT2, HT3, HT4 },
330
+ .channels = { channel1, channel2, channel3, channel4 },
331
+ .pwm_frequency = pwm_frequency
332
+ };
333
+ return params;
270
334
}
271
335
336
+
337
+
272
338
// function setting the pwm duty cycle to the hardware
273
339
// - Stepper motor - 2PWM setting
274
340
// - hardware speciffic
275
- void _writeDutyCycle2PWM (float dc_a, float dc_b, int pinA, int pinB ){
341
+ void _writeDutyCycle2PWM (float dc_a, float dc_b, void * params ){
276
342
// transform duty cycle from [0,1] to [0,4095]
277
- _setPwm (pinA , _PWM_RANGE*dc_a, _PWM_RESOLUTION);
278
- _setPwm (pinB , _PWM_RANGE*dc_b, _PWM_RESOLUTION);
343
+ _setPwm (((STM32DriverParams*)params)-> timers [ 0 ], ((STM32DriverParams*)params)-> channels [ 0 ] , _PWM_RANGE*dc_a, _PWM_RESOLUTION);
344
+ _setPwm (((STM32DriverParams*)params)-> timers [ 1 ], ((STM32DriverParams*)params)-> channels [ 1 ] , _PWM_RANGE*dc_b, _PWM_RESOLUTION);
279
345
}
280
346
281
347
// function setting the pwm duty cycle to the hardware
282
348
// - BLDC motor - 3PWM setting
283
349
// - hardware speciffic
284
- void _writeDutyCycle3PWM (float dc_a, float dc_b, float dc_c, int pinA, int pinB, int pinC ){
350
+ void _writeDutyCycle3PWM (float dc_a, float dc_b, float dc_c, void * params ){
285
351
// transform duty cycle from [0,1] to [0,4095]
286
- _setPwm (pinA , _PWM_RANGE*dc_a, _PWM_RESOLUTION);
287
- _setPwm (pinB , _PWM_RANGE*dc_b, _PWM_RESOLUTION);
288
- _setPwm (pinC , _PWM_RANGE*dc_c, _PWM_RESOLUTION);
352
+ _setPwm (((STM32DriverParams*)params)-> timers [ 0 ], ((STM32DriverParams*)params)-> channels [ 0 ] , _PWM_RANGE*dc_a, _PWM_RESOLUTION);
353
+ _setPwm (((STM32DriverParams*)params)-> timers [ 1 ], ((STM32DriverParams*)params)-> channels [ 1 ] , _PWM_RANGE*dc_b, _PWM_RESOLUTION);
354
+ _setPwm (((STM32DriverParams*)params)-> timers [ 2 ], ((STM32DriverParams*)params)-> channels [ 2 ] , _PWM_RANGE*dc_c, _PWM_RESOLUTION);
289
355
}
290
356
291
357
292
358
// function setting the pwm duty cycle to the hardware
293
359
// - Stepper motor - 4PWM setting
294
360
// - hardware speciffic
295
- void _writeDutyCycle4PWM (float dc_1a, float dc_1b, float dc_2a, float dc_2b, int pin1A, int pin1B, int pin2A, int pin2B ){
361
+ void _writeDutyCycle4PWM (float dc_1a, float dc_1b, float dc_2a, float dc_2b, void * params ){
296
362
// transform duty cycle from [0,1] to [0,4095]
297
- _setPwm (pin1A , _PWM_RANGE*dc_1a, _PWM_RESOLUTION);
298
- _setPwm (pin1B , _PWM_RANGE*dc_1b, _PWM_RESOLUTION);
299
- _setPwm (pin2A , _PWM_RANGE*dc_2a, _PWM_RESOLUTION);
300
- _setPwm (pin2B , _PWM_RANGE*dc_2b, _PWM_RESOLUTION);
363
+ _setPwm (((STM32DriverParams*)params)-> timers [ 0 ], ((STM32DriverParams*)params)-> channels [ 0 ] , _PWM_RANGE*dc_1a, _PWM_RESOLUTION);
364
+ _setPwm (((STM32DriverParams*)params)-> timers [ 1 ], ((STM32DriverParams*)params)-> channels [ 1 ] , _PWM_RANGE*dc_1b, _PWM_RESOLUTION);
365
+ _setPwm (((STM32DriverParams*)params)-> timers [ 2 ], ((STM32DriverParams*)params)-> channels [ 2 ] , _PWM_RANGE*dc_2a, _PWM_RESOLUTION);
366
+ _setPwm (((STM32DriverParams*)params)-> timers [ 3 ], ((STM32DriverParams*)params)-> channels [ 3 ] , _PWM_RANGE*dc_2b, _PWM_RESOLUTION);
301
367
}
302
368
303
369
@@ -306,55 +372,66 @@ void _writeDutyCycle4PWM(float dc_1a, float dc_1b, float dc_2a, float dc_2b, in
306
372
// Configuring PWM frequency, resolution and alignment
307
373
// - BLDC driver - 6PWM setting
308
374
// - hardware specific
309
- 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){
375
+ 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){
310
376
if ( !pwm_frequency || !_isset (pwm_frequency) ) pwm_frequency = _PWM_FREQUENCY; // default frequency 25khz
311
377
else pwm_frequency = _constrain (pwm_frequency, 0 , _PWM_FREQUENCY_MAX); // constrain to |%0kHz max
312
378
// center-aligned frequency is uses two periods
313
379
pwm_frequency *=2 ;
314
380
315
381
// find configuration
316
382
int config = _interfaceType (pinA_h, pinA_l, pinB_h, pinB_l, pinC_h, pinC_l);
383
+ STM32DriverParams* params;
317
384
// configure accordingly
318
385
switch (config){
319
386
case _ERROR_6PWM:
320
- return -1 ; // fail
321
- break ;
387
+ return SIMPLEFOC_DRIVER_INIT_FAILED;
322
388
case _HARDWARE_6PWM:
323
- _initHardware6PWMInterface (pwm_frequency, dead_zone, pinA_h, pinA_l, pinB_h, pinB_l, pinC_h, pinC_l);
389
+ params = _initHardware6PWMInterface (pwm_frequency, dead_zone, pinA_h, pinA_l, pinB_h, pinB_l, pinC_h, pinC_l);
324
390
break ;
325
391
case _SOFTWARE_6PWM:
326
392
HardwareTimer* HT1 = _initPinPWMHigh (pwm_frequency, pinA_h);
327
393
_initPinPWMLow (pwm_frequency, pinA_l);
328
- HardwareTimer* HT2 = _initPinPWMHigh (pwm_frequency,pinB_h);
394
+ HardwareTimer* HT2 = _initPinPWMHigh (pwm_frequency, pinB_h);
329
395
_initPinPWMLow (pwm_frequency, pinB_l);
330
- HardwareTimer* HT3 = _initPinPWMHigh (pwm_frequency,pinC_h);
396
+ HardwareTimer* HT3 = _initPinPWMHigh (pwm_frequency, pinC_h);
331
397
_initPinPWMLow (pwm_frequency, pinC_l);
332
398
_alignPWMTimers (HT1, HT2, HT3);
399
+ uint32_t channel1 = STM_PIN_CHANNEL (pinmap_function (digitalPinToPinName (pinA_h), PinMap_PWM));
400
+ uint32_t channel2 = STM_PIN_CHANNEL (pinmap_function (digitalPinToPinName (pinA_l), PinMap_PWM));
401
+ uint32_t channel3 = STM_PIN_CHANNEL (pinmap_function (digitalPinToPinName (pinB_h), PinMap_PWM));
402
+ uint32_t channel4 = STM_PIN_CHANNEL (pinmap_function (digitalPinToPinName (pinB_l), PinMap_PWM));
403
+ uint32_t channel5 = STM_PIN_CHANNEL (pinmap_function (digitalPinToPinName (pinC_h), PinMap_PWM));
404
+ uint32_t channel6 = STM_PIN_CHANNEL (pinmap_function (digitalPinToPinName (pinC_l), PinMap_PWM));
405
+ params = new STM32DriverParams {
406
+ .timers = { HT1, HT2, HT3 },
407
+ .channels = { channel1, channel2, channel3, channel4, channel5, channel6 },
408
+ .pwm_frequency = pwm_frequency,
409
+ .dead_zone = dead_zone,
410
+ .interface_type = _SOFTWARE_6PWM
411
+ };
333
412
break ;
334
413
}
335
- return 0 ; // success
414
+ return params ; // success
336
415
}
337
416
338
417
// Function setting the duty cycle to the pwm pin (ex. analogWrite())
339
418
// - BLDC driver - 6PWM setting
340
419
// - hardware specific
341
- void _writeDutyCycle6PWM (float dc_a, float dc_b, float dc_c, float dead_zone, int pinA_h, int pinA_l, int pinB_h, int pinB_l, int pinC_h, int pinC_l){
342
- // find configuration
343
- int config = _interfaceType (pinA_h, pinA_l, pinB_h, pinB_l, pinC_h, pinC_l);
344
- // set pwm accordingly
345
- switch (config){
420
+ void _writeDutyCycle6PWM (float dc_a, float dc_b, float dc_c, void * params){
421
+ switch (((STM32DriverParams*)params)->interface_type ){
346
422
case _HARDWARE_6PWM:
347
- _setPwm (pinA_h , _PWM_RANGE*dc_a, _PWM_RESOLUTION);
348
- _setPwm (pinB_h , _PWM_RANGE*dc_b, _PWM_RESOLUTION);
349
- _setPwm (pinC_h , _PWM_RANGE*dc_c, _PWM_RESOLUTION);
423
+ _setPwm (((STM32DriverParams*)params)-> timers [ 0 ], ((STM32DriverParams*)params)-> channels [ 0 ] , _PWM_RANGE*dc_a, _PWM_RESOLUTION);
424
+ _setPwm (((STM32DriverParams*)params)-> timers [ 0 ], ((STM32DriverParams*)params)-> channels [ 1 ] , _PWM_RANGE*dc_b, _PWM_RESOLUTION);
425
+ _setPwm (((STM32DriverParams*)params)-> timers [ 0 ], ((STM32DriverParams*)params)-> channels [ 2 ] , _PWM_RANGE*dc_c, _PWM_RESOLUTION);
350
426
break ;
351
427
case _SOFTWARE_6PWM:
352
- _setPwm (pinA_l, _constrain (dc_a + dead_zone/2 , 0 , 1 )*_PWM_RANGE, _PWM_RESOLUTION);
353
- _setPwm (pinA_h, _constrain (dc_a - dead_zone/2 , 0 , 1 )*_PWM_RANGE, _PWM_RESOLUTION);
354
- _setPwm (pinB_l, _constrain (dc_b + dead_zone/2 , 0 , 1 )*_PWM_RANGE, _PWM_RESOLUTION);
355
- _setPwm (pinB_h, _constrain (dc_b - dead_zone/2 , 0 , 1 )*_PWM_RANGE, _PWM_RESOLUTION);
356
- _setPwm (pinC_l, _constrain (dc_c + dead_zone/2 , 0 , 1 )*_PWM_RANGE, _PWM_RESOLUTION);
357
- _setPwm (pinC_h, _constrain (dc_c - dead_zone/2 , 0 , 1 )*_PWM_RANGE, _PWM_RESOLUTION);
428
+ float dead_zone = ((STM32DriverParams*)params)->dead_zone ;
429
+ _setPwm (((STM32DriverParams*)params)->timers [0 ], ((STM32DriverParams*)params)->channels [0 ], _constrain (dc_a + dead_zone/2 , 0 , 1 )*_PWM_RANGE, _PWM_RESOLUTION);
430
+ _setPwm (((STM32DriverParams*)params)->timers [0 ], ((STM32DriverParams*)params)->channels [1 ], _constrain (dc_a - dead_zone/2 , 0 , 1 )*_PWM_RANGE, _PWM_RESOLUTION);
431
+ _setPwm (((STM32DriverParams*)params)->timers [1 ], ((STM32DriverParams*)params)->channels [2 ], _constrain (dc_b + dead_zone/2 , 0 , 1 )*_PWM_RANGE, _PWM_RESOLUTION);
432
+ _setPwm (((STM32DriverParams*)params)->timers [1 ], ((STM32DriverParams*)params)->channels [3 ], _constrain (dc_b - dead_zone/2 , 0 , 1 )*_PWM_RANGE, _PWM_RESOLUTION);
433
+ _setPwm (((STM32DriverParams*)params)->timers [2 ], ((STM32DriverParams*)params)->channels [4 ], _constrain (dc_c + dead_zone/2 , 0 , 1 )*_PWM_RANGE, _PWM_RESOLUTION);
434
+ _setPwm (((STM32DriverParams*)params)->timers [2 ], ((STM32DriverParams*)params)->channels [5 ], _constrain (dc_c - dead_zone/2 , 0 , 1 )*_PWM_RANGE, _PWM_RESOLUTION);
358
435
break ;
359
436
}
360
437
}
0 commit comments