Skip to content

Commit d226061

Browse files
committed
added support for leonardo #108 and some cases for stm32l0x achitecture
1 parent 361d043 commit d226061

File tree

4 files changed

+184
-7
lines changed

4 files changed

+184
-7
lines changed

src/common/time_utils.cpp

Lines changed: 2 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -3,7 +3,7 @@
33
// function buffering delay()
44
// arduino uno function doesn't work well with interrupts
55
void _delay(unsigned long ms){
6-
#if defined(__AVR_ATmega328P__) || defined(__AVR_ATmega168__) || defined(__AVR_ATmega328PB__) || defined(__AVR_ATmega2560__)
6+
#if defined(__AVR_ATmega328P__) || defined(__AVR_ATmega168__) || defined(__AVR_ATmega328PB__) || defined(__AVR_ATmega2560__) || defined(__AVR_ATmega32U4__)
77
// if arduino uno and other atmega328p chips
88
// use while instad of delay,
99
// due to wrong measurement based on changed timer0
@@ -19,7 +19,7 @@ void _delay(unsigned long ms){
1919
// function buffering _micros()
2020
// arduino function doesn't work well with interrupts
2121
unsigned long _micros(){
22-
#if defined(__AVR_ATmega328P__) || defined(__AVR_ATmega168__) || defined(__AVR_ATmega328PB__) || defined(__AVR_ATmega2560__)
22+
#if defined(__AVR_ATmega328P__) || defined(__AVR_ATmega168__) || defined(__AVR_ATmega328PB__) || defined(__AVR_ATmega2560__) || defined(__AVR_ATmega32U4__)
2323
// if arduino uno and other atmega328p chips
2424
//return the value based on the prescaler
2525
if((TCCR0B & 0b00000111) == 0x01) return (micros()/32);

src/drivers/hardware_specific/atmega2560_mcu.cpp

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -7,7 +7,7 @@ void _pinHighFrequency(const int pin){
77
// High PWM frequency
88
// https://sites.google.com/site/qeewiki/books/avr-guide/timers-on-the-atmega328
99
// https://forum.arduino.cc/index.php?topic=72092.0
10-
if (pin == 13 || pin == 4 ) {
10+
if (pin == 13 || pin == 4 ) {
1111
TCCR0A = ((TCCR0A & 0b11111100) | 0x01); // configure the pwm phase-corrected mode
1212
TCCR0B = ((TCCR0B & 0b11110000) | 0x01); // set prescaler to 1
1313
}
Lines changed: 158 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,158 @@
1+
2+
#include "../hardware_api.h"
3+
4+
#if defined(__AVR_ATmega32U4__)
5+
6+
// set pwm frequency to 32KHz
7+
void _pinHighFrequency(const int pin){
8+
// High PWM frequency
9+
// reference: http://r6500.blogspot.com/2014/12/fast-pwm-on-arduino-leonardo.html
10+
if (pin == 3 || pin == 11 ) {
11+
TCCR0A = ((TCCR0A & 0b11111100) | 0x01); // configure the pwm phase-corrected mode
12+
TCCR0B = ((TCCR0B & 0b11110000) | 0x01); // set prescaler to 1
13+
}
14+
else if (pin == 9 || pin == 10 )
15+
TCCR1B = ((TCCR1B & 0b11111000) | 0x01); // set prescaler to 1
16+
else if (pin == 5 )
17+
TCCR3B = ((TCCR3B & 0b11111000) | 0x01); // set prescaler to 1
18+
else if ( pin == 6 || pin == 13 ) { // a bit more complicated 10 bit timer
19+
// PLL Configuration
20+
PLLFRQ= ((PLLFRQ & 0b11001111) | 0x20) // Use 96MHz / 1.5 = 64MHz
21+
TCCR4B = ((TCCR4B & 0b11110000) | 0xB); // configure prescaler to get 64M/2/1024 = 31.25 kHz
22+
TCCR4D = ((TCCR4D & 0b11111100) | 0x01); // configure the pwm phase-corrected mode
23+
24+
if (pin == 6) TCCR4A = 0x82; // activate channel A - pin 13
25+
else if (pin == 13) TCCR4C |= 0x09; // Activate channel D - pin 6
26+
}
27+
28+
}
29+
30+
31+
// function setting the high pwm frequency to the supplied pins
32+
// - Stepper motor - 2PWM setting
33+
// - hardware speciffic
34+
void _configure2PWM(long pwm_frequency,const int pinA, const int pinB) {
35+
// High PWM frequency
36+
// - always max 32kHz
37+
_pinHighFrequency(pinA);
38+
_pinHighFrequency(pinB);
39+
}
40+
41+
// function setting the high pwm frequency to the supplied pins
42+
// - BLDC motor - 3PWM setting
43+
// - hardware speciffic
44+
void _configure3PWM(long pwm_frequency,const int pinA, const int pinB, const int pinC) {
45+
// High PWM frequency
46+
// - always max 32kHz
47+
_pinHighFrequency(pinA);
48+
_pinHighFrequency(pinB);
49+
_pinHighFrequency(pinC);
50+
}
51+
52+
// function setting the pwm duty cycle to the hardware
53+
// - Stepper motor - 2PWM setting
54+
// - hardware speciffic
55+
void _writeDutyCycle2PWM(float dc_a, float dc_b, int pinA, int pinB){
56+
// transform duty cycle from [0,1] to [0,255]
57+
analogWrite(pinA, 255.0*dc_a);
58+
analogWrite(pinB, 255.0*dc_b);
59+
}
60+
61+
// function setting the pwm duty cycle to the hardware
62+
// - BLDC motor - 3PWM setting
63+
// - hardware speciffic
64+
void _writeDutyCycle3PWM(float dc_a, float dc_b, float dc_c, int pinA, int pinB, int pinC){
65+
// transform duty cycle from [0,1] to [0,255]
66+
analogWrite(pinA, 255.0*dc_a);
67+
analogWrite(pinB, 255.0*dc_b);
68+
analogWrite(pinC, 255.0*dc_c);
69+
}
70+
71+
// function setting the high pwm frequency to the supplied pins
72+
// - Stepper motor - 4PWM setting
73+
// - hardware speciffic
74+
void _configure4PWM(long pwm_frequency,const int pin1A, const int pin1B, const int pin2A, const int pin2B) {
75+
// High PWM frequency
76+
// - always max 32kHz
77+
_pinHighFrequency(pin1A);
78+
_pinHighFrequency(pin1B);
79+
_pinHighFrequency(pin2A);
80+
_pinHighFrequency(pin2B);
81+
}
82+
83+
// function setting the pwm duty cycle to the hardware
84+
// - Stepper motor - 4PWM setting
85+
// - hardware speciffic
86+
void _writeDutyCycle4PWM(float dc_1a, float dc_1b, float dc_2a, float dc_2b, int pin1A, int pin1B, int pin2A, int pin2B){
87+
// transform duty cycle from [0,1] to [0,255]
88+
analogWrite(pin1A, 255.0*dc_1a);
89+
analogWrite(pin1B, 255.0*dc_1b);
90+
analogWrite(pin2A, 255.0*dc_2a);
91+
analogWrite(pin2B, 255.0*dc_2b);
92+
}
93+
94+
95+
96+
// Configuring PWM frequency, resolution and alignment
97+
// - BLDC driver - 6PWM setting
98+
// - hardware specific
99+
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) {
100+
101+
if( (pinH == 3 && pinL == 11 ) || (pinH == 11 && pinL == 3 ) ){
102+
// configure the pwm phase-corrected mode
103+
TCCR0A = ((TCCR0A & 0b11111100) | 0x01);
104+
// configure complementary pwm on low side
105+
if(pinH == 11 ) TCCR0A = 0b10110000 | (TCCR0A & 0b00001111) ;
106+
else TCCR0A = 0b11100000 | (TCCR0A & 0b00001111) ;
107+
// set prescaler to 1 - 32kHz freq
108+
TCCR0B = ((TCCR0B & 0b11110000) | 0x01);
109+
}else if( (pinH == 9 && pinL == 10 ) || (pinH == 10 && pinL == 9 ) ){
110+
// set prescaler to 1 - 32kHz freq
111+
TCCR1B = ((TCCR1B & 0b11111000) | 0x01);
112+
// configure complementary pwm on low side
113+
if(pinH == 9 ) TCCR1A = 0b10110000 | (TCCR1A & 0b00001111) ;
114+
else TCCR1A = 0b11100000 | (TCCR1A & 0b00001111) ;
115+
}else if((pinH == 6 && pinL == 13 ) || (pinH == 13 && pinL == 6 ) ){
116+
// PLL Configuration
117+
PLLFRQ= ((PLLFRQ & 0b11001111) | 0x20) // Use 96MHz / 1.5 = 64MHz
118+
TCCR4B = ((TCCR4B & 0b11110000) | 0xB); // configure prescaler to get 64M/2/1024 = 31.25 kHz
119+
TCCR4D = ((TCCR4D & 0b11111100) | 0x01); // configure the pwm phase-corrected mode
120+
121+
// configure complementary pwm on low side
122+
if(pinH == 13 ){
123+
TCCR4A = 0x82; // activate channel A - pin 13
124+
TCCR4C |= 0x0d; // Activate complementary channel D - pin 6
125+
}else {
126+
TCCR4C |= 0x09; // Activate channel D - pin 6
127+
TCCR4A = 0xc2; // activate complementary channel A - pin 13
128+
}
129+
}else{
130+
return -1;
131+
}
132+
return 0;
133+
}
134+
135+
// function setting the
136+
void _setPwmPair(int pinH, int pinL, float val, int dead_time)
137+
{
138+
int pwm_h = _constrain(val-dead_time/2,0,255);
139+
int pwm_l = _constrain(val+dead_time/2,0,255);
140+
141+
analogWrite(pinH, pwm_h);
142+
if(pwm_l == 255 || pwm_l == 0)
143+
digitalWrite(pinL, pwm_l ? LOW : HIGH);
144+
else
145+
analogWrite(pinL, pwm_l);
146+
}
147+
148+
// Function setting the duty cycle to the pwm pin (ex. analogWrite())
149+
// - BLDC driver - 6PWM setting
150+
// - hardware specific
151+
// supports Arudino/ATmega328
152+
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){
153+
_setPwmPair(pinA_h, pinA_l, dc_a*255.0, dead_zone*255.0);
154+
_setPwmPair(pinB_h, pinB_l, dc_b*255.0, dead_zone*255.0);
155+
_setPwmPair(pinC_h, pinC_l, dc_c*255.0, dead_zone*255.0);
156+
}
157+
158+
#endif

src/drivers/hardware_specific/stm32_mcu.cpp

Lines changed: 23 additions & 4 deletions
Original file line numberDiff line numberDiff line change
@@ -4,7 +4,7 @@
44
#if defined(_STM32_DEF_)
55
// default pwm parameters
66
#define _PWM_RESOLUTION 12 // 12bit
7-
#define _PWM_RANGE 4095.0// 2^12 -1 = 4095
7+
#define _PWM_RANGE 4095.0 // 2^12 -1 = 4095
88
#define _PWM_FREQUENCY 25000 // 25khz
99
#define _PWM_FREQUENCY_MAX 50000 // 50khz
1010

@@ -70,10 +70,14 @@ HardwareTimer* _initPinPWMLow(uint32_t PWM_freq, int ulPin)
7070
sConfigOC.OCMode = TIM_OCMODE_PWM2;
7171
sConfigOC.Pulse = 100;
7272
sConfigOC.OCPolarity = TIM_OCPOLARITY_LOW;
73-
sConfigOC.OCNPolarity = TIM_OCNPOLARITY_HIGH;
7473
sConfigOC.OCFastMode = TIM_OCFAST_DISABLE;
75-
sConfigOC.OCIdleState = TIM_OCIDLESTATE_SET;
76-
sConfigOC.OCNIdleState = TIM_OCNIDLESTATE_RESET;
74+
#if defined(TIM_OCIDLESTATE_SET)
75+
sConfig.OCIdleState = TIM_OCIDLESTATE_SET;
76+
#endif
77+
#if defined(TIM_OCNIDLESTATE_RESET)
78+
sConfig.OCNPolarity = TIM_OCNPOLARITY_HIGH;
79+
sConfig.OCNIdleState = TIM_OCNIDLESTATE_RESET;
80+
#endif
7781
uint32_t channel = STM_PIN_CHANNEL(pinmap_function(pin, PinMap_PWM));
7882
HAL_TIM_PWM_ConfigChannel(&(HardwareTimer_Handle[index]->handle), &sConfigOC, channel);
7983
}
@@ -121,6 +125,8 @@ void _alignPWMTimers(HardwareTimer *HT1,HardwareTimer *HT2,HardwareTimer *HT3,Ha
121125
// configure hardware 6pwm interface only one timer with inverted channels
122126
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)
123127
{
128+
129+
#if !defined(STM32L0xx) // L0 boards dont have hardware 6pwm interface
124130
PinName uhPinName = digitalPinToPinName(pinA_h);
125131
PinName ulPinName = digitalPinToPinName(pinA_l);
126132
PinName vhPinName = digitalPinToPinName(pinB_h);
@@ -157,6 +163,9 @@ HardwareTimer* _initHardware6PWMInterface(uint32_t PWM_freq, float dead_zone, in
157163
HT->refresh();
158164
HT->resume();
159165
return HT;
166+
#else
167+
return nullptr; // return nothing
168+
#endif
160169
}
161170

162171

@@ -176,12 +185,22 @@ int _interfaceType(const int pinA_h, const int pinA_l, const int pinB_h, const
176185
int tim4 = get_timer_index((TIM_TypeDef *)pinmap_peripheral(nameBL, PinMap_PWM));
177186
int tim5 = get_timer_index((TIM_TypeDef *)pinmap_peripheral(nameCH, PinMap_PWM));
178187
int tim6 = get_timer_index((TIM_TypeDef *)pinmap_peripheral(nameCL, PinMap_PWM));
188+
189+
#if defined(STM32L0xx) // L0 boards dont have hardware 6pwm interface
190+
191+
if(tim1 == tim2 && tim3==tim4 && tim5==tim6)
192+
return _SOFTWARE_6PWM; // software 6pwm interface - each pair of high-low side same timer
193+
else
194+
return _ERROR_6PWM; // might be error avoid configuration
195+
#else // the rest of stm32 boards
196+
179197
if(tim1 == tim2 && tim2==tim3 && tim3==tim4 && tim4==tim5 && tim5==tim6)
180198
return _HARDWARE_6PWM; // hardware 6pwm interface - only on timer
181199
else if(tim1 == tim2 && tim3==tim4 && tim5==tim6)
182200
return _SOFTWARE_6PWM; // software 6pwm interface - each pair of high-low side same timer
183201
else
184202
return _ERROR_6PWM; // might be error avoid configuration
203+
#endif
185204
}
186205

187206

0 commit comments

Comments
 (0)