SimpleFOClibrary 2.4.0
Loading...
Searching...
No Matches
atmega328_mcu.cpp
Go to the documentation of this file.
1#include "../../hardware_api.h"
2
3#if defined(__AVR_ATmega328P__) || defined(__AVR_ATmega168__) || defined(__AVR_ATmega328PB__)
4
5#pragma message("")
6#pragma message("SimpleFOC: compiling for Arduino/ATmega328 ATmega168 ATmega328PB")
7#pragma message("")
8
9#define _PWM_FREQUENCY 32000
10#define _PWM_FREQUENCY_MAX 32000
11#define _PWM_FREQUENCY_MIN 4000
12
13// set pwm frequency to 32KHz
14void _pinHighFrequency(const int pin, const long frequency){
15 bool high_fq = false;
16 // set 32kHz frequency if requested freq is higher than the middle of the range (14kHz)
17 // else set the 4kHz
18 if(frequency >= 0.5*(_PWM_FREQUENCY_MAX-_PWM_FREQUENCY_MIN)) high_fq=true;
19 // High PWM frequency
20 // https://www.arxterra.com/9-atmega328p-timers/
21 if (pin == 5 || pin == 6 ) {
22 TCCR0A = ((TCCR0A & 0b11111100) | 0x01); // configure the pwm phase-corrected mode
23 if(high_fq) TCCR0B = ((TCCR0B & 0b11110000) | 0x01); // set prescaler to 1 - 32kHz
24 else TCCR0B = ((TCCR0B & 0b11110000) | 0x02); // set prescaler to 2 - 4kHz
25 }else if (pin == 9 || pin == 10 ){
26 if(high_fq) TCCR1B = ((TCCR1B & 0b11110000) | 0x01); // set prescaler to 1 - 32kHz
27 else TCCR1B = ((TCCR1B & 0b11110000) | 0x02); // set prescaler to 2 - 4kHz
28 }else if (pin == 3 || pin == 11){
29 if(high_fq) TCCR2B = ((TCCR2B & 0b11110000) | 0x01); // set prescaler to 1 - 32kHz
30 else TCCR2B = ((TCCR2B & 0b11110000) | 0x02); // set prescaler to 2 - 4kHz
31 }
32}
33
34void _syncAllTimers(){
35 GTCCR = (1<<TSM)|(1<<PSRASY)|(1<<PSRSYNC); // halt all timers
36 // set all timers to the same value
37 TCNT0 = 0; // set timer0 to 0
38 TCNT1H = 0; // set timer1 high byte to 0
39 TCNT1L = 0; // set timer1 low byte to 0
40 TCNT2 = 0; // set timer2 to 0
41 GTCCR = 0; // release all timers
42}
43
44// function setting the high pwm frequency to the supplied pins
45// - Stepper motor - 2PWM setting
46// - hardware specific
47// supports Arduino/ATmega328
48void* _configure1PWM(long pwm_frequency,const int pinA) {
49 if(!pwm_frequency || !_isset(pwm_frequency) ) pwm_frequency = _PWM_FREQUENCY; // default frequency 32kHz
50 else pwm_frequency = _constrain(pwm_frequency, _PWM_FREQUENCY_MIN, _PWM_FREQUENCY_MAX); // constrain to 4-32kHz max
51 // High PWM frequency
52 // - always max 32kHz
53 _pinHighFrequency(pinA, pwm_frequency);
55 .pins = { pinA },
56 .pwm_frequency = pwm_frequency,
57 .dead_zone = 0.0f
58 };
59 return params;
60}
61// function setting the high pwm frequency to the supplied pins
62// - Stepper motor - 2PWM setting
63// - hardware specific
64// supports Arduino/ATmega328
65void* _configure2PWM(long pwm_frequency,const int pinA, const int pinB) {
66 if(!pwm_frequency || !_isset(pwm_frequency) ) pwm_frequency = _PWM_FREQUENCY; // default frequency 32kHz
67 else pwm_frequency = _constrain(pwm_frequency, _PWM_FREQUENCY_MIN, _PWM_FREQUENCY_MAX); // constrain to 4-32kHz max
68 // High PWM frequency
69 // - always max 32kHz
70 _pinHighFrequency(pinA, pwm_frequency);
71 _pinHighFrequency(pinB, pwm_frequency);
73 .pins = { pinA, pinB },
74 .pwm_frequency = pwm_frequency,
75 .dead_zone = 0.0f
76 };
77 return params;
78}
79
80// function setting the high pwm frequency to the supplied pins
81// - BLDC motor - 3PWM setting
82// - hardware specific
83// supports Arduino/ATmega328
84void* _configure3PWM(long pwm_frequency,const int pinA, const int pinB, const int pinC) {
85 if(!pwm_frequency || !_isset(pwm_frequency) ) pwm_frequency = _PWM_FREQUENCY; // default frequency 32kHz
86 else pwm_frequency = _constrain(pwm_frequency, _PWM_FREQUENCY_MIN, _PWM_FREQUENCY_MAX); // constrain to 4-32kHz max
87 // High PWM frequency
88 // - always max 32kHz
89 _pinHighFrequency(pinA, pwm_frequency);
90 _pinHighFrequency(pinB, pwm_frequency);
91 _pinHighFrequency(pinC, pwm_frequency);
93 .pins = { pinA, pinB, pinC },
94 .pwm_frequency = pwm_frequency,
95 .dead_zone = 0.0f
96 };
97 _syncAllTimers();
98 return params;
99}
100
101
102
103
104// function setting the pwm duty cycle to the hardware
105// - Stepper motor - 2PWM setting
106// - hardware specific
107void _writeDutyCycle1PWM(float dc_a, void* params){
108 // transform duty cycle from [0,1] to [0,255]
109 analogWrite(((GenericDriverParams*)params)->pins[0], 255.0f*dc_a);
110}
111
112
113// function setting the pwm duty cycle to the hardware
114// - Stepper motor - 2PWM setting
115// - hardware specific
116void _writeDutyCycle2PWM(float dc_a, float dc_b, void* params){
117 // transform duty cycle from [0,1] to [0,255]
118 analogWrite(((GenericDriverParams*)params)->pins[0], 255.0f*dc_a);
119 analogWrite(((GenericDriverParams*)params)->pins[1], 255.0f*dc_b);
120}
121
122// function setting the pwm duty cycle to the hardware
123// - BLDC motor - 3PWM setting
124// - hardware specific
125void _writeDutyCycle3PWM(float dc_a, float dc_b, float dc_c, void* params){
126 // transform duty cycle from [0,1] to [0,255]
127 analogWrite(((GenericDriverParams*)params)->pins[0], 255.0f*dc_a);
128 analogWrite(((GenericDriverParams*)params)->pins[1], 255.0f*dc_b);
129 analogWrite(((GenericDriverParams*)params)->pins[2], 255.0f*dc_c);
130}
131
132// function setting the high pwm frequency to the supplied pins
133// - Stepper motor - 4PWM setting
134// - hardware specific
135// supports Arduino/ATmega328
136void* _configure4PWM(long pwm_frequency,const int pin1A, const int pin1B, const int pin2A, const int pin2B) {
137 if(!pwm_frequency || !_isset(pwm_frequency) ) pwm_frequency = _PWM_FREQUENCY; // default frequency 32kHz
138 else pwm_frequency = _constrain(pwm_frequency, _PWM_FREQUENCY_MIN, _PWM_FREQUENCY_MAX); // constrain to 4-32kHz max
139 // High PWM frequency
140 // - always max 32kHz
141 _pinHighFrequency(pin1A,pwm_frequency);
142 _pinHighFrequency(pin1B,pwm_frequency);
143 _pinHighFrequency(pin2A,pwm_frequency);
144 _pinHighFrequency(pin2B,pwm_frequency);
146 .pins = { pin1A, pin1B, pin2A, pin2B },
147 .pwm_frequency = pwm_frequency,
148 .dead_zone = 0.0f
149 };
150 return params;
151}
152
153// function setting the pwm duty cycle to the hardware
154// - Stepper motor - 4PWM setting
155// - hardware specific
156void _writeDutyCycle4PWM(float dc_1a, float dc_1b, float dc_2a, float dc_2b, void* params){
157 // transform duty cycle from [0,1] to [0,255]
158 analogWrite(((GenericDriverParams*)params)->pins[0], 255.0f*dc_1a);
159 analogWrite(((GenericDriverParams*)params)->pins[1], 255.0f*dc_1b);
160 analogWrite(((GenericDriverParams*)params)->pins[2], 255.0f*dc_2a);
161 analogWrite(((GenericDriverParams*)params)->pins[3], 255.0f*dc_2b);
162}
163
164
165// function configuring pair of high-low side pwm channels, 32khz frequency and center aligned pwm
166int _configureComplementaryPair(const int pinH, const int pinL, long frequency) {
167 bool high_fq = false;
168 // set 32kHz frequency if requested freq is higher than the middle of the range (14kHz)
169 // else set the 4kHz
170 if(frequency >= 0.5*(_PWM_FREQUENCY_MAX-_PWM_FREQUENCY_MIN)) high_fq=true;
171
172 // configure pins
173 if( (pinH == 5 && pinL == 6 ) || (pinH == 6 && pinL == 5 ) ){
174 // configure the pwm phase-corrected mode
175 TCCR0A = ((TCCR0A & 0b11111100) | 0x01);
176 // configure complementary pwm on low side
177 if(pinH == 6 ) TCCR0A = 0b10110000 | (TCCR0A & 0b00001111) ;
178 else TCCR0A = 0b11100000 | (TCCR0A & 0b00001111) ;
179 // set frequency
180 if(high_fq) TCCR0B = ((TCCR0B & 0b11110000) | 0x01); // set prescaler to 1 - 32kHz
181 else TCCR0B = ((TCCR0B & 0b11110000) | 0x02); // set prescaler to 2 - 4kHz
182 }else if( (pinH == 9 && pinL == 10 ) || (pinH == 10 && pinL == 9 ) ){
183 // set frequency
184 if(high_fq) TCCR1B = ((TCCR1B & 0b11110000) | 0x01); // set prescaler to 1 - 32kHz
185 else TCCR1B = ((TCCR1B & 0b11110000) | 0x02); // set prescaler to 2 - 4kHz
186 // configure complementary pwm on low side
187 if(pinH == 9 ) TCCR1A = 0b10110000 | (TCCR1A & 0b00001111) ;
188 else TCCR1A = 0b11100000 | (TCCR1A & 0b00001111) ;
189 }else if((pinH == 3 && pinL == 11 ) || (pinH == 11 && pinL == 3 ) ){
190 // set frequency
191 if(high_fq) TCCR2B = ((TCCR2B & 0b11110000) | 0x01); // set prescaler to 1 - 32kHz
192 else TCCR2B = ((TCCR2B & 0b11110000) | 0x02); // set prescaler to 2 - 4kHz
193 // configure complementary pwm on low side
194 if(pinH == 11 ) TCCR2A = 0b10110000 | (TCCR2A & 0b00001111) ;
195 else TCCR2A = 0b11100000 | (TCCR2A & 0b00001111) ;
196 }else{
197 return -1;
198 }
199 return 0;
200}
201
202// Configuring PWM frequency, resolution and alignment
203// - BLDC driver - setting
204// - hardware specific
205// supports Arduino/ATmega328
206void* _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) {
207 if(!pwm_frequency || !_isset(pwm_frequency) ) pwm_frequency = _PWM_FREQUENCY; // default frequency 32kHz
208 else pwm_frequency = _constrain(pwm_frequency, _PWM_FREQUENCY_MIN, _PWM_FREQUENCY_MAX); // constrain to 4-32kHz max
209 // High PWM frequency
210 // - always max 32kHz
211 int ret_flag = 0;
212 ret_flag += _configureComplementaryPair(pinA_h, pinA_l, pwm_frequency);
213 ret_flag += _configureComplementaryPair(pinB_h, pinB_l, pwm_frequency);
214 ret_flag += _configureComplementaryPair(pinC_h, pinC_l, pwm_frequency);
215 if (ret_flag!=0) return SIMPLEFOC_DRIVER_INIT_FAILED;
218 .pwm_frequency = pwm_frequency,
219 .dead_zone = dead_zone
220 };
221 _syncAllTimers();
222 return params;
223}
224
225// function setting the
226void _setPwmPair(int pinH, int pinL, float val, int dead_time, PhaseState ps)
227{
228 int pwm_h = _constrain(val-dead_time/2,0,255);
229 int pwm_l = _constrain(val+dead_time/2,0,255);
230 // determine the phase state and set the pwm accordingly
231 // deactivate phases if needed
232 if((ps == PhaseState::PHASE_OFF) || (ps == PhaseState::PHASE_LO)){
233 digitalWrite(pinH, LOW);
234 }else{
235 analogWrite(pinH, pwm_h);
236 }
237 if((ps == PhaseState::PHASE_OFF) || (ps == PhaseState::PHASE_HI)){
238 digitalWrite(pinL, LOW);
239 }else{
240 if(pwm_l == 255 || pwm_l == 0)
241 digitalWrite(pinL, pwm_l ? LOW : HIGH);
242 else
243 analogWrite(pinL, pwm_l);
244 }
245
246
247}
248
249// Function setting the duty cycle to the pwm pin (ex. analogWrite())
250// - BLDC driver - 6PWM setting
251// - hardware specific
252// supports Arduino/ATmega328
253void _writeDutyCycle6PWM(float dc_a, float dc_b, float dc_c, PhaseState *phase_state, void* params){
254 _setPwmPair(((GenericDriverParams*)params)->pins[0], ((GenericDriverParams*)params)->pins[1], dc_a*255.0, ((GenericDriverParams*)params)->dead_zone*255.0, phase_state[0]);
255 _setPwmPair(((GenericDriverParams*)params)->pins[2], ((GenericDriverParams*)params)->pins[3], dc_b*255.0, ((GenericDriverParams*)params)->dead_zone*255.0, phase_state[1]);
256 _setPwmPair(((GenericDriverParams*)params)->pins[4], ((GenericDriverParams*)params)->pins[5], dc_c*255.0, ((GenericDriverParams*)params)->dead_zone*255.0, phase_state[2]);
257}
258
259#endif
PhaseState
Definition FOCDriver.h:7
@ PHASE_HI
Definition FOCDriver.h:10
@ PHASE_LO
Definition FOCDriver.h:11
@ PHASE_OFF
Definition FOCDriver.h:8
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 * _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)
void * _configure2PWM(long pwm_frequency, const int pinA, const int pinB)
void _writeDutyCycle2PWM(float dc_a, float dc_b, void *params)
void _writeDutyCycle1PWM(float dc_a, void *params)
#define SIMPLEFOC_DRIVER_INIT_FAILED
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 _writeDutyCycle6PWM(float dc_a, float dc_b, float dc_c, PhaseState *phase_state, void *params)
void * _configure1PWM(long pwm_frequency, const int pinA)
void _writeDutyCycle3PWM(float dc_a, float dc_b, float dc_c, void *params)
float const int const int const int pinB_h
float const int const int const int const int pinB_l
const int const int pin1B
const int const int const int pin2A
float const int const int const int const int const int pinC_h
float float float dc_2b
float float PhaseState * phase_state
float const int const int const int const int const int const int pinC_l
float const int const int pinA_l
analogWrite(((GenericDriverParams *) params) ->pins[1], 255.0f *dc_b)
const int const int const int const int pin2B
#define _isset(a)
Definition foc_utils.h:13
#define _constrain(amt, low, high)
Definition foc_utils.h:11