1
1
#include " ../hardware_api.h"
2
2
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
4
9
5
10
// pwm frequency and max duty cycle
6
11
static unsigned long _pwm_frequency;
@@ -101,7 +106,29 @@ void initPWM(uint32_t ulPin, uint32_t pwm_freq){
101
106
if (!PWMEnabled) {
102
107
// PWM Startup code
103
108
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
+
105
132
PWMEnabled = 1 ;
106
133
}
107
134
@@ -112,6 +139,8 @@ void initPWM(uint32_t ulPin, uint32_t pwm_freq){
112
139
g_APinDescription[ulPin].ulPinType ,
113
140
g_APinDescription[ulPin].ulPin ,
114
141
g_APinDescription[ulPin].ulPinConfiguration );
142
+ // PWM_CMR_CALG - center align
143
+ // PWMC_ConfigureChannel(PWM_INTERFACE, chan, PWM_CMR_CPRE_CLKA, PWM_CMR_CALG, 0);
115
144
PWMC_ConfigureChannel (PWM_INTERFACE, chan, PWM_CMR_CPRE_CLKA, 0 , 0 );
116
145
PWMC_SetPeriod (PWM_INTERFACE, chan, _max_pwm_value);
117
146
PWMC_SetDutyCycle (PWM_INTERFACE, chan, 0 );
@@ -123,25 +152,26 @@ void initPWM(uint32_t ulPin, uint32_t pwm_freq){
123
152
124
153
if ((attr & PIN_ATTR_TIMER) == PIN_ATTR_TIMER) { // if timer pin
125
154
// 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 ;
127
156
// Setup Timer for this pin
128
157
ETCChannel channel = g_APinDescription[ulPin].ulTCChannel ;
129
158
uint32_t chNo = channelToChNo[channel];
130
159
uint32_t chA = channelToAB[channel];
131
160
Tc *chTC = channelToTC[channel];
132
161
uint32_t interfaceID = channelToId[channel];
133
162
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
+
145
175
// disable the counter on start
146
176
if (chA){
147
177
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) {
197
227
const uint32_t TC = VARIANT_MCK / 2 / _pwm_frequency;
198
228
// Map value to Timer ranges 0..max_duty_cycle => 0..TC
199
229
// Setup Timer for this pin
200
- ulValue = ulValue * TC;
230
+ ulValue = ulValue * TC ;
201
231
pwm_counter_vals[channel] = ulValue / _max_pwm_value;
202
232
// enable counter
203
233
if (channelToAB[channel])
@@ -297,8 +327,8 @@ void TC8_Handler()
297
327
// - BLDC motor - 3PWM setting
298
328
// - hardware specific
299
329
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
302
332
// save the pwm frequency
303
333
_pwm_frequency = pwm_frequency;
304
334
// cinfigure pwm pins
@@ -314,8 +344,8 @@ void _configure3PWM(long pwm_frequency,const int pinA, const int pinB, const int
314
344
// - Stepper driver - 2PWM setting
315
345
// - hardware specific
316
346
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
319
349
// save the pwm frequency
320
350
_pwm_frequency = pwm_frequency;
321
351
// cinfigure pwm pins
@@ -329,8 +359,8 @@ void _configure2PWM(long pwm_frequency, const int pinA, const int pinB) {
329
359
// - Stepper motor - 4PWM setting
330
360
// - hardware speciffic
331
361
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
334
364
// save the pwm frequency
335
365
_pwm_frequency = pwm_frequency;
336
366
// cinfigure pwm pins
@@ -373,19 +403,4 @@ void _writeDutyCycle2PWM(float dc_a, float dc_b, int pinA, int pinB){
373
403
}
374
404
375
405
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
-
391
406
#endif
0 commit comments