SimpleFOClibrary 2.4.0
Loading...
Searching...
No Matches
portenta_h7_mcu.cpp
Go to the documentation of this file.
1
2#include "../hardware_api.h"
3
4#if defined(TARGET_PORTENTA_H7) && false
5
6
7#pragma message("")
8#pragma message("SimpleFOC: compiling for Arduino/Portenta_H7")
9#pragma message("")
10
11
12#include "pwmout_api.h"
13#include "pinDefinitions.h"
14#include "platform/mbed_critical.h"
15#include "platform/mbed_power_mgmt.h"
16#include "platform/mbed_assert.h"
17#include "PeripheralPins.h"
18#include "pwmout_device.h"
19
20// default pwm parameters
21#define _PWM_FREQUENCY 25000 // 25khz
22#define _PWM_FREQUENCY_MAX 50000 // 50khz
23
24
25// // 6pwm parameters
26// #define _HARDWARE_6PWM 1
27// #define _SOFTWARE_6PWM 0
28// #define _ERROR_6PWM -1
29
30
31
32typedef struct PortentaDriverParams {
33 pwmout_t pins[4];
34 long pwm_frequency;
35// float dead_zone;
36} PortentaDriverParams;
37
38
39
40/* Convert STM32 Cube HAL channel to LL channel */
41uint32_t _TIM_ChannelConvert_HAL2LL(uint32_t channel, pwmout_t *obj)
42{
43#if !defined(PWMOUT_INVERTED_NOT_SUPPORTED)
44 if (obj->inverted) {
45 switch (channel) {
46 case TIM_CHANNEL_1 :
47 return LL_TIM_CHANNEL_CH1N;
48 case TIM_CHANNEL_2 :
49 return LL_TIM_CHANNEL_CH2N;
50 case TIM_CHANNEL_3 :
51 return LL_TIM_CHANNEL_CH3N;
52#if defined(LL_TIM_CHANNEL_CH4N)
53 case TIM_CHANNEL_4 :
54 return LL_TIM_CHANNEL_CH4N;
55#endif
56 default : /* Optional */
57 return 0;
58 }
59 } else
60#endif
61 {
62 switch (channel) {
63 case TIM_CHANNEL_1 :
64 return LL_TIM_CHANNEL_CH1;
65 case TIM_CHANNEL_2 :
66 return LL_TIM_CHANNEL_CH2;
67 case TIM_CHANNEL_3 :
68 return LL_TIM_CHANNEL_CH3;
69 case TIM_CHANNEL_4 :
70 return LL_TIM_CHANNEL_CH4;
71 default : /* Optional */
72 return 0;
73 }
74 }
75}
76
77
78
79// int _pwm_init(pwmout_t *obj, uint32_t pin, long frequency){
80// return _pwm_init(obj, digitalPinToPinName(pin), frequency);
81// }
82
83int _pwm_init(pwmout_t *obj, uint32_t pin, long frequency){
84 int peripheral = (int)pinmap_peripheral(digitalPinToPinName(pin), PinMap_PWM);
85 int function = (int)pinmap_find_function(digitalPinToPinName(pin), PinMap_PWM);
86
87 const PinMap static_pinmap = {digitalPinToPinName(pin), peripheral, function};
88
89 pwmout_init_direct(obj, &static_pinmap);
90
91 TIM_HandleTypeDef TimHandle;
92 TimHandle.Instance = (TIM_TypeDef *)(obj->pwm);
93 RCC_ClkInitTypeDef RCC_ClkInitStruct;
94 uint32_t PclkFreq = 0;
95 uint32_t APBxCLKDivider = RCC_HCLK_DIV1;
96 uint8_t i = 0;
97
98
99 __HAL_TIM_DISABLE(&TimHandle);
100
101 // Get clock configuration
102 // Note: PclkFreq contains here the Latency (not used after)
103 HAL_RCC_GetClockConfig(&RCC_ClkInitStruct, &PclkFreq);
104
105 /* Parse the pwm / apb mapping table to find the right entry */
106 while (pwm_apb_map_table[i].pwm != obj->pwm) i++;
107 // sanity check
108 if (pwm_apb_map_table[i].pwm == 0) return -1;
109
110
111 if (pwm_apb_map_table[i].pwmoutApb == PWMOUT_ON_APB1) {
112 PclkFreq = HAL_RCC_GetPCLK1Freq();
113 APBxCLKDivider = RCC_ClkInitStruct.APB1CLKDivider;
114 } else {
115#if !defined(PWMOUT_APB2_NOT_SUPPORTED)
116 PclkFreq = HAL_RCC_GetPCLK2Freq();
117 APBxCLKDivider = RCC_ClkInitStruct.APB2CLKDivider;
118#endif
119 }
120
121 long period_us = 500000.0/((float)frequency);
122 /* By default use, 1us as SW pre-scaler */
123 obj->prescaler = 1;
124 // TIMxCLK = PCLKx when the APB prescaler = 1 else TIMxCLK = 2 * PCLKx
125 if (APBxCLKDivider == RCC_HCLK_DIV1) {
126 TimHandle.Init.Prescaler = (((PclkFreq) / 1000000)) - 1; // 1 us tick
127 } else {
128 TimHandle.Init.Prescaler = (((PclkFreq * 2) / 1000000)) - 1; // 1 us tick
129 }
130 TimHandle.Init.Period = (period_us - 1);
131
132 /* In case period or pre-scalers are out of range, loop-in to get valid values */
133 while ((TimHandle.Init.Period > 0xFFFF) || (TimHandle.Init.Prescaler > 0xFFFF)) {
134 obj->prescaler = obj->prescaler * 2;
135 if (APBxCLKDivider == RCC_HCLK_DIV1) {
136 TimHandle.Init.Prescaler = (((PclkFreq) / 1000000) * obj->prescaler) - 1;
137 } else {
138 TimHandle.Init.Prescaler = (((PclkFreq * 2) / 1000000) * obj->prescaler) - 1;
139 }
140 TimHandle.Init.Period = (period_us - 1) / obj->prescaler;
141 /* Period decreases and prescaler increases over loops, so check for
142 * possible out of range cases */
143 if ((TimHandle.Init.Period < 0xFFFF) && (TimHandle.Init.Prescaler > 0xFFFF)) {
144 break;
145 }
146 }
147
148 TimHandle.Init.ClockDivision = 0;
149 TimHandle.Init.CounterMode = TIM_COUNTERMODE_CENTERALIGNED3; // center aligned
150
151 if (HAL_TIM_PWM_Init(&TimHandle) != HAL_OK) {
152 return -1;
153 }
154
155 TIM_OC_InitTypeDef sConfig;
156 // Configure channels
157 sConfig.OCMode = TIM_OCMODE_PWM1;
158 sConfig.Pulse = obj->pulse / obj->prescaler;
159 sConfig.OCPolarity = TIM_OCPOLARITY_HIGH;
160 sConfig.OCFastMode = TIM_OCFAST_DISABLE;
161#if defined(TIM_OCIDLESTATE_RESET)
162 sConfig.OCIdleState = TIM_OCIDLESTATE_RESET;
163#endif
164#if defined(TIM_OCNIDLESTATE_RESET)
165 sConfig.OCNPolarity = TIM_OCNPOLARITY_HIGH;
166 sConfig.OCNIdleState = TIM_OCNIDLESTATE_RESET;
167#endif
168
169 int channel = 0;
170 switch (obj->channel) {
171 case 1:
172 channel = TIM_CHANNEL_1;
173 break;
174 case 2:
175 channel = TIM_CHANNEL_2;
176 break;
177 case 3:
178 channel = TIM_CHANNEL_3;
179 break;
180 case 4:
181 channel = TIM_CHANNEL_4;
182 break;
183 default:
184 return -1;
185 }
186
187 if (LL_TIM_CC_IsEnabledChannel(TimHandle.Instance, _TIM_ChannelConvert_HAL2LL(channel, obj)) == 0) {
188 // If channel is not enabled, proceed to channel configuration
189 if (HAL_TIM_PWM_ConfigChannel(&TimHandle, &sConfig, channel) != HAL_OK) {
190 return -1;
191 }
192 }
193
194 // Save for future use
195 obj->period = period_us;
196#if !defined(PWMOUT_INVERTED_NOT_SUPPORTED)
197 if (obj->inverted) {
198 HAL_TIMEx_PWMN_Start(&TimHandle, channel);
199 } else
200#endif
201 {
202 HAL_TIM_PWM_Start(&TimHandle, channel);
203 }
204
205 return 0;
206}
207
208// setting pwm to hardware pin - instead analogWrite()
209void _pwm_write(pwmout_t *obj, float value){
210 TIM_HandleTypeDef TimHandle;
211 int channel = 0;
212
213 TimHandle.Instance = (TIM_TypeDef *)(obj->pwm);
214
215 if (value < (float)0.0) {
216 value = 0.0;
217 } else if (value > (float)1.0) {
218 value = 1.0;
219 }
220
221 obj->pulse = (uint32_t)((float)obj->period * value + 0.5);
222
223 switch (obj->channel) {
224 case 1:
225 channel = TIM_CHANNEL_1;
226 break;
227 case 2:
228 channel = TIM_CHANNEL_2;
229 break;
230 case 3:
231 channel = TIM_CHANNEL_3;
232 break;
233 case 4:
234 channel = TIM_CHANNEL_4;
235 break;
236 default:
237 return;
238 }
239
240 // If channel already enabled, only update compare value to avoid glitch
241 __HAL_TIM_SET_COMPARE(&TimHandle, channel, obj->pulse / obj->prescaler);
242}
243
244// init low side pin
245// HardwareTimer* _initPinPWMLow(uint32_t PWM_freq, int ulPin)
246// {
247// PinName pin = digitalPinToPinName(ulPin);
248// TIM_TypeDef *Instance = (TIM_TypeDef *)pinmap_peripheral(pin, PinMap_PWM);
249// uint32_t index = get_timer_index(Instance);
250
251// if (HardwareTimer_Handle[index] == NULL) {
252// HardwareTimer_Handle[index]->__this = new HardwareTimer((TIM_TypeDef *)pinmap_peripheral(pin, PinMap_PWM));
253// HardwareTimer_Handle[index]->handle.Init.CounterMode = TIM_COUNTERMODE_CENTERALIGNED3;
254// HAL_TIM_Base_Init(&(HardwareTimer_Handle[index]->handle));
255// TIM_OC_InitTypeDef sConfigOC = TIM_OC_InitTypeDef();
256// sConfigOC.OCMode = TIM_OCMODE_PWM2;
257// sConfigOC.Pulse = 100;
258// sConfigOC.OCPolarity = TIM_OCPOLARITY_LOW;
259// sConfigOC.OCFastMode = TIM_OCFAST_DISABLE;
260// sConfigOC.OCNPolarity = TIM_OCNPOLARITY_HIGH;
261// sConfigOC.OCIdleState = TIM_OCIDLESTATE_SET;
262// sConfigOC.OCNIdleState = TIM_OCNIDLESTATE_RESET;
263// uint32_t channel = STM_PIN_CHANNEL(pinmap_function(pin, PinMap_PWM));
264// HAL_TIM_PWM_ConfigChannel(&(HardwareTimer_Handle[index]->handle), &sConfigOC, channel);
265// }
266// HardwareTimer *HT = (HardwareTimer *)(HardwareTimer_Handle[index]->__this);
267// uint32_t channel = STM_PIN_CHANNEL(pinmap_function(pin, PinMap_PWM));
268// HT->setMode(channel, TIMER_OUTPUT_COMPARE_PWM2, pin);
269// HT->setOverflow(PWM_freq, HERTZ_FORMAT);
270// HT->pause();
271// HT->refresh();
272// return HT;
273// }
274
275
276// align the timers to end the init
277void _alignPWMTimers(pwmout_t *t1, pwmout_t *t2){
278 TIM_HandleTypeDef TimHandle1, TimHandle2;
279 TimHandle1.Instance = (TIM_TypeDef *)(t1->pwm);
280 TimHandle2.Instance = (TIM_TypeDef *)(t2->pwm);
281 __HAL_TIM_DISABLE(&TimHandle1);
282 __HAL_TIM_DISABLE(&TimHandle2);
283 __HAL_TIM_ENABLE(&TimHandle1);
284 __HAL_TIM_ENABLE(&TimHandle2);
285}
286
287// align the timers to end the init
288void _alignPWMTimers(pwmout_t *t1, pwmout_t *t2, pwmout_t *t3){
289 TIM_HandleTypeDef TimHandle1, TimHandle2, TimHandle3;
290 TimHandle1.Instance = (TIM_TypeDef *)(t1->pwm);
291 TimHandle2.Instance = (TIM_TypeDef *)(t2->pwm);
292 TimHandle3.Instance = (TIM_TypeDef *)(t3->pwm);
293 __HAL_TIM_DISABLE(&TimHandle1);
294 __HAL_TIM_DISABLE(&TimHandle2);
295 __HAL_TIM_DISABLE(&TimHandle3);
296 __HAL_TIM_ENABLE(&TimHandle1);
297 __HAL_TIM_ENABLE(&TimHandle2);
298 __HAL_TIM_ENABLE(&TimHandle3);
299}
300
301// align the timers to end the init
302void _alignPWMTimers(pwmout_t *t1, pwmout_t *t2, pwmout_t *t3, pwmout_t *t4){
303 TIM_HandleTypeDef TimHandle1, TimHandle2, TimHandle3, TimHandle4;
304 TimHandle1.Instance = (TIM_TypeDef *)(t1->pwm);
305 TimHandle2.Instance = (TIM_TypeDef *)(t2->pwm);
306 TimHandle3.Instance = (TIM_TypeDef *)(t3->pwm);
307 TimHandle4.Instance = (TIM_TypeDef *)(t4->pwm);
308 __HAL_TIM_DISABLE(&TimHandle1);
309 __HAL_TIM_DISABLE(&TimHandle2);
310 __HAL_TIM_DISABLE(&TimHandle3);
311 __HAL_TIM_DISABLE(&TimHandle4);
312 __HAL_TIM_ENABLE(&TimHandle1);
313 __HAL_TIM_ENABLE(&TimHandle2);
314 __HAL_TIM_ENABLE(&TimHandle3);
315 __HAL_TIM_ENABLE(&TimHandle4);
316}
317
318// // configure hardware 6pwm interface only one timer with inverted channels
319// 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)
320// {
321// PinName uhPinName = digitalPinToPinName(pinA_h);
322// PinName ulPinName = digitalPinToPinName(pinA_l);
323// PinName vhPinName = digitalPinToPinName(pinB_h);
324// PinName vlPinName = digitalPinToPinName(pinB_l);
325// PinName whPinName = digitalPinToPinName(pinC_h);
326// PinName wlPinName = digitalPinToPinName(pinC_l);
327
328// TIM_TypeDef *Instance = (TIM_TypeDef *)pinmap_peripheral(uhPinName, PinMap_PWM);
329
330// uint32_t index = get_timer_index(Instance);
331
332// if (HardwareTimer_Handle[index] == NULL) {
333// HardwareTimer_Handle[index]->__this = new HardwareTimer((TIM_TypeDef *)pinmap_peripheral(uhPinName, PinMap_PWM));
334// HardwareTimer_Handle[index]->handle.Init.CounterMode = TIM_COUNTERMODE_CENTERALIGNED3;
335// HAL_TIM_Base_Init(&(HardwareTimer_Handle[index]->handle));
336// ((HardwareTimer *)HardwareTimer_Handle[index]->__this)->setOverflow(PWM_freq, HERTZ_FORMAT);
337// }
338// HardwareTimer *HT = (HardwareTimer *)(HardwareTimer_Handle[index]->__this);
339
340// HT->setMode(STM_PIN_CHANNEL(pinmap_function(uhPinName, PinMap_PWM)), TIMER_OUTPUT_COMPARE_PWM1, uhPinName);
341// HT->setMode(STM_PIN_CHANNEL(pinmap_function(ulPinName, PinMap_PWM)), TIMER_OUTPUT_COMPARE_PWM1, ulPinName);
342// HT->setMode(STM_PIN_CHANNEL(pinmap_function(vhPinName, PinMap_PWM)), TIMER_OUTPUT_COMPARE_PWM1, vhPinName);
343// HT->setMode(STM_PIN_CHANNEL(pinmap_function(vlPinName, PinMap_PWM)), TIMER_OUTPUT_COMPARE_PWM1, vlPinName);
344// HT->setMode(STM_PIN_CHANNEL(pinmap_function(whPinName, PinMap_PWM)), TIMER_OUTPUT_COMPARE_PWM1, whPinName);
345// HT->setMode(STM_PIN_CHANNEL(pinmap_function(wlPinName, PinMap_PWM)), TIMER_OUTPUT_COMPARE_PWM1, wlPinName);
346
347// // dead time is set in nanoseconds
348// uint32_t dead_time_ns = (float)(1e9f/PWM_freq)*dead_zone;
349// uint32_t dead_time = __LL_TIM_CALC_DEADTIME(SystemCoreClock, LL_TIM_GetClockDivision(HT->getHandle()->Instance), dead_time_ns);
350// LL_TIM_OC_SetDeadTime(HT->getHandle()->Instance, dead_time); // deadtime is non linear!
351// LL_TIM_CC_EnableChannel(HT->getHandle()->Instance, LL_TIM_CHANNEL_CH1 | LL_TIM_CHANNEL_CH1N | LL_TIM_CHANNEL_CH2 | LL_TIM_CHANNEL_CH2N | LL_TIM_CHANNEL_CH3 | LL_TIM_CHANNEL_CH3N);
352
353// HT->pause();
354// HT->refresh();
355// HT->resume();
356// return HT;
357// }
358
359
360// // returns 0 if each pair of pwm channels has same channel
361// // returns 1 all the channels belong to the same timer - hardware inverted channels
362// // returns -1 if neither - avoid configuring - error!!!
363// int _interfaceType(const int pinA_h, const int pinA_l, const int pinB_h, const int pinB_l, const int pinC_h, const int pinC_l){
364// PinName nameAH = digitalPinToPinName(pinA_h);
365// PinName nameAL = digitalPinToPinName(pinA_l);
366// PinName nameBH = digitalPinToPinName(pinB_h);
367// PinName nameBL = digitalPinToPinName(pinB_l);
368// PinName nameCH = digitalPinToPinName(pinC_h);
369// PinName nameCL = digitalPinToPinName(pinC_l);
370// int tim1 = get_timer_index((TIM_TypeDef *)pinmap_peripheral(nameAH, PinMap_PWM));
371// int tim2 = get_timer_index((TIM_TypeDef *)pinmap_peripheral(nameAL, PinMap_PWM));
372// int tim3 = get_timer_index((TIM_TypeDef *)pinmap_peripheral(nameBH, PinMap_PWM));
373// int tim4 = get_timer_index((TIM_TypeDef *)pinmap_peripheral(nameBL, PinMap_PWM));
374// int tim5 = get_timer_index((TIM_TypeDef *)pinmap_peripheral(nameCH, PinMap_PWM));
375// int tim6 = get_timer_index((TIM_TypeDef *)pinmap_peripheral(nameCL, PinMap_PWM));
376// if(tim1 == tim2 && tim2==tim3 && tim3==tim4 && tim4==tim5 && tim5==tim6)
377// return _HARDWARE_6PWM; // hardware 6pwm interface - only on timer
378// else if(tim1 == tim2 && tim3==tim4 && tim5==tim6)
379// return _SOFTWARE_6PWM; // software 6pwm interface - each pair of high-low side same timer
380// else
381// return _ERROR_6PWM; // might be error avoid configuration
382// }
383
384
385
386// function setting the high pwm frequency to the supplied pins
387// - Stepper motor - 2PWM setting
388// - hardware speciffic
389void* _configure2PWM(long pwm_frequency,const int pinA, const int pinB) {
390 if( !pwm_frequency || !_isset(pwm_frequency) ) pwm_frequency = _PWM_FREQUENCY; // default frequency 25khz
391 else pwm_frequency = _constrain(pwm_frequency, 0, _PWM_FREQUENCY_MAX); // constrain to 50kHz max
392
393 PortentaDriverParams* params = new PortentaDriverParams();
394 params->pwm_frequency = pwm_frequency;
395
396 core_util_critical_section_enter();
397 _pwm_init(&(params->pins[0]), pinA, (long)pwm_frequency);
398 _pwm_init(&(params->pins[1]), pinB, (long)pwm_frequency);
399 // allign the timers
400 _alignPWMTimers(&(params->pins[0]), &(params->pins[1]));
401 core_util_critical_section_exit();
402 return params;
403}
404
405
406// function setting the high pwm frequency to the supplied pins
407// - BLDC motor - 3PWM setting
408// - hardware speciffic
409void* _configure3PWM(long pwm_frequency,const int pinA, const int pinB, const int pinC) {
410 if( !pwm_frequency || !_isset(pwm_frequency) ) pwm_frequency = _PWM_FREQUENCY; // default frequency 25khz
411 else pwm_frequency = _constrain(pwm_frequency, 0, _PWM_FREQUENCY_MAX); // constrain to 50kHz max
412
413 PortentaDriverParams* params = new PortentaDriverParams();
414 params->pwm_frequency = pwm_frequency;
415
416 core_util_critical_section_enter();
417 _pwm_init(&(params->pins[0]), pinA, (long)pwm_frequency);
418 _pwm_init(&(params->pins[1]), pinB, (long)pwm_frequency);
419 _pwm_init(&(params->pins[2]), pinC, (long)pwm_frequency);
420 // allign the timers
421 _alignPWMTimers(&(params->pins[0]), &(params->pins[1]), &(params->pins[2]));
422 core_util_critical_section_exit();
423
424 return params;
425}
426
427
428
429// function setting the high pwm frequency to the supplied pins
430// - Stepper motor - 4PWM setting
431// - hardware speciffic
432void* _configure4PWM(long pwm_frequency,const int pinA, const int pinB, const int pinC, const int pinD) {
433 if( !pwm_frequency || !_isset(pwm_frequency) ) pwm_frequency = _PWM_FREQUENCY; // default frequency 25khz
434 else pwm_frequency = _constrain(pwm_frequency, 0, _PWM_FREQUENCY_MAX); // constrain to 50kHz max
435
436 PortentaDriverParams* params = new PortentaDriverParams();
437 params->pwm_frequency = pwm_frequency;
438
439 core_util_critical_section_enter();
440 _pwm_init(&(params->pins[0]), pinA, (long)pwm_frequency);
441 _pwm_init(&(params->pins[1]), pinB, (long)pwm_frequency);
442 _pwm_init(&(params->pins[2]), pinC, (long)pwm_frequency);
443 _pwm_init(&(params->pins[3]), pinD, (long)pwm_frequency);
444 // allign the timers
445 _alignPWMTimers(&(params->pins[0]), &(params->pins[1]), &(params->pins[2]), &(params->pins[3]));
446 core_util_critical_section_exit();
447
448 return params;
449}
450
451
452
453// function setting the pwm duty cycle to the hardware
454// - Stepper motor - 2PWM setting
455//- hardware speciffic
456void _writeDutyCycle2PWM(float dc_a, float dc_b, void* params){
457 core_util_critical_section_enter();
458 _pwm_write(&(((PortentaDriverParams*)params)->pins[0]), (float)dc_a);
459 _pwm_write(&(((PortentaDriverParams*)params)->pins[1]), (float)dc_b);
460 core_util_critical_section_exit();
461}
462
463// function setting the pwm duty cycle to the hardware
464// - BLDC motor - 3PWM setting
465//- hardware speciffic
466void _writeDutyCycle3PWM(float dc_a, float dc_b, float dc_c, void* params){
467 core_util_critical_section_enter();
468 _pwm_write(&(((PortentaDriverParams*)params)->pins[0]), (float)dc_a);
469 _pwm_write(&(((PortentaDriverParams*)params)->pins[1]), (float)dc_b);
470 _pwm_write(&(((PortentaDriverParams*)params)->pins[2]), (float)dc_c);
471 core_util_critical_section_exit();
472}
473
474
475// function setting the pwm duty cycle to the hardware
476// - Stepper motor - 4PWM setting
477//- hardware speciffic
478void _writeDutyCycle4PWM(float dc_1a, float dc_1b, float dc_2a, float dc_2b, void* params){
479 core_util_critical_section_enter();
480 _pwm_write(&(((PortentaDriverParams*)params)->pins[0]), (float)dc_1a);
481 _pwm_write(&(((PortentaDriverParams*)params)->pins[1]), (float)dc_1b);
482 _pwm_write(&(((PortentaDriverParams*)params)->pins[2]), (float)dc_2a);
483 _pwm_write(&(((PortentaDriverParams*)params)->pins[3]), (float)dc_2b);
484 core_util_critical_section_exit();
485}
486
487
488// 6-PWM currently not supported, defer to generic, which also doesn't support it ;-)
489
490// Configuring PWM frequency, resolution and alignment
491// - BLDC driver - 6PWM setting
492// - hardware specific
493//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){
494 // if( !pwm_frequency || !_isset(pwm_frequency) ) pwm_frequency = _PWM_FREQUENCY; // default frequency 25khz
495 // else pwm_frequency = _constrain(pwm_frequency, 0, _PWM_FREQUENCY_MAX); // constrain to |%0kHz max
496 // // center-aligned frequency is uses two periods
497 // pwm_frequency *=2;
498
499 // // find configuration
500 // int config = _interfaceType(pinA_h, pinA_l, pinB_h, pinB_l, pinC_h, pinC_l);
501 // // configure accordingly
502 // switch(config){
503 // case _ERROR_6PWM:
504 // return -1; // fail
505 // break;
506 // case _HARDWARE_6PWM:
507 // _initHardware6PWMInterface(pwm_frequency, dead_zone, pinA_h, pinA_l, pinB_h, pinB_l, pinC_h, pinC_l);
508 // break;
509 // case _SOFTWARE_6PWM:
510 // HardwareTimer* HT1 = _initPinPWMHigh(pwm_frequency, pinA_h);
511 // _initPinPWMLow(pwm_frequency, pinA_l);
512 // HardwareTimer* HT2 = _initPinPWMHigh(pwm_frequency,pinB_h);
513 // _initPinPWMLow(pwm_frequency, pinB_l);
514 // HardwareTimer* HT3 = _initPinPWMHigh(pwm_frequency,pinC_h);
515 // _initPinPWMLow(pwm_frequency, pinC_l);
516 // _alignPWMTimers(HT1, HT2, HT3);
517 // break;
518 // }
519// return -1; // success
520// }
521
522// Function setting the duty cycle to the pwm pin (ex. analogWrite())
523// - BLDC driver - 6PWM setting
524// - hardware specific
525//void _writeDutyCycle6PWM(float dc_a, float dc_b, float dc_c, void* params){
526 // // find configuration
527 // int config = _interfaceType(pinA_h, pinA_l, pinB_h, pinB_l, pinC_h, pinC_l);
528 // // set pwm accordingly
529 // switch(config){
530 // case _HARDWARE_6PWM:
531 // _setPwm(pinA_h, _PWM_RANGE*dc_a, _PWM_RESOLUTION);
532 // _setPwm(pinB_h, _PWM_RANGE*dc_b, _PWM_RESOLUTION);
533 // _setPwm(pinC_h, _PWM_RANGE*dc_c, _PWM_RESOLUTION);
534 // break;
535 // case _SOFTWARE_6PWM:
536 // _setPwm(pinA_l, _constrain(dc_a + dead_zone/2, 0, 1)*_PWM_RANGE, _PWM_RESOLUTION);
537 // _setPwm(pinA_h, _constrain(dc_a - dead_zone/2, 0, 1)*_PWM_RANGE, _PWM_RESOLUTION);
538 // _setPwm(pinB_l, _constrain(dc_b + dead_zone/2, 0, 1)*_PWM_RANGE, _PWM_RESOLUTION);
539 // _setPwm(pinB_h, _constrain(dc_b - dead_zone/2, 0, 1)*_PWM_RANGE, _PWM_RESOLUTION);
540 // _setPwm(pinC_l, _constrain(dc_c + dead_zone/2, 0, 1)*_PWM_RANGE, _PWM_RESOLUTION);
541 // _setPwm(pinC_h, _constrain(dc_c - dead_zone/2, 0, 1)*_PWM_RANGE, _PWM_RESOLUTION);
542 // break;
543 // }
544//}
545#endif
const int const int const int pinC
GenericCurrentSenseParams * params
void * _configure4PWM(long pwm_frequency, const int pin1A, const int pin1B, const int pin2A, const int pin2B)
void * _configure2PWM(long pwm_frequency, const int pinA, const int pinB)
void _writeDutyCycle2PWM(float dc_a, float dc_b, void *params)
void _writeDutyCycle4PWM(float dc_1a, float dc_1b, float dc_2a, float dc_2b, void *params)
void * _configure3PWM(long pwm_frequency, const int pinA, const int pinB, const int pinC)
void _writeDutyCycle3PWM(float dc_a, float dc_b, float dc_c, void *params)
float float float dc_2b
#define _isset(a)
Definition foc_utils.h:13
#define _constrain(amt, low, high)
Definition foc_utils.h:11