Explorar el Código

Clean up fast_pwm.cpp

Scott Lahteine hace 6 años
padre
commit
47fd74a98d
Se han modificado 1 ficheros con 234 adiciones y 213 borrados
  1. 234
    213
      Marlin/src/HAL/HAL_AVR/fast_pwm.cpp

+ 234
- 213
Marlin/src/HAL/HAL_AVR/fast_pwm.cpp Ver fichero

@@ -1,250 +1,271 @@
1
-#ifdef __AVR__
2
-
3
-#include "../../inc/MarlinConfigPre.h"
4 1
 /**
5
- * get_pwm_timer
6
- *  Grabs timer information and registers of the provided pin
7
- *  returns Timer struct containing this information
8
- *  Used by set_pwm_frequency, set_pwm_duty
2
+ * Marlin 3D Printer Firmware
3
+ * Copyright (C) 2019 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
4
+ *
5
+ * Based on Sprinter and grbl.
6
+ * Copyright (C) 2011 Camiel Gubbels / Erik van der Zalm
7
+ *
8
+ * This program is free software: you can redistribute it and/or modify
9
+ * it under the terms of the GNU General Public License as published by
10
+ * the Free Software Foundation, either version 3 of the License, or
11
+ * (at your option) any later version.
12
+ *
13
+ * This program is distributed in the hope that it will be useful,
14
+ * but WITHOUT ANY WARRANTY; without even the implied warranty of
15
+ * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the
16
+ * GNU General Public License for more details.
17
+ *
18
+ * You should have received a copy of the GNU General Public License
19
+ * along with this program.  If not, see <http://www.gnu.org/licenses/>.
9 20
  *
10 21
  */
22
+#ifdef __AVR__
23
+
24
+#include "../../inc/MarlinConfigPre.h"
11 25
 
12 26
 #if ENABLED(FAST_PWM_FAN)
27
+
13 28
 #include "HAL.h"
14 29
 
15
-  struct Timer {
16
-    volatile uint8_t* TCCRnQ[3];  // max 3 TCCR registers per timer
17
-    volatile uint16_t* OCRnQ[3];  // max 3 OCR registers per timer
18
-    volatile uint16_t* ICRn;      // max 1 ICR register per timer
19
-    uint8_t n;                    // the timer number [0->5]
20
-    uint8_t q;                    // the timer output [0->2] (A->C)
21
-  };
30
+struct Timer {
31
+  volatile uint8_t* TCCRnQ[3];  // max 3 TCCR registers per timer
32
+  volatile uint16_t* OCRnQ[3];  // max 3 OCR registers per timer
33
+  volatile uint16_t* ICRn;      // max 1 ICR register per timer
34
+  uint8_t n;                    // the timer number [0->5]
35
+  uint8_t q;                    // the timer output [0->2] (A->C)
36
+};
22 37
 
23
-  Timer get_pwm_timer(pin_t pin) {
24
-    uint8_t q = 0;
25
-    switch (digitalPinToTimer(pin)) {
26
-      // Protect reserved timers (TIMER0 & TIMER1)
27
-      #ifdef TCCR0A
28
-        #if !AVR_AT90USB1286_FAMILY
29
-          case TIMER0A:
30
-        #endif
31
-        case TIMER0B:
32
-      #endif
33
-      #ifdef TCCR1A
34
-        case TIMER1A: case TIMER1B:
38
+/**
39
+ * get_pwm_timer
40
+ *  Get the timer information and register of the provided pin.
41
+ *  Return a Timer struct containing this information.
42
+ *  Used by set_pwm_frequency, set_pwm_duty
43
+ */
44
+Timer get_pwm_timer(const pin_t pin) {
45
+  uint8_t q = 0;
46
+  switch (digitalPinToTimer(pin)) {
47
+    // Protect reserved timers (TIMER0 & TIMER1)
48
+    #ifdef TCCR0A
49
+      #if !AVR_AT90USB1286_FAMILY
50
+        case TIMER0A:
35 51
       #endif
36
-                                          break;
37
-      #if defined(TCCR2) || defined(TCCR2A)
38
-        #ifdef TCCR2
39
-          case TIMER2: {
52
+      case TIMER0B:
53
+    #endif
54
+    #ifdef TCCR1A
55
+      case TIMER1A: case TIMER1B:
56
+    #endif
57
+                                        break;
58
+    #if defined(TCCR2) || defined(TCCR2A)
59
+      #ifdef TCCR2
60
+        case TIMER2: {
61
+          Timer timer = {
62
+            /*TCCRnQ*/  { &TCCR2, nullptr, nullptr},
63
+            /*OCRnQ*/   { (uint16_t*)&OCR2, nullptr, nullptr},
64
+            /*ICRn*/      nullptr,
65
+            /*n, q*/      2, 0
66
+          };
67
+        }
68
+      #elif defined TCCR2A
69
+        #if ENABLED(USE_OCR2A_AS_TOP)
70
+          case TIMER2A:   break; // protect TIMER2A
71
+          case TIMER2B: {
72
+            Timer timer = {
73
+              /*TCCRnQ*/  { &TCCR2A,  &TCCR2B,  nullptr},
74
+              /*OCRnQ*/   { (uint16_t*)&OCR2A, (uint16_t*)&OCR2B, nullptr},
75
+              /*ICRn*/      nullptr,
76
+              /*n, q*/      2, 1
77
+            };
78
+            return timer;
79
+          }
80
+        #else
81
+          case TIMER2B:   ++q;
82
+          case TIMER2A: {
40 83
             Timer timer = {
41
-              /*TCCRnQ*/  { &TCCR2, nullptr, nullptr},
42
-              /*OCRnQ*/   { (uint16_t*)&OCR2, nullptr, nullptr},
84
+              /*TCCRnQ*/  { &TCCR2A,  &TCCR2B,  nullptr},
85
+              /*OCRnQ*/   { (uint16_t*)&OCR2A, (uint16_t*)&OCR2B, nullptr},
43 86
               /*ICRn*/      nullptr,
44
-              /*n, q*/      2, 0
87
+                            2, q
45 88
             };
89
+            return timer;
46 90
           }
47
-        #elif defined TCCR2A
48
-          #if ENABLED(USE_OCR2A_AS_TOP)
49
-            case TIMER2A:   break; // protect TIMER2A
50
-            case TIMER2B: {
51
-              Timer timer = {
52
-                /*TCCRnQ*/  { &TCCR2A,  &TCCR2B,  nullptr},
53
-                /*OCRnQ*/   { (uint16_t*)&OCR2A, (uint16_t*)&OCR2B, nullptr},
54
-                /*ICRn*/      nullptr,
55
-                /*n, q*/      2, 1
56
-              };
57
-              return timer;
58
-            }
59
-          #else
60
-            case TIMER2B:   ++q;
61
-            case TIMER2A: {
62
-              Timer timer = {
63
-                /*TCCRnQ*/  { &TCCR2A,  &TCCR2B,  nullptr},
64
-                /*OCRnQ*/   { (uint16_t*)&OCR2A, (uint16_t*)&OCR2B, nullptr},
65
-                /*ICRn*/      nullptr,
66
-                              2, q
67
-              };
68
-              return timer;
69
-            }
70
-          #endif
71 91
         #endif
72 92
       #endif
73
-      #ifdef TCCR3A
74
-        case TIMER3C:   ++q;
75
-        case TIMER3B:   ++q;
76
-        case TIMER3A: {
77
-          Timer timer = {
78
-            /*TCCRnQ*/  { &TCCR3A,  &TCCR3B,  &TCCR3C},
79
-            /*OCRnQ*/   { &OCR3A,   &OCR3B,   &OCR3C},
80
-            /*ICRn*/      &ICR3,
81
-            /*n, q*/      3, q
82
-          };
83
-          return timer;
84
-        }
85
-      #endif
86
-      #ifdef TCCR4A
87
-        case TIMER4C:   ++q;
88
-        case TIMER4B:   ++q;
89
-        case TIMER4A: {
90
-          Timer timer = {
91
-            /*TCCRnQ*/  { &TCCR4A,  &TCCR4B,  &TCCR4C},
92
-            /*OCRnQ*/   { &OCR4A,   &OCR4B,   &OCR4C},
93
-            /*ICRn*/      &ICR4,
94
-            /*n, q*/      4, q
95
-          };
96
-          return timer;
97
-        }
98
-      #endif
99
-      #ifdef TCCR5A
100
-        case TIMER5C:   ++q;
101
-        case TIMER5B:   ++q;
102
-        case TIMER5A: {
103
-          Timer timer = {
104
-            /*TCCRnQ*/  { &TCCR5A,  &TCCR5B,  &TCCR5C},
105
-            /*OCRnQ*/   { &OCR5A,   &OCR5B,   &OCR5C },
106
-            /*ICRn*/      &ICR5,
107
-            /*n, q*/      5, q
108
-          };
109
-          return timer;
110
-        }
111
-      #endif
112
-    }
113
-    Timer timer = {
114
-        /*TCCRnQ*/  { nullptr, nullptr, nullptr},
115
-        /*OCRnQ*/   { nullptr, nullptr, nullptr},
116
-        /*ICRn*/      nullptr,
117
-                      0, 0
118
-    };
119
-    return timer;
93
+    #endif
94
+    #ifdef TCCR3A
95
+      case TIMER3C:   ++q;
96
+      case TIMER3B:   ++q;
97
+      case TIMER3A: {
98
+        Timer timer = {
99
+          /*TCCRnQ*/  { &TCCR3A,  &TCCR3B,  &TCCR3C},
100
+          /*OCRnQ*/   { &OCR3A,   &OCR3B,   &OCR3C},
101
+          /*ICRn*/      &ICR3,
102
+          /*n, q*/      3, q
103
+        };
104
+        return timer;
105
+      }
106
+    #endif
107
+    #ifdef TCCR4A
108
+      case TIMER4C:   ++q;
109
+      case TIMER4B:   ++q;
110
+      case TIMER4A: {
111
+        Timer timer = {
112
+          /*TCCRnQ*/  { &TCCR4A,  &TCCR4B,  &TCCR4C},
113
+          /*OCRnQ*/   { &OCR4A,   &OCR4B,   &OCR4C},
114
+          /*ICRn*/      &ICR4,
115
+          /*n, q*/      4, q
116
+        };
117
+        return timer;
118
+      }
119
+    #endif
120
+    #ifdef TCCR5A
121
+      case TIMER5C:   ++q;
122
+      case TIMER5B:   ++q;
123
+      case TIMER5A: {
124
+        Timer timer = {
125
+          /*TCCRnQ*/  { &TCCR5A,  &TCCR5B,  &TCCR5C},
126
+          /*OCRnQ*/   { &OCR5A,   &OCR5B,   &OCR5C },
127
+          /*ICRn*/      &ICR5,
128
+          /*n, q*/      5, q
129
+        };
130
+        return timer;
131
+      }
132
+    #endif
120 133
   }
134
+  Timer timer = {
135
+      /*TCCRnQ*/  { nullptr, nullptr, nullptr},
136
+      /*OCRnQ*/   { nullptr, nullptr, nullptr},
137
+      /*ICRn*/      nullptr,
138
+                    0, 0
139
+  };
140
+  return timer;
141
+}
121 142
 
122
-  void set_pwm_frequency(const pin_t pin, int f_desired) {
123
-    Timer timer = get_pwm_timer(pin);
124
-    if (timer.n == 0) return; // Don't proceed if protected timer or not recognised
125
-    uint16_t size;
126
-    if (timer.n == 2) size = 255; else size = 65535;
143
+void set_pwm_frequency(const pin_t pin, int f_desired) {
144
+  Timer timer = get_pwm_timer(pin);
145
+  if (timer.n == 0) return; // Don't proceed if protected timer or not recognised
146
+  uint16_t size;
147
+  if (timer.n == 2) size = 255; else size = 65535;
127 148
 
128
-    uint16_t res = 255;   // resolution (TOP value)
129
-    uint8_t j = 0;        // prescaler index
130
-    uint8_t wgm = 1;      // waveform generation mode
149
+  uint16_t res = 255;   // resolution (TOP value)
150
+  uint8_t j = 0;        // prescaler index
151
+  uint8_t wgm = 1;      // waveform generation mode
131 152
 
132
-    // Calculating the prescaler and resolution to use to achieve closest frequency
133
-    if (f_desired != 0) {
134
-      int f = (F_CPU) / (2 * 1024 * size) + 1; // Initialize frequency as lowest (non-zero) achievable
135
-      uint16_t prescaler[] = { 0, 1, 8, /*TIMER2 ONLY*/32, 64, /*TIMER2 ONLY*/128, 256, 1024 };
153
+  // Calculating the prescaler and resolution to use to achieve closest frequency
154
+  if (f_desired != 0) {
155
+    int f = (F_CPU) / (2 * 1024 * size) + 1; // Initialize frequency as lowest (non-zero) achievable
156
+    uint16_t prescaler[] = { 0, 1, 8, /*TIMER2 ONLY*/32, 64, /*TIMER2 ONLY*/128, 256, 1024 };
136 157
 
137
-      // loop over prescaler values
138
-      for (uint8_t i = 1; i < 8; i++) {
139
-        uint16_t res_temp_fast = 255, res_temp_phase_correct = 255;
140
-        if (timer.n == 2) {
141
-          // No resolution calculation for TIMER2 unless enabled USE_OCR2A_AS_TOP
142
-          #if ENABLED(USE_OCR2A_AS_TOP)
143
-            const uint16_t rtf = (F_CPU) / (prescaler[i] * f_desired);
144
-            res_temp_fast = rtf - 1;
145
-            res_temp_phase_correct = rtf / 2;
146
-          #endif
147
-        }
148
-        else {
149
-          // Skip TIMER2 specific prescalers when not TIMER2
150
-          if (i == 3 || i == 5) continue;
158
+    // loop over prescaler values
159
+    for (uint8_t i = 1; i < 8; i++) {
160
+      uint16_t res_temp_fast = 255, res_temp_phase_correct = 255;
161
+      if (timer.n == 2) {
162
+        // No resolution calculation for TIMER2 unless enabled USE_OCR2A_AS_TOP
163
+        #if ENABLED(USE_OCR2A_AS_TOP)
151 164
           const uint16_t rtf = (F_CPU) / (prescaler[i] * f_desired);
152 165
           res_temp_fast = rtf - 1;
153 166
           res_temp_phase_correct = rtf / 2;
154
-        }
167
+        #endif
168
+      }
169
+      else {
170
+        // Skip TIMER2 specific prescalers when not TIMER2
171
+        if (i == 3 || i == 5) continue;
172
+        const uint16_t rtf = (F_CPU) / (prescaler[i] * f_desired);
173
+        res_temp_fast = rtf - 1;
174
+        res_temp_phase_correct = rtf / 2;
175
+      }
155 176
 
156
-        LIMIT(res_temp_fast, 1u, size);
157
-        LIMIT(res_temp_phase_correct, 1u, size);
158
-        // Calculate frequencies of test prescaler and resolution values
159
-        const int f_temp_fast = (F_CPU) / (prescaler[i] * (1 + res_temp_fast)),
160
-                  f_temp_phase_correct = (F_CPU) / (2 * prescaler[i] * res_temp_phase_correct),
161
-                  f_diff = ABS(f - f_desired),
162
-                  f_fast_diff = ABS(f_temp_fast - f_desired),
163
-                  f_phase_diff = ABS(f_temp_phase_correct - f_desired);
164
-
165
-        // If FAST values are closest to desired f
166
-        if (f_fast_diff < f_diff && f_fast_diff <= f_phase_diff) {
167
-          // Remember this combination
168
-          f = f_temp_fast;
169
-          res = res_temp_fast;
170
-          j = i;
171
-          // Set the Wave Generation Mode to FAST PWM
172
-          if (timer.n == 2) {
173
-            wgm = (
174
-              #if ENABLED(USE_OCR2A_AS_TOP)
175
-                WGM2_FAST_PWM_OCR2A
176
-              #else
177
-                WGM2_FAST_PWM
178
-              #endif
179
-            );
180
-          }
181
-          else wgm = WGM_FAST_PWM_ICRn;
177
+      LIMIT(res_temp_fast, 1u, size);
178
+      LIMIT(res_temp_phase_correct, 1u, size);
179
+      // Calculate frequencies of test prescaler and resolution values
180
+      const int f_temp_fast = (F_CPU) / (prescaler[i] * (1 + res_temp_fast)),
181
+                f_temp_phase_correct = (F_CPU) / (2 * prescaler[i] * res_temp_phase_correct),
182
+                f_diff = ABS(f - f_desired),
183
+                f_fast_diff = ABS(f_temp_fast - f_desired),
184
+                f_phase_diff = ABS(f_temp_phase_correct - f_desired);
185
+
186
+      // If FAST values are closest to desired f
187
+      if (f_fast_diff < f_diff && f_fast_diff <= f_phase_diff) {
188
+        // Remember this combination
189
+        f = f_temp_fast;
190
+        res = res_temp_fast;
191
+        j = i;
192
+        // Set the Wave Generation Mode to FAST PWM
193
+        if (timer.n == 2) {
194
+          wgm = (
195
+            #if ENABLED(USE_OCR2A_AS_TOP)
196
+              WGM2_FAST_PWM_OCR2A
197
+            #else
198
+              WGM2_FAST_PWM
199
+            #endif
200
+          );
182 201
         }
183
-        // If PHASE CORRECT values are closes to desired f
184
-        else if (f_phase_diff < f_diff) {
185
-          f = f_temp_phase_correct;
186
-          res = res_temp_phase_correct;
187
-          j = i;
188
-          // Set the Wave Generation Mode to PWM PHASE CORRECT
189
-          if (timer.n == 2) {
190
-            wgm = (
191
-              #if ENABLED(USE_OCR2A_AS_TOP)
192
-                WGM2_PWM_PC_OCR2A
193
-              #else
194
-                WGM2_PWM_PC
195
-              #endif
196
-            );
197
-          }
198
-          else wgm = WGM_PWM_PC_ICRn;
202
+        else wgm = WGM_FAST_PWM_ICRn;
203
+      }
204
+      // If PHASE CORRECT values are closes to desired f
205
+      else if (f_phase_diff < f_diff) {
206
+        f = f_temp_phase_correct;
207
+        res = res_temp_phase_correct;
208
+        j = i;
209
+        // Set the Wave Generation Mode to PWM PHASE CORRECT
210
+        if (timer.n == 2) {
211
+          wgm = (
212
+            #if ENABLED(USE_OCR2A_AS_TOP)
213
+              WGM2_PWM_PC_OCR2A
214
+            #else
215
+              WGM2_PWM_PC
216
+            #endif
217
+          );
199 218
         }
219
+        else wgm = WGM_PWM_PC_ICRn;
200 220
       }
201 221
     }
202
-    _SET_WGMnQ(timer.TCCRnQ, wgm);
203
-    _SET_CSn(timer.TCCRnQ, j);
204
-
205
-    if (timer.n == 2) {
206
-      #if ENABLED(USE_OCR2A_AS_TOP)
207
-        _SET_OCRnQ(timer.OCRnQ, 0, res);  // Set OCR2A value (TOP) = res
208
-      #endif
209
-    }
210
-    else
211
-      _SET_ICRn(timer.ICRn, res);         // Set ICRn value (TOP) = res
212 222
   }
223
+  _SET_WGMnQ(timer.TCCRnQ, wgm);
224
+  _SET_CSn(timer.TCCRnQ, j);
213 225
 
214
-  void set_pwm_duty(const pin_t pin, const uint16_t v, const uint16_t v_size/*=255*/, const bool invert/*=false*/) {
215
-    // If v is 0 or v_size (max), digitalWrite to LOW or HIGH.
216
-    // Note that digitalWrite also disables pwm output for us (sets COM bit to 0)
217
-    if (v == 0)
218
-      digitalWrite(pin, invert);
219
-    else if (v == v_size)
220
-      digitalWrite(pin, !invert);
221
-    else {
222
-      Timer timer = get_pwm_timer(pin);
223
-      if (timer.n == 0) return; // Don't proceed if protected timer or not recognised
224
-      // Set compare output mode to CLEAR -> SET or SET -> CLEAR (if inverted)
225
-      _SET_COMnQ(timer.TCCRnQ, (timer.q
226
-          #ifdef TCCR2
227
-            + (timer.q == 2) // COM20 is on bit 4 of TCCR2, thus requires q + 1 in the macro
228
-          #endif
229
-        ), COM_CLEAR_SET + invert
230
-      );
226
+  if (timer.n == 2) {
227
+    #if ENABLED(USE_OCR2A_AS_TOP)
228
+      _SET_OCRnQ(timer.OCRnQ, 0, res);  // Set OCR2A value (TOP) = res
229
+    #endif
230
+  }
231
+  else
232
+    _SET_ICRn(timer.ICRn, res);         // Set ICRn value (TOP) = res
233
+}
231 234
 
232
-      uint16_t top;
233
-      if (timer.n == 2) { // if TIMER2
234
-        top = (
235
-          #if ENABLED(USE_OCR2A_AS_TOP)
236
-            *timer.OCRnQ[0] // top = OCR2A
237
-          #else
238
-            255 // top = 0xFF (max)
239
-          #endif
240
-        );
241
-      }
242
-      else
243
-        top = *timer.ICRn; // top = ICRn
235
+void set_pwm_duty(const pin_t pin, const uint16_t v, const uint16_t v_size/*=255*/, const bool invert/*=false*/) {
236
+  // If v is 0 or v_size (max), digitalWrite to LOW or HIGH.
237
+  // Note that digitalWrite also disables pwm output for us (sets COM bit to 0)
238
+  if (v == 0)
239
+    digitalWrite(pin, invert);
240
+  else if (v == v_size)
241
+    digitalWrite(pin, !invert);
242
+  else {
243
+    Timer timer = get_pwm_timer(pin);
244
+    if (timer.n == 0) return; // Don't proceed if protected timer or not recognised
245
+    // Set compare output mode to CLEAR -> SET or SET -> CLEAR (if inverted)
246
+    _SET_COMnQ(timer.TCCRnQ, (timer.q
247
+        #ifdef TCCR2
248
+          + (timer.q == 2) // COM20 is on bit 4 of TCCR2, thus requires q + 1 in the macro
249
+        #endif
250
+      ), COM_CLEAR_SET + invert
251
+    );
244 252
 
245
-      _SET_OCRnQ(timer.OCRnQ, timer.q, v * float(top / v_size)); // Scale 8/16-bit v to top value
253
+    uint16_t top;
254
+    if (timer.n == 2) { // if TIMER2
255
+      top = (
256
+        #if ENABLED(USE_OCR2A_AS_TOP)
257
+          *timer.OCRnQ[0] // top = OCR2A
258
+        #else
259
+          255 // top = 0xFF (max)
260
+        #endif
261
+      );
246 262
     }
263
+    else
264
+      top = *timer.ICRn; // top = ICRn
265
+
266
+    _SET_OCRnQ(timer.OCRnQ, timer.q, v * float(top / v_size)); // Scale 8/16-bit v to top value
247 267
   }
268
+}
248 269
 
249 270
 #endif // FAST_PWM_FAN
250 271
 #endif // __AVR__

Loading…
Cancelar
Guardar