Skip to content

Commit 0b7839f

Browse files
committed
FEAT added weak definitions of generic hardware implementations + arduino due same frequency PWM and TC calculation
1 parent dd3dbeb commit 0b7839f

File tree

5 files changed

+95
-84
lines changed

5 files changed

+95
-84
lines changed

src/common/foc_utils.h

Lines changed: 1 addition & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -9,6 +9,7 @@
99
#define _constrain(amt,low,high) ((amt)<(low)?(low):((amt)>(high)?(high):(amt)))
1010
#define _sqrt(a) (_sqrtApprox(a))
1111
#define _isset(a) ( (a) != (NOT_SET) )
12+
#define _UNUSED(v) (void) (v)
1213

1314
// utility defines
1415
#define _2_SQRT3 1.15470053838

src/drivers/hardware_specific/atmega328_mcu.cpp

Lines changed: 5 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -6,7 +6,7 @@
66
void _pinHighFrequency(const int pin){
77
// High PWM frequency
88
// https://sites.google.com/site/qeewiki/books/avr-guide/timers-on-the-atmega328
9-
if (pin == 5 || pin == 6 ) {
9+
if (pin == 5 || pin == 6 ) {
1010
TCCR0A = ((TCCR0A & 0b11111100) | 0x01); // configure the pwm phase-corrected mode
1111
TCCR0B = ((TCCR0B & 0b11110000) | 0x01); // set prescaler to 1
1212
}
@@ -17,12 +17,12 @@ void _pinHighFrequency(const int pin){
1717

1818
}
1919

20-
2120
// function setting the high pwm frequency to the supplied pins
2221
// - Stepper motor - 2PWM setting
2322
// - hardware speciffic
2423
// supports Arudino/ATmega328
2524
void _configure2PWM(long pwm_frequency,const int pinA, const int pinB) {
25+
_UNUSED(pwm_frequency);
2626
// High PWM frequency
2727
// - always max 32kHz
2828
_pinHighFrequency(pinA);
@@ -34,6 +34,7 @@ void _configure2PWM(long pwm_frequency,const int pinA, const int pinB) {
3434
// - hardware speciffic
3535
// supports Arudino/ATmega328
3636
void _configure3PWM(long pwm_frequency,const int pinA, const int pinB, const int pinC) {
37+
_UNUSED(pwm_frequency);
3738
// High PWM frequency
3839
// - always max 32kHz
3940
_pinHighFrequency(pinA);
@@ -118,6 +119,8 @@ int _configureComplementaryPair(int pinH, int pinL) {
118119
// - hardware specific
119120
// supports Arudino/ATmega328
120121
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) {
122+
_UNUSED(pwm_frequency);
123+
_UNUSED(dead_zone);
121124
// High PWM frequency
122125
// - always max 32kHz
123126
int ret_flag = 0;

src/drivers/hardware_specific/due_mcu.cpp

Lines changed: 51 additions & 36 deletions
Original file line numberDiff line numberDiff line change
@@ -1,6 +1,11 @@
11
#include "../hardware_api.h"
22

3-
#if defined(__arm__) && defined(__SAM3X8E__)
3+
#if defined(__arm__) && defined(__SAM3X8E__)
4+
5+
#define _PWM_FREQUENCY 25000 // 25khz
6+
#define _PWM_FREQUENCY_MAX 50000 // 50khz
7+
8+
#define _PWM_RES_MIN 255 // 50khz
49

510
// pwm frequency and max duty cycle
611
static unsigned long _pwm_frequency;
@@ -101,7 +106,29 @@ void initPWM(uint32_t ulPin, uint32_t pwm_freq){
101106
if (!PWMEnabled) {
102107
// PWM Startup code
103108
pmc_enable_periph_clk(PWM_INTERFACE_ID);
104-
PWMC_ConfigureClocks(pwm_freq * _max_pwm_value, 0, VARIANT_MCK);
109+
// this function does not work too well - I'll rewrite it
110+
// PWMC_ConfigureClocks(PWM_FREQUENCY * _max_pwm_value, 0, VARIANT_MCK);
111+
112+
// finding the divisors an prescalers form FindClockConfiguration function
113+
uint32_t divisors[11] = {1, 2, 4, 8, 16, 32, 64, 128, 256, 512, 1024};
114+
uint8_t divisor = 0;
115+
uint32_t prescaler;
116+
117+
/* Find prescaler and divisor values */
118+
prescaler = (VARIANT_MCK / divisors[divisor]) / (pwm_freq*_max_pwm_value);
119+
while ((prescaler > 255) && (divisor < 11)) {
120+
divisor++;
121+
prescaler = (VARIANT_MCK / divisors[divisor]) / (pwm_freq*_max_pwm_value);
122+
}
123+
// update the divisor*prescaler value
124+
prescaler = prescaler | (divisor << 8);
125+
126+
// now calculate the real resolution timer period necessary (pwm resolution)
127+
// pwm_res = bus_freq / (pwm_freq * (prescaler))
128+
_max_pwm_value = (double)VARIANT_MCK / (double)pwm_freq / (double)(prescaler);
129+
// set the prescaler value
130+
PWM->PWM_CLK = prescaler;
131+
105132
PWMEnabled = 1;
106133
}
107134

@@ -112,6 +139,8 @@ void initPWM(uint32_t ulPin, uint32_t pwm_freq){
112139
g_APinDescription[ulPin].ulPinType,
113140
g_APinDescription[ulPin].ulPin,
114141
g_APinDescription[ulPin].ulPinConfiguration);
142+
// PWM_CMR_CALG - center align
143+
// PWMC_ConfigureChannel(PWM_INTERFACE, chan, PWM_CMR_CPRE_CLKA, PWM_CMR_CALG, 0);
115144
PWMC_ConfigureChannel(PWM_INTERFACE, chan, PWM_CMR_CPRE_CLKA, 0, 0);
116145
PWMC_SetPeriod(PWM_INTERFACE, chan, _max_pwm_value);
117146
PWMC_SetDutyCycle(PWM_INTERFACE, chan, 0);
@@ -123,25 +152,26 @@ void initPWM(uint32_t ulPin, uint32_t pwm_freq){
123152

124153
if ((attr & PIN_ATTR_TIMER) == PIN_ATTR_TIMER) { // if timer pin
125154
// We use MCLK/2 as clock.
126-
const uint32_t TC = VARIANT_MCK / 2 / pwm_freq;
155+
const uint32_t TC = VARIANT_MCK / 2 / pwm_freq ;
127156
// Setup Timer for this pin
128157
ETCChannel channel = g_APinDescription[ulPin].ulTCChannel;
129158
uint32_t chNo = channelToChNo[channel];
130159
uint32_t chA = channelToAB[channel];
131160
Tc *chTC = channelToTC[channel];
132161
uint32_t interfaceID = channelToId[channel];
133162

134-
if (!TCChanEnabled[interfaceID]) {
135-
pmc_enable_periph_clk(TC_INTERFACE_ID + interfaceID);
136-
TC_Configure(chTC, chNo,
137-
TC_CMR_TCCLKS_TIMER_CLOCK1 |
138-
TC_CMR_WAVE | // Waveform mode
139-
TC_CMR_WAVSEL_UP_RC | // Counter running up and reset when equals to RC
140-
TC_CMR_EEVT_XC0 | // Set external events from XC0 (this setup TIOB as output)
141-
TC_CMR_ACPA_CLEAR | TC_CMR_ACPC_CLEAR |
142-
TC_CMR_BCPB_CLEAR | TC_CMR_BCPC_CLEAR);
143-
TC_SetRC(chTC, chNo, TC);
144-
}
163+
if (!TCChanEnabled[interfaceID]) {
164+
pmc_enable_periph_clk(TC_INTERFACE_ID + interfaceID);
165+
TC_Configure(chTC, chNo,
166+
TC_CMR_TCCLKS_TIMER_CLOCK1 |
167+
TC_CMR_WAVE | // Waveform mode
168+
TC_CMR_WAVSEL_UP_RC | // Counter running up and reset when equals to RC
169+
TC_CMR_EEVT_XC0 | // Set external events from XC0 (this setup TIOB as output)
170+
TC_CMR_ACPA_CLEAR | TC_CMR_ACPC_CLEAR |
171+
TC_CMR_BCPB_CLEAR | TC_CMR_BCPC_CLEAR);
172+
TC_SetRC(chTC, chNo, TC);
173+
}
174+
145175
// disable the counter on start
146176
if (chA){
147177
TC_SetCMR_ChannelA(chTC, chNo, TC_CMR_ACPA_CLEAR | TC_CMR_ACPC_SET);
@@ -197,7 +227,7 @@ void setPwm(uint32_t ulPin, uint32_t ulValue) {
197227
const uint32_t TC = VARIANT_MCK / 2 / _pwm_frequency;
198228
// Map value to Timer ranges 0..max_duty_cycle => 0..TC
199229
// Setup Timer for this pin
200-
ulValue = ulValue * TC;
230+
ulValue = ulValue * TC ;
201231
pwm_counter_vals[channel] = ulValue / _max_pwm_value;
202232
// enable counter
203233
if (channelToAB[channel])
@@ -297,8 +327,8 @@ void TC8_Handler()
297327
// - BLDC motor - 3PWM setting
298328
// - hardware specific
299329
void _configure3PWM(long pwm_frequency,const int pinA, const int pinB, const int pinC) {
300-
if(!pwm_frequency || !_isset(pwm_frequency) ) pwm_frequency = 35000; // default frequency 50khz
301-
else pwm_frequency = _constrain(pwm_frequency, 0, 50000); // constrain to 50kHz max
330+
if(!pwm_frequency || !_isset(pwm_frequency) ) pwm_frequency = _PWM_FREQUENCY; // default frequency 50khz
331+
else pwm_frequency = _constrain(pwm_frequency, 0, _PWM_FREQUENCY_MAX); // constrain to 50kHz max
302332
// save the pwm frequency
303333
_pwm_frequency = pwm_frequency;
304334
// cinfigure pwm pins
@@ -314,8 +344,8 @@ void _configure3PWM(long pwm_frequency,const int pinA, const int pinB, const int
314344
//- Stepper driver - 2PWM setting
315345
// - hardware specific
316346
void _configure2PWM(long pwm_frequency, const int pinA, const int pinB) {
317-
if(!pwm_frequency || !_isset(pwm_frequency)) pwm_frequency = 35000; // default frequency 50khz
318-
else pwm_frequency = _constrain(pwm_frequency, 0, 50000); // constrain to 50kHz max
347+
if(!pwm_frequency || !_isset(pwm_frequency)) pwm_frequency = _PWM_FREQUENCY; // default frequency 50khz
348+
else pwm_frequency = _constrain(pwm_frequency, 0, _PWM_FREQUENCY_MAX); // constrain to 50kHz max
319349
// save the pwm frequency
320350
_pwm_frequency = pwm_frequency;
321351
// cinfigure pwm pins
@@ -329,8 +359,8 @@ void _configure2PWM(long pwm_frequency, const int pinA, const int pinB) {
329359
// - Stepper motor - 4PWM setting
330360
// - hardware speciffic
331361
void _configure4PWM(long pwm_frequency,const int pinA, const int pinB, const int pinC, const int pinD) {
332-
if(!pwm_frequency || !_isset(pwm_frequency)) pwm_frequency = 35000; // default frequency 50khz
333-
else pwm_frequency = _constrain(pwm_frequency, 0, 50000); // constrain to 50kHz max
362+
if(!pwm_frequency || !_isset(pwm_frequency)) pwm_frequency = _PWM_FREQUENCY; // default frequency 50khz
363+
else pwm_frequency = _constrain(pwm_frequency, 0, _PWM_FREQUENCY_MAX); // constrain to 50kHz max
334364
// save the pwm frequency
335365
_pwm_frequency = pwm_frequency;
336366
// cinfigure pwm pins
@@ -373,19 +403,4 @@ void _writeDutyCycle2PWM(float dc_a, float dc_b, int pinA, int pinB){
373403
}
374404

375405

376-
// Configuring PWM frequency, resolution and alignment
377-
// - BLDC driver - 6PWM setting
378-
// - hardware specific
379-
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){
380-
return -1;
381-
}
382-
383-
// Function setting the duty cycle to the pwm pin (ex. analogWrite())
384-
// - BLDC driver - 6PWM setting
385-
// - hardware specific
386-
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){
387-
return;
388-
}
389-
390-
391406
#endif

src/drivers/hardware_specific/generic_mcu.cpp

Lines changed: 38 additions & 32 deletions
Original file line numberDiff line numberDiff line change
@@ -1,40 +1,25 @@
11
#include "../hardware_api.h"
22

3-
#if defined(__AVR_ATmega328P__) || defined(__AVR_ATmega168__) || defined(__AVR_ATmega328PB__) // if mcu is not atmega328
4-
5-
#elif defined(__AVR_ATmega2560__) // if mcu is not atmega2560
6-
7-
#elif defined(__arm__) && defined(CORE_TEENSY) // or teensy
8-
9-
#elif defined(__arm__) && defined(__SAM3X8E__) // or due
10-
11-
#elif defined(ESP_H) // or esp32
12-
13-
#elif defined(_STM32_DEF_) // or stm32
14-
15-
#elif defined(_SAMD21_) // samd21
16-
17-
#elif defined(_SAMD51_) // samd51
18-
19-
#elif defined(__SAME51J19A__) || defined(__ATSAME51J19A__) // samd51
20-
21-
#elif defined(TARGET_RP2040)
22-
23-
#else
24-
253
// function setting the high pwm frequency to the supplied pins
264
// - Stepper motor - 2PWM setting
275
// - hardware speciffic
286
// in generic case dont do anything
29-
void _configure2PWM(long pwm_frequency,const int pinA, const int pinB) {
7+
__attribute__((weak)) void _configure2PWM(long pwm_frequency,const int pinA, const int pinB) {
8+
_UNUSED(pwm_frequency);
9+
_UNUSED(pinA);
10+
_UNUSED(pinB);
3011
return;
3112
}
3213

3314
// function setting the high pwm frequency to the supplied pins
3415
// - BLDC motor - 3PWM setting
3516
// - hardware speciffic
3617
// in generic case dont do anything
37-
void _configure3PWM(long pwm_frequency,const int pinA, const int pinB, const int pinC) {
18+
__attribute__((weak)) void _configure3PWM(long pwm_frequency,const int pinA, const int pinB, const int pinC) {
19+
_UNUSED(pwm_frequency);
20+
_UNUSED(pinA);
21+
_UNUSED(pinB);
22+
_UNUSED(pinC);
3823
return;
3924
}
4025

@@ -43,22 +28,35 @@ void _configure3PWM(long pwm_frequency,const int pinA, const int pinB, const int
4328
// - Stepper motor - 4PWM setting
4429
// - hardware speciffic
4530
// in generic case dont do anything
46-
void _configure4PWM(long pwm_frequency,const int pin1A, const int pin1B, const int pin2A, const int pin2B) {
31+
__attribute__((weak)) void _configure4PWM(long pwm_frequency,const int pin1A, const int pin1B, const int pin2A, const int pin2B) {
32+
_UNUSED(pwm_frequency);
33+
_UNUSED(pin1A);
34+
_UNUSED(pin1B);
35+
_UNUSED(pin2A);
36+
_UNUSED(pin2B);
4737
return;
4838
}
4939

5040
// Configuring PWM frequency, resolution and alignment
5141
// - BLDC driver - 6PWM setting
5242
// - hardware specific
53-
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){
43+
__attribute__((weak)) 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){
44+
_UNUSED(pwm_frequency);
45+
_UNUSED(dead_zone);
46+
_UNUSED(pinA_h);
47+
_UNUSED(pinB_h);
48+
_UNUSED(pinC_h);
49+
_UNUSED(pinA_l);
50+
_UNUSED(pinB_l);
51+
_UNUSED(pinC_l);
5452
return -1;
5553
}
5654

5755

5856
// function setting the pwm duty cycle to the hardware
5957
// - Stepper motor - 2PWM setting
6058
// - hardware speciffic
61-
void _writeDutyCycle2PWM(float dc_a, float dc_b, int pinA, int pinB){
59+
__attribute__((weak)) void _writeDutyCycle2PWM(float dc_a, float dc_b, int pinA, int pinB){
6260
// transform duty cycle from [0,1] to [0,255]
6361
analogWrite(pinA, 255.0*dc_a);
6462
analogWrite(pinB, 255.0*dc_b);
@@ -67,7 +65,7 @@ void _writeDutyCycle2PWM(float dc_a, float dc_b, int pinA, int pinB){
6765
// function setting the pwm duty cycle to the hardware
6866
// - BLDC motor - 3PWM setting
6967
// - hardware speciffic
70-
void _writeDutyCycle3PWM(float dc_a, float dc_b, float dc_c, int pinA, int pinB, int pinC){
68+
__attribute__((weak)) void _writeDutyCycle3PWM(float dc_a, float dc_b, float dc_c, int pinA, int pinB, int pinC){
7169
// transform duty cycle from [0,1] to [0,255]
7270
analogWrite(pinA, 255.0*dc_a);
7371
analogWrite(pinB, 255.0*dc_b);
@@ -77,7 +75,7 @@ void _writeDutyCycle3PWM(float dc_a, float dc_b, float dc_c, int pinA, int pinB
7775
// function setting the pwm duty cycle to the hardware
7876
// - Stepper motor - 4PWM setting
7977
// - hardware speciffic
80-
void _writeDutyCycle4PWM(float dc_1a, float dc_1b, float dc_2a, float dc_2b, int pin1A, int pin1B, int pin2A, int pin2B){
78+
__attribute__((weak)) void _writeDutyCycle4PWM(float dc_1a, float dc_1b, float dc_2a, float dc_2b, int pin1A, int pin1B, int pin2A, int pin2B){
8179
// transform duty cycle from [0,1] to [0,255]
8280
analogWrite(pin1A, 255.0*dc_1a);
8381
analogWrite(pin1B, 255.0*dc_1b);
@@ -89,9 +87,17 @@ void _writeDutyCycle4PWM(float dc_1a, float dc_1b, float dc_2a, float dc_2b, in
8987
// Function setting the duty cycle to the pwm pin (ex. analogWrite())
9088
// - BLDC driver - 6PWM setting
9189
// - hardware specific
92-
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){
90+
__attribute__((weak)) 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){
91+
_UNUSED(dc_a);
92+
_UNUSED(dc_b);
93+
_UNUSED(dc_c);
94+
_UNUSED(dead_zone);
95+
_UNUSED(pinA_h);
96+
_UNUSED(pinB_h);
97+
_UNUSED(pinC_h);
98+
_UNUSED(pinA_l);
99+
_UNUSED(pinB_l);
100+
_UNUSED(pinC_l);
93101
return;
94102
}
95103

96-
97-
#endif

src/drivers/hardware_specific/teensy_mcu.cpp

Lines changed: 0 additions & 14 deletions
Original file line numberDiff line numberDiff line change
@@ -74,18 +74,4 @@ void _writeDutyCycle4PWM(float dc_1a, float dc_1b, float dc_2a, float dc_2b, in
7474
analogWrite(pin2B, 255.0*dc_2b);
7575
}
7676

77-
78-
// Configuring PWM frequency, resolution and alignment
79-
// - BLDC driver - 6PWM setting
80-
// - hardware specific
81-
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){
82-
return -1;
83-
}
84-
85-
// Function setting the duty cycle to the pwm pin (ex. analogWrite())
86-
// - BLDC driver - 6PWM setting
87-
// - hardware specific
88-
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){
89-
return;
90-
}
9177
#endif

0 commit comments

Comments
 (0)