Browse Source

🎨 Rename HAL timer elements

Scott Lahteine 3 years ago
parent
commit
0539e870de
51 changed files with 384 additions and 404 deletions
  1. 8
    8
      Marlin/src/HAL/AVR/timers.h
  2. 3
    3
      Marlin/src/HAL/DUE/Tone.cpp
  3. 8
    8
      Marlin/src/HAL/DUE/timers.cpp
  4. 24
    24
      Marlin/src/HAL/DUE/timers.h
  5. 3
    3
      Marlin/src/HAL/ESP32/HAL.cpp
  6. 3
    3
      Marlin/src/HAL/ESP32/Tone.cpp
  7. 9
    9
      Marlin/src/HAL/ESP32/timers.cpp
  8. 16
    16
      Marlin/src/HAL/ESP32/timers.h
  9. 11
    12
      Marlin/src/HAL/LINUX/timers.h
  10. 2
    2
      Marlin/src/HAL/LPC1768/timers.cpp
  11. 31
    31
      Marlin/src/HAL/LPC1768/timers.h
  12. 13
    13
      Marlin/src/HAL/NATIVE_SIM/timers.h
  13. 4
    4
      Marlin/src/HAL/SAMD51/Servo.cpp
  14. 1
    1
      Marlin/src/HAL/SAMD51/inc/SanityCheck.h
  15. 10
    10
      Marlin/src/HAL/SAMD51/timers.cpp
  16. 31
    31
      Marlin/src/HAL/SAMD51/timers.h
  17. 5
    6
      Marlin/src/HAL/STM32/fast_pwm.cpp
  18. 7
    7
      Marlin/src/HAL/STM32/timers.cpp
  19. 11
    11
      Marlin/src/HAL/STM32/timers.h
  20. 2
    2
      Marlin/src/HAL/STM32F1/HAL.h
  21. 9
    9
      Marlin/src/HAL/STM32F1/Servo.cpp
  22. 4
    5
      Marlin/src/HAL/STM32F1/fast_pwm.cpp
  23. 13
    17
      Marlin/src/HAL/STM32F1/timers.cpp
  24. 35
    35
      Marlin/src/HAL/STM32F1/timers.h
  25. 10
    10
      Marlin/src/HAL/TEENSY31_32/timers.cpp
  26. 17
    17
      Marlin/src/HAL/TEENSY31_32/timers.h
  27. 10
    10
      Marlin/src/HAL/TEENSY35_36/timers.cpp
  28. 17
    17
      Marlin/src/HAL/TEENSY35_36/timers.h
  29. 10
    18
      Marlin/src/HAL/TEENSY40_41/timers.cpp
  30. 17
    21
      Marlin/src/HAL/TEENSY40_41/timers.h
  31. 2
    2
      Marlin/src/feature/easythreed_ui.cpp
  32. 1
    1
      Marlin/src/module/planner.h
  33. 10
    10
      Marlin/src/module/stepper.cpp
  34. 3
    3
      Marlin/src/module/temperature.cpp
  35. 1
    2
      Marlin/src/pins/sam/pins_ARCHIM1.h
  36. 2
    2
      Marlin/src/pins/stm32f0/pins_MALYAN_M300.h
  37. 1
    1
      Marlin/src/pins/stm32f1/pins_FLSUN_HISPEED.h
  38. 2
    2
      Marlin/src/pins/stm32f1/pins_MALYAN_M200.h
  39. 1
    1
      Marlin/src/pins/stm32f1/pins_MKS_ROBIN_E3P.h
  40. 1
    1
      Marlin/src/pins/stm32f1/pins_MKS_ROBIN_NANO_V2.h
  41. 1
    1
      Marlin/src/pins/stm32f1/pins_MKS_ROBIN_NANO_common.h
  42. 1
    1
      Marlin/src/pins/stm32f4/pins_BTT_OCTOPUS_V1_common.h
  43. 1
    1
      Marlin/src/pins/stm32f4/pins_BTT_SKR_V2_0_common.h
  44. 2
    2
      Marlin/src/pins/stm32f4/pins_FLYF407ZG.h
  45. 2
    2
      Marlin/src/pins/stm32f4/pins_LERDGE_S.h
  46. 2
    2
      Marlin/src/pins/stm32f4/pins_LERDGE_X.h
  47. 1
    1
      Marlin/src/pins/stm32f4/pins_MKS_MONSTER8.h
  48. 1
    1
      Marlin/src/pins/stm32f4/pins_MKS_ROBIN_NANO_V3_common.h
  49. 2
    2
      Marlin/src/pins/stm32f4/pins_RUMBA32_common.h
  50. 2
    2
      Marlin/src/pins/stm32f7/pins_NUCLEO_F767ZI.h
  51. 1
    1
      Marlin/src/pins/stm32f7/pins_REMRAM_V1.h

+ 8
- 8
Marlin/src/HAL/AVR/timers.h View File

34
 
34
 
35
 #define HAL_TIMER_RATE          ((F_CPU) / 8)    // i.e., 2MHz or 2.5MHz
35
 #define HAL_TIMER_RATE          ((F_CPU) / 8)    // i.e., 2MHz or 2.5MHz
36
 
36
 
37
-#ifndef STEP_TIMER_NUM
38
-  #define STEP_TIMER_NUM        1
37
+#ifndef MF_TIMER_STEP
38
+  #define MF_TIMER_STEP         1
39
 #endif
39
 #endif
40
-#ifndef PULSE_TIMER_NUM
41
-  #define PULSE_TIMER_NUM       STEP_TIMER_NUM
40
+#ifndef MF_TIMER_PULSE
41
+  #define MF_TIMER_PULSE        MF_TIMER_STEP
42
 #endif
42
 #endif
43
-#ifndef TEMP_TIMER_NUM
44
-  #define TEMP_TIMER_NUM        0
43
+#ifndef MF_TIMER_TEMP
44
+  #define MF_TIMER_TEMP         0
45
 #endif
45
 #endif
46
 
46
 
47
 #define TEMP_TIMER_FREQUENCY    ((F_CPU) / 64.0 / 256.0)
47
 #define TEMP_TIMER_FREQUENCY    ((F_CPU) / 64.0 / 256.0)
64
 
64
 
65
 FORCE_INLINE void HAL_timer_start(const uint8_t timer_num, const uint32_t) {
65
 FORCE_INLINE void HAL_timer_start(const uint8_t timer_num, const uint32_t) {
66
   switch (timer_num) {
66
   switch (timer_num) {
67
-    case STEP_TIMER_NUM:
67
+    case MF_TIMER_STEP:
68
       // waveform generation = 0100 = CTC
68
       // waveform generation = 0100 = CTC
69
       SET_WGM(1, CTC_OCRnA);
69
       SET_WGM(1, CTC_OCRnA);
70
 
70
 
84
       TCNT1 = 0;
84
       TCNT1 = 0;
85
       break;
85
       break;
86
 
86
 
87
-    case TEMP_TIMER_NUM:
87
+    case MF_TIMER_TEMP:
88
       // Use timer0 for temperature measurement
88
       // Use timer0 for temperature measurement
89
       // Interleave temperature interrupt with millies interrupt
89
       // Interleave temperature interrupt with millies interrupt
90
       OCR0B = 128;
90
       OCR0B = 128;

+ 3
- 3
Marlin/src/HAL/DUE/Tone.cpp View File

38
 void tone(const pin_t _pin, const unsigned int frequency, const unsigned long duration) {
38
 void tone(const pin_t _pin, const unsigned int frequency, const unsigned long duration) {
39
   tone_pin = _pin;
39
   tone_pin = _pin;
40
   toggles = 2 * frequency * duration / 1000;
40
   toggles = 2 * frequency * duration / 1000;
41
-  HAL_timer_start(TONE_TIMER_NUM, 2 * frequency);
41
+  HAL_timer_start(MF_TIMER_TONE, 2 * frequency);
42
 }
42
 }
43
 
43
 
44
 void noTone(const pin_t _pin) {
44
 void noTone(const pin_t _pin) {
45
-  HAL_timer_disable_interrupt(TONE_TIMER_NUM);
45
+  HAL_timer_disable_interrupt(MF_TIMER_TONE);
46
   extDigitalWrite(_pin, LOW);
46
   extDigitalWrite(_pin, LOW);
47
 }
47
 }
48
 
48
 
49
 HAL_TONE_TIMER_ISR() {
49
 HAL_TONE_TIMER_ISR() {
50
   static uint8_t pin_state = 0;
50
   static uint8_t pin_state = 0;
51
-  HAL_timer_isr_prologue(TONE_TIMER_NUM);
51
+  HAL_timer_isr_prologue(MF_TIMER_TONE);
52
 
52
 
53
   if (toggles) {
53
   if (toggles) {
54
     toggles--;
54
     toggles--;

+ 8
- 8
Marlin/src/HAL/DUE/timers.cpp View File

42
 // Private Variables
42
 // Private Variables
43
 // ------------------------
43
 // ------------------------
44
 
44
 
45
-const tTimerConfig TimerConfig [NUM_HARDWARE_TIMERS] = {
45
+const tTimerConfig timer_config[NUM_HARDWARE_TIMERS] = {
46
   { TC0, 0, TC0_IRQn,  3}, // 0 - [servo timer5]
46
   { TC0, 0, TC0_IRQn,  3}, // 0 - [servo timer5]
47
   { TC0, 1, TC1_IRQn,  0}, // 1
47
   { TC0, 1, TC1_IRQn,  0}, // 1
48
   { TC0, 2, TC2_IRQn,  2}, // 2 - stepper
48
   { TC0, 2, TC2_IRQn,  2}, // 2 - stepper
66
 */
66
 */
67
 
67
 
68
 void HAL_timer_start(const uint8_t timer_num, const uint32_t frequency) {
68
 void HAL_timer_start(const uint8_t timer_num, const uint32_t frequency) {
69
-  Tc *tc = TimerConfig[timer_num].pTimerRegs;
70
-  IRQn_Type irq = TimerConfig[timer_num].IRQ_Id;
71
-  uint32_t channel = TimerConfig[timer_num].channel;
69
+  Tc *tc = timer_config[timer_num].pTimerRegs;
70
+  IRQn_Type irq = timer_config[timer_num].IRQ_Id;
71
+  uint32_t channel = timer_config[timer_num].channel;
72
 
72
 
73
   // Disable interrupt, just in case it was already enabled
73
   // Disable interrupt, just in case it was already enabled
74
   NVIC_DisableIRQ(irq);
74
   NVIC_DisableIRQ(irq);
86
 
86
 
87
   pmc_set_writeprotect(false);
87
   pmc_set_writeprotect(false);
88
   pmc_enable_periph_clk((uint32_t)irq);
88
   pmc_enable_periph_clk((uint32_t)irq);
89
-  NVIC_SetPriority(irq, TimerConfig [timer_num].priority);
89
+  NVIC_SetPriority(irq, timer_config[timer_num].priority);
90
 
90
 
91
   // wave mode, reset counter on match with RC,
91
   // wave mode, reset counter on match with RC,
92
   TC_Configure(tc, channel, TC_CMR_WAVE | TC_CMR_WAVSEL_UP_RC | TC_CMR_TCCLKS_TIMER_CLOCK1);
92
   TC_Configure(tc, channel, TC_CMR_WAVE | TC_CMR_WAVSEL_UP_RC | TC_CMR_TCCLKS_TIMER_CLOCK1);
105
 }
105
 }
106
 
106
 
107
 void HAL_timer_enable_interrupt(const uint8_t timer_num) {
107
 void HAL_timer_enable_interrupt(const uint8_t timer_num) {
108
-  IRQn_Type irq = TimerConfig[timer_num].IRQ_Id;
108
+  IRQn_Type irq = timer_config[timer_num].IRQ_Id;
109
   NVIC_EnableIRQ(irq);
109
   NVIC_EnableIRQ(irq);
110
 }
110
 }
111
 
111
 
112
 void HAL_timer_disable_interrupt(const uint8_t timer_num) {
112
 void HAL_timer_disable_interrupt(const uint8_t timer_num) {
113
-  IRQn_Type irq = TimerConfig[timer_num].IRQ_Id;
113
+  IRQn_Type irq = timer_config[timer_num].IRQ_Id;
114
   NVIC_DisableIRQ(irq);
114
   NVIC_DisableIRQ(irq);
115
 
115
 
116
   // We NEED memory barriers to ensure Interrupts are actually disabled!
116
   // We NEED memory barriers to ensure Interrupts are actually disabled!
125
 }
125
 }
126
 
126
 
127
 bool HAL_timer_interrupt_enabled(const uint8_t timer_num) {
127
 bool HAL_timer_interrupt_enabled(const uint8_t timer_num) {
128
-  IRQn_Type irq = TimerConfig[timer_num].IRQ_Id;
128
+  IRQn_Type irq = timer_config[timer_num].IRQ_Id;
129
   return NVIC_GetEnabledIRQ(irq);
129
   return NVIC_GetEnabledIRQ(irq);
130
 }
130
 }
131
 
131
 

+ 24
- 24
Marlin/src/HAL/DUE/timers.h View File

37
 
37
 
38
 #define HAL_TIMER_RATE         ((F_CPU) / 2)    // frequency of timers peripherals
38
 #define HAL_TIMER_RATE         ((F_CPU) / 2)    // frequency of timers peripherals
39
 
39
 
40
-#ifndef STEP_TIMER_NUM
41
-  #define STEP_TIMER_NUM        2  // Timer Index for Stepper
40
+#ifndef MF_TIMER_STEP
41
+  #define MF_TIMER_STEP         2  // Timer Index for Stepper
42
 #endif
42
 #endif
43
-#ifndef PULSE_TIMER_NUM
44
-  #define PULSE_TIMER_NUM       STEP_TIMER_NUM
43
+#ifndef MF_TIMER_PULSE
44
+  #define MF_TIMER_PULSE        MF_TIMER_STEP
45
 #endif
45
 #endif
46
-#ifndef TEMP_TIMER_NUM
47
-  #define TEMP_TIMER_NUM        4  // Timer Index for Temperature
46
+#ifndef MF_TIMER_TEMP
47
+  #define MF_TIMER_TEMP         4  // Timer Index for Temperature
48
 #endif
48
 #endif
49
-#ifndef TONE_TIMER_NUM
50
-  #define TONE_TIMER_NUM        6  // index of timer to use for beeper tones
49
+#ifndef MF_TIMER_TONE
50
+  #define MF_TIMER_TONE         6  // index of timer to use for beeper tones
51
 #endif
51
 #endif
52
 
52
 
53
 #define TEMP_TIMER_FREQUENCY   1000 // temperature interrupt frequency
53
 #define TEMP_TIMER_FREQUENCY   1000 // temperature interrupt frequency
54
 
54
 
55
-#define STEPPER_TIMER_RATE     HAL_TIMER_RATE   // frequency of stepper timer (HAL_TIMER_RATE / STEPPER_TIMER_PRESCALE)
56
-#define STEPPER_TIMER_TICKS_PER_US ((STEPPER_TIMER_RATE) / 1000000) // stepper timer ticks per µs
57
-#define STEPPER_TIMER_PRESCALE (CYCLES_PER_MICROSECOND / STEPPER_TIMER_TICKS_PER_US)
55
+#define STEPPER_TIMER_RATE          HAL_TIMER_RATE                                        // frequency of stepper timer (HAL_TIMER_RATE / STEPPER_TIMER_PRESCALE)
56
+#define STEPPER_TIMER_TICKS_PER_US  ((STEPPER_TIMER_RATE) / 1000000)                      // stepper timer ticks per µs
57
+#define STEPPER_TIMER_PRESCALE      (CYCLES_PER_MICROSECOND / STEPPER_TIMER_TICKS_PER_US)
58
 
58
 
59
-#define PULSE_TIMER_RATE       STEPPER_TIMER_RATE   // frequency of pulse timer
60
-#define PULSE_TIMER_PRESCALE   STEPPER_TIMER_PRESCALE
61
-#define PULSE_TIMER_TICKS_PER_US STEPPER_TIMER_TICKS_PER_US
59
+#define PULSE_TIMER_RATE            STEPPER_TIMER_RATE                                    // frequency of pulse timer
60
+#define PULSE_TIMER_PRESCALE        STEPPER_TIMER_PRESCALE
61
+#define PULSE_TIMER_TICKS_PER_US    STEPPER_TIMER_TICKS_PER_US
62
 
62
 
63
-#define ENABLE_STEPPER_DRIVER_INTERRUPT() HAL_timer_enable_interrupt(STEP_TIMER_NUM)
64
-#define DISABLE_STEPPER_DRIVER_INTERRUPT()  HAL_timer_disable_interrupt(STEP_TIMER_NUM)
65
-#define STEPPER_ISR_ENABLED() HAL_timer_interrupt_enabled(STEP_TIMER_NUM)
63
+#define ENABLE_STEPPER_DRIVER_INTERRUPT() HAL_timer_enable_interrupt(MF_TIMER_STEP)
64
+#define DISABLE_STEPPER_DRIVER_INTERRUPT()  HAL_timer_disable_interrupt(MF_TIMER_STEP)
65
+#define STEPPER_ISR_ENABLED() HAL_timer_interrupt_enabled(MF_TIMER_STEP)
66
 
66
 
67
-#define ENABLE_TEMPERATURE_INTERRUPT()  HAL_timer_enable_interrupt(TEMP_TIMER_NUM)
68
-#define DISABLE_TEMPERATURE_INTERRUPT() HAL_timer_disable_interrupt(TEMP_TIMER_NUM)
67
+#define ENABLE_TEMPERATURE_INTERRUPT()  HAL_timer_enable_interrupt(MF_TIMER_TEMP)
68
+#define DISABLE_TEMPERATURE_INTERRUPT() HAL_timer_disable_interrupt(MF_TIMER_TEMP)
69
 
69
 
70
 #ifndef HAL_STEP_TIMER_ISR
70
 #ifndef HAL_STEP_TIMER_ISR
71
   #define HAL_STEP_TIMER_ISR() void TC2_Handler()
71
   #define HAL_STEP_TIMER_ISR() void TC2_Handler()
92
 // Public Variables
92
 // Public Variables
93
 // ------------------------
93
 // ------------------------
94
 
94
 
95
-extern const tTimerConfig TimerConfig[];
95
+extern const tTimerConfig timer_config[];
96
 
96
 
97
 // ------------------------
97
 // ------------------------
98
 // Public functions
98
 // Public functions
101
 void HAL_timer_start(const uint8_t timer_num, const uint32_t frequency);
101
 void HAL_timer_start(const uint8_t timer_num, const uint32_t frequency);
102
 
102
 
103
 FORCE_INLINE static void HAL_timer_set_compare(const uint8_t timer_num, const hal_timer_t compare) {
103
 FORCE_INLINE static void HAL_timer_set_compare(const uint8_t timer_num, const hal_timer_t compare) {
104
-  const tTimerConfig * const pConfig = &TimerConfig[timer_num];
104
+  const tTimerConfig * const pConfig = &timer_config[timer_num];
105
   pConfig->pTimerRegs->TC_CHANNEL[pConfig->channel].TC_RC = compare;
105
   pConfig->pTimerRegs->TC_CHANNEL[pConfig->channel].TC_RC = compare;
106
 }
106
 }
107
 
107
 
108
 FORCE_INLINE static hal_timer_t HAL_timer_get_compare(const uint8_t timer_num) {
108
 FORCE_INLINE static hal_timer_t HAL_timer_get_compare(const uint8_t timer_num) {
109
-  const tTimerConfig * const pConfig = &TimerConfig[timer_num];
109
+  const tTimerConfig * const pConfig = &timer_config[timer_num];
110
   return pConfig->pTimerRegs->TC_CHANNEL[pConfig->channel].TC_RC;
110
   return pConfig->pTimerRegs->TC_CHANNEL[pConfig->channel].TC_RC;
111
 }
111
 }
112
 
112
 
113
 FORCE_INLINE static hal_timer_t HAL_timer_get_count(const uint8_t timer_num) {
113
 FORCE_INLINE static hal_timer_t HAL_timer_get_count(const uint8_t timer_num) {
114
-  const tTimerConfig * const pConfig = &TimerConfig[timer_num];
114
+  const tTimerConfig * const pConfig = &timer_config[timer_num];
115
   return pConfig->pTimerRegs->TC_CHANNEL[pConfig->channel].TC_CV;
115
   return pConfig->pTimerRegs->TC_CHANNEL[pConfig->channel].TC_CV;
116
 }
116
 }
117
 
117
 
120
 bool HAL_timer_interrupt_enabled(const uint8_t timer_num);
120
 bool HAL_timer_interrupt_enabled(const uint8_t timer_num);
121
 
121
 
122
 FORCE_INLINE static void HAL_timer_isr_prologue(const uint8_t timer_num) {
122
 FORCE_INLINE static void HAL_timer_isr_prologue(const uint8_t timer_num) {
123
-  const tTimerConfig * const pConfig = &TimerConfig[timer_num];
123
+  const tTimerConfig * const pConfig = &timer_config[timer_num];
124
   // Reading the status register clears the interrupt flag
124
   // Reading the status register clears the interrupt flag
125
   pConfig->pTimerRegs->TC_CHANNEL[pConfig->channel].TC_SR;
125
   pConfig->pTimerRegs->TC_CHANNEL[pConfig->channel].TC_SR;
126
 }
126
 }

+ 3
- 3
Marlin/src/HAL/ESP32/HAL.cpp View File

276
     idx = numPWMUsed;
276
     idx = numPWMUsed;
277
     pwmPins[idx] = pin;
277
     pwmPins[idx] = pin;
278
     // Start timer on first use
278
     // Start timer on first use
279
-    if (idx == 0) HAL_timer_start(PWM_TIMER_NUM, PWM_TIMER_FREQUENCY);
279
+    if (idx == 0) HAL_timer_start(MF_TIMER_PWM, PWM_TIMER_FREQUENCY);
280
 
280
 
281
     ++numPWMUsed;
281
     ++numPWMUsed;
282
   }
282
   }
287
 
287
 
288
 // Handle PWM timer interrupt
288
 // Handle PWM timer interrupt
289
 HAL_PWM_TIMER_ISR() {
289
 HAL_PWM_TIMER_ISR() {
290
-  HAL_timer_isr_prologue(PWM_TIMER_NUM);
290
+  HAL_timer_isr_prologue(MF_TIMER_PWM);
291
 
291
 
292
   static uint8_t count = 0;
292
   static uint8_t count = 0;
293
 
293
 
301
   // 128 for 7 Bit resolution
301
   // 128 for 7 Bit resolution
302
   count = (count + 1) & 0x7F;
302
   count = (count + 1) & 0x7F;
303
 
303
 
304
-  HAL_timer_isr_epilogue(PWM_TIMER_NUM);
304
+  HAL_timer_isr_epilogue(MF_TIMER_PWM);
305
 }
305
 }
306
 
306
 
307
 #endif // ARDUINO_ARCH_ESP32
307
 #endif // ARDUINO_ARCH_ESP32

+ 3
- 3
Marlin/src/HAL/ESP32/Tone.cpp View File

38
 void tone(const pin_t _pin, const unsigned int frequency, const unsigned long duration) {
38
 void tone(const pin_t _pin, const unsigned int frequency, const unsigned long duration) {
39
   tone_pin = _pin;
39
   tone_pin = _pin;
40
   toggles = 2 * frequency * duration / 1000;
40
   toggles = 2 * frequency * duration / 1000;
41
-  HAL_timer_start(TONE_TIMER_NUM, 2 * frequency);
41
+  HAL_timer_start(MF_TIMER_TONE, 2 * frequency);
42
 }
42
 }
43
 
43
 
44
 void noTone(const pin_t _pin) {
44
 void noTone(const pin_t _pin) {
45
-  HAL_timer_disable_interrupt(TONE_TIMER_NUM);
45
+  HAL_timer_disable_interrupt(MF_TIMER_TONE);
46
   WRITE(_pin, LOW);
46
   WRITE(_pin, LOW);
47
 }
47
 }
48
 
48
 
49
 HAL_TONE_TIMER_ISR() {
49
 HAL_TONE_TIMER_ISR() {
50
-  HAL_timer_isr_prologue(TONE_TIMER_NUM);
50
+  HAL_timer_isr_prologue(MF_TIMER_TONE);
51
 
51
 
52
   if (toggles) {
52
   if (toggles) {
53
     toggles--;
53
     toggles--;

+ 9
- 9
Marlin/src/HAL/ESP32/timers.cpp View File

41
 
41
 
42
 static timg_dev_t *TG[2] = {&TIMERG0, &TIMERG1};
42
 static timg_dev_t *TG[2] = {&TIMERG0, &TIMERG1};
43
 
43
 
44
-const tTimerConfig TimerConfig [NUM_HARDWARE_TIMERS] = {
44
+const tTimerConfig timer_config[NUM_HARDWARE_TIMERS] = {
45
   { TIMER_GROUP_0, TIMER_0, STEPPER_TIMER_PRESCALE, stepTC_Handler }, // 0 - Stepper
45
   { TIMER_GROUP_0, TIMER_0, STEPPER_TIMER_PRESCALE, stepTC_Handler }, // 0 - Stepper
46
   { TIMER_GROUP_0, TIMER_1,    TEMP_TIMER_PRESCALE, tempTC_Handler }, // 1 - Temperature
46
   { TIMER_GROUP_0, TIMER_1,    TEMP_TIMER_PRESCALE, tempTC_Handler }, // 1 - Temperature
47
   { TIMER_GROUP_1, TIMER_0,     PWM_TIMER_PRESCALE, pwmTC_Handler  }, // 2 - PWM
47
   { TIMER_GROUP_1, TIMER_0,     PWM_TIMER_PRESCALE, pwmTC_Handler  }, // 2 - PWM
53
 // ------------------------
53
 // ------------------------
54
 
54
 
55
 void IRAM_ATTR timer_isr(void *para) {
55
 void IRAM_ATTR timer_isr(void *para) {
56
-  const tTimerConfig& timer = TimerConfig[(int)para];
56
+  const tTimerConfig& timer = timer_config[(int)para];
57
 
57
 
58
   // Retrieve the interrupt status and the counter value
58
   // Retrieve the interrupt status and the counter value
59
   // from the timer that reported the interrupt
59
   // from the timer that reported the interrupt
82
  * @param frequency frequency of the timer
82
  * @param frequency frequency of the timer
83
  */
83
  */
84
 void HAL_timer_start(const uint8_t timer_num, uint32_t frequency) {
84
 void HAL_timer_start(const uint8_t timer_num, uint32_t frequency) {
85
-  const tTimerConfig timer = TimerConfig[timer_num];
85
+  const tTimerConfig timer = timer_config[timer_num];
86
 
86
 
87
   timer_config_t config;
87
   timer_config_t config;
88
   config.divider     = timer.divider;
88
   config.divider     = timer.divider;
115
  * @param count     threshold at which the interrupt is triggered
115
  * @param count     threshold at which the interrupt is triggered
116
  */
116
  */
117
 void HAL_timer_set_compare(const uint8_t timer_num, hal_timer_t count) {
117
 void HAL_timer_set_compare(const uint8_t timer_num, hal_timer_t count) {
118
-  const tTimerConfig timer = TimerConfig[timer_num];
118
+  const tTimerConfig timer = timer_config[timer_num];
119
   timer_set_alarm_value(timer.group, timer.idx, count);
119
   timer_set_alarm_value(timer.group, timer.idx, count);
120
 }
120
 }
121
 
121
 
125
  * @return           the timer current threshold for the alarm to be triggered
125
  * @return           the timer current threshold for the alarm to be triggered
126
  */
126
  */
127
 hal_timer_t HAL_timer_get_compare(const uint8_t timer_num) {
127
 hal_timer_t HAL_timer_get_compare(const uint8_t timer_num) {
128
-  const tTimerConfig timer = TimerConfig[timer_num];
128
+  const tTimerConfig timer = timer_config[timer_num];
129
 
129
 
130
   uint64_t alarm_value;
130
   uint64_t alarm_value;
131
   timer_get_alarm_value(timer.group, timer.idx, &alarm_value);
131
   timer_get_alarm_value(timer.group, timer.idx, &alarm_value);
139
  * @return           the current counter of the alarm
139
  * @return           the current counter of the alarm
140
  */
140
  */
141
 hal_timer_t HAL_timer_get_count(const uint8_t timer_num) {
141
 hal_timer_t HAL_timer_get_count(const uint8_t timer_num) {
142
-  const tTimerConfig timer = TimerConfig[timer_num];
142
+  const tTimerConfig timer = timer_config[timer_num];
143
   uint64_t counter_value;
143
   uint64_t counter_value;
144
   timer_get_counter_value(timer.group, timer.idx, &counter_value);
144
   timer_get_counter_value(timer.group, timer.idx, &counter_value);
145
   return counter_value;
145
   return counter_value;
150
  * @param timer_num timer number to enable interrupts on
150
  * @param timer_num timer number to enable interrupts on
151
  */
151
  */
152
 void HAL_timer_enable_interrupt(const uint8_t timer_num) {
152
 void HAL_timer_enable_interrupt(const uint8_t timer_num) {
153
-  //const tTimerConfig timer = TimerConfig[timer_num];
153
+  //const tTimerConfig timer = timer_config[timer_num];
154
   //timer_enable_intr(timer.group, timer.idx);
154
   //timer_enable_intr(timer.group, timer.idx);
155
 }
155
 }
156
 
156
 
159
  * @param timer_num timer number to disable interrupts on
159
  * @param timer_num timer number to disable interrupts on
160
  */
160
  */
161
 void HAL_timer_disable_interrupt(const uint8_t timer_num) {
161
 void HAL_timer_disable_interrupt(const uint8_t timer_num) {
162
-  //const tTimerConfig timer = TimerConfig[timer_num];
162
+  //const tTimerConfig timer = timer_config[timer_num];
163
   //timer_disable_intr(timer.group, timer.idx);
163
   //timer_disable_intr(timer.group, timer.idx);
164
 }
164
 }
165
 
165
 
166
 bool HAL_timer_interrupt_enabled(const uint8_t timer_num) {
166
 bool HAL_timer_interrupt_enabled(const uint8_t timer_num) {
167
-  const tTimerConfig timer = TimerConfig[timer_num];
167
+  const tTimerConfig timer = timer_config[timer_num];
168
   return TG[timer.group]->int_ena.val | BIT(timer_num);
168
   return TG[timer.group]->int_ena.val | BIT(timer_num);
169
 }
169
 }
170
 
170
 

+ 16
- 16
Marlin/src/HAL/ESP32/timers.h View File

32
 typedef uint64_t hal_timer_t;
32
 typedef uint64_t hal_timer_t;
33
 #define HAL_TIMER_TYPE_MAX 0xFFFFFFFFFFFFFFFFULL
33
 #define HAL_TIMER_TYPE_MAX 0xFFFFFFFFFFFFFFFFULL
34
 
34
 
35
-#ifndef STEP_TIMER_NUM
36
-  #define STEP_TIMER_NUM        0  // Timer Index for Stepper
35
+#ifndef MF_TIMER_STEP
36
+  #define MF_TIMER_STEP         0  // Timer Index for Stepper
37
 #endif
37
 #endif
38
-#ifndef PULSE_TIMER_NUM
39
-  #define PULSE_TIMER_NUM       STEP_TIMER_NUM
38
+#ifndef MF_TIMER_PULSE
39
+  #define MF_TIMER_PULSE        MF_TIMER_STEP
40
 #endif
40
 #endif
41
-#ifndef TEMP_TIMER_NUM
42
-  #define TEMP_TIMER_NUM        1  // Timer Index for Temperature
41
+#ifndef MF_TIMER_TEMP
42
+  #define MF_TIMER_TEMP         1  // Timer Index for Temperature
43
 #endif
43
 #endif
44
-#ifndef PWM_TIMER_NUM
45
-  #define PWM_TIMER_NUM         2  // index of timer to use for PWM outputs
44
+#ifndef MF_TIMER_PWM
45
+  #define MF_TIMER_PWM          2  // index of timer to use for PWM outputs
46
 #endif
46
 #endif
47
-#ifndef TONE_TIMER_NUM
48
-  #define TONE_TIMER_NUM        3  // index of timer for beeper tones
47
+#ifndef MF_TIMER_TONE
48
+  #define MF_TIMER_TONE         3  // index of timer for beeper tones
49
 #endif
49
 #endif
50
 
50
 
51
 #define HAL_TIMER_RATE APB_CLK_FREQ // frequency of timer peripherals
51
 #define HAL_TIMER_RATE APB_CLK_FREQ // frequency of timer peripherals
79
 #define PULSE_TIMER_PRESCALE     STEPPER_TIMER_PRESCALE
79
 #define PULSE_TIMER_PRESCALE     STEPPER_TIMER_PRESCALE
80
 #define PULSE_TIMER_TICKS_PER_US STEPPER_TIMER_TICKS_PER_US
80
 #define PULSE_TIMER_TICKS_PER_US STEPPER_TIMER_TICKS_PER_US
81
 
81
 
82
-#define ENABLE_STEPPER_DRIVER_INTERRUPT() HAL_timer_enable_interrupt(STEP_TIMER_NUM)
83
-#define DISABLE_STEPPER_DRIVER_INTERRUPT()  HAL_timer_disable_interrupt(STEP_TIMER_NUM)
84
-#define STEPPER_ISR_ENABLED() HAL_timer_interrupt_enabled(STEP_TIMER_NUM)
82
+#define ENABLE_STEPPER_DRIVER_INTERRUPT() HAL_timer_enable_interrupt(MF_TIMER_STEP)
83
+#define DISABLE_STEPPER_DRIVER_INTERRUPT()  HAL_timer_disable_interrupt(MF_TIMER_STEP)
84
+#define STEPPER_ISR_ENABLED() HAL_timer_interrupt_enabled(MF_TIMER_STEP)
85
 
85
 
86
-#define ENABLE_TEMPERATURE_INTERRUPT()  HAL_timer_enable_interrupt(TEMP_TIMER_NUM)
87
-#define DISABLE_TEMPERATURE_INTERRUPT() HAL_timer_disable_interrupt(TEMP_TIMER_NUM)
86
+#define ENABLE_TEMPERATURE_INTERRUPT()  HAL_timer_enable_interrupt(MF_TIMER_TEMP)
87
+#define DISABLE_TEMPERATURE_INTERRUPT() HAL_timer_disable_interrupt(MF_TIMER_TEMP)
88
 
88
 
89
 #ifndef HAL_TEMP_TIMER_ISR
89
 #ifndef HAL_TEMP_TIMER_ISR
90
   #define HAL_TEMP_TIMER_ISR() extern "C" void tempTC_Handler()
90
   #define HAL_TEMP_TIMER_ISR() extern "C" void tempTC_Handler()
121
 // Public Variables
121
 // Public Variables
122
 // ------------------------
122
 // ------------------------
123
 
123
 
124
-extern const tTimerConfig TimerConfig[];
124
+extern const tTimerConfig timer_config[];
125
 
125
 
126
 // ------------------------
126
 // ------------------------
127
 // Public functions
127
 // Public functions

+ 11
- 12
Marlin/src/HAL/LINUX/timers.h View File

37
 
37
 
38
 #define HAL_TIMER_RATE         ((SystemCoreClock) / 4)  // frequency of timers peripherals
38
 #define HAL_TIMER_RATE         ((SystemCoreClock) / 4)  // frequency of timers peripherals
39
 
39
 
40
-#ifndef STEP_TIMER_NUM
41
-  #define STEP_TIMER_NUM        0  // Timer Index for Stepper
40
+#ifndef MF_TIMER_STEP
41
+  #define MF_TIMER_STEP         0  // Timer Index for Stepper
42
 #endif
42
 #endif
43
-#ifndef PULSE_TIMER_NUM
44
-  #define PULSE_TIMER_NUM       STEP_TIMER_NUM
43
+#ifndef MF_TIMER_PULSE
44
+  #define MF_TIMER_PULSE        MF_TIMER_STEP
45
 #endif
45
 #endif
46
-#ifndef TEMP_TIMER_NUM
47
-  #define TEMP_TIMER_NUM        1  // Timer Index for Temperature
46
+#ifndef MF_TIMER_TEMP
47
+  #define MF_TIMER_TEMP         1  // Timer Index for Temperature
48
 #endif
48
 #endif
49
 
49
 
50
 #define TEMP_TIMER_RATE        1000000
50
 #define TEMP_TIMER_RATE        1000000
58
 #define PULSE_TIMER_PRESCALE   STEPPER_TIMER_PRESCALE
58
 #define PULSE_TIMER_PRESCALE   STEPPER_TIMER_PRESCALE
59
 #define PULSE_TIMER_TICKS_PER_US STEPPER_TIMER_TICKS_PER_US
59
 #define PULSE_TIMER_TICKS_PER_US STEPPER_TIMER_TICKS_PER_US
60
 
60
 
61
-#define ENABLE_STEPPER_DRIVER_INTERRUPT() HAL_timer_enable_interrupt(STEP_TIMER_NUM)
62
-#define DISABLE_STEPPER_DRIVER_INTERRUPT() HAL_timer_disable_interrupt(STEP_TIMER_NUM)
63
-#define STEPPER_ISR_ENABLED() HAL_timer_interrupt_enabled(STEP_TIMER_NUM)
61
+#define ENABLE_STEPPER_DRIVER_INTERRUPT() HAL_timer_enable_interrupt(MF_TIMER_STEP)
62
+#define DISABLE_STEPPER_DRIVER_INTERRUPT() HAL_timer_disable_interrupt(MF_TIMER_STEP)
63
+#define STEPPER_ISR_ENABLED() HAL_timer_interrupt_enabled(MF_TIMER_STEP)
64
 
64
 
65
-#define ENABLE_TEMPERATURE_INTERRUPT() HAL_timer_enable_interrupt(TEMP_TIMER_NUM)
66
-#define DISABLE_TEMPERATURE_INTERRUPT() HAL_timer_disable_interrupt(TEMP_TIMER_NUM)
65
+#define ENABLE_TEMPERATURE_INTERRUPT() HAL_timer_enable_interrupt(MF_TIMER_TEMP)
66
+#define DISABLE_TEMPERATURE_INTERRUPT() HAL_timer_disable_interrupt(MF_TIMER_TEMP)
67
 
67
 
68
 #ifndef HAL_STEP_TIMER_ISR
68
 #ifndef HAL_STEP_TIMER_ISR
69
   #define HAL_STEP_TIMER_ISR()  extern "C" void TIMER0_IRQHandler()
69
   #define HAL_STEP_TIMER_ISR()  extern "C" void TIMER0_IRQHandler()
77
 #define HAL_PWM_TIMER_ISR()   extern "C" void TIMER3_IRQHandler()
77
 #define HAL_PWM_TIMER_ISR()   extern "C" void TIMER3_IRQHandler()
78
 #define HAL_PWM_TIMER_IRQn
78
 #define HAL_PWM_TIMER_IRQn
79
 
79
 
80
-
81
 void HAL_timer_init();
80
 void HAL_timer_init();
82
 void HAL_timer_start(const uint8_t timer_num, const uint32_t frequency);
81
 void HAL_timer_start(const uint8_t timer_num, const uint32_t frequency);
83
 
82
 

+ 2
- 2
Marlin/src/HAL/LPC1768/timers.cpp View File

40
 
40
 
41
 void HAL_timer_start(const uint8_t timer_num, const uint32_t frequency) {
41
 void HAL_timer_start(const uint8_t timer_num, const uint32_t frequency) {
42
   switch (timer_num) {
42
   switch (timer_num) {
43
-    case 0:
43
+    case MF_TIMER_STEP:
44
       LPC_TIM0->MCR = _BV(SBIT_MR0I) | _BV(SBIT_MR0R); // Match on MR0, reset on MR0, interrupts when NVIC enables them
44
       LPC_TIM0->MCR = _BV(SBIT_MR0I) | _BV(SBIT_MR0R); // Match on MR0, reset on MR0, interrupts when NVIC enables them
45
       LPC_TIM0->MR0 = uint32_t(STEPPER_TIMER_RATE) / frequency; // Match value (period) to set frequency
45
       LPC_TIM0->MR0 = uint32_t(STEPPER_TIMER_RATE) / frequency; // Match value (period) to set frequency
46
       LPC_TIM0->TCR = _BV(SBIT_CNTEN); // Counter Enable
46
       LPC_TIM0->TCR = _BV(SBIT_CNTEN); // Counter Enable
49
       NVIC_EnableIRQ(TIMER0_IRQn);
49
       NVIC_EnableIRQ(TIMER0_IRQn);
50
       break;
50
       break;
51
 
51
 
52
-    case 1:
52
+    case MF_TIMER_TEMP:
53
       LPC_TIM1->MCR = _BV(SBIT_MR0I) | _BV(SBIT_MR0R); // Match on MR0, reset on MR0, interrupts when NVIC enables them
53
       LPC_TIM1->MCR = _BV(SBIT_MR0I) | _BV(SBIT_MR0R); // Match on MR0, reset on MR0, interrupts when NVIC enables them
54
       LPC_TIM1->MR0 = uint32_t(TEMP_TIMER_RATE) / frequency;
54
       LPC_TIM1->MR0 = uint32_t(TEMP_TIMER_RATE) / frequency;
55
       LPC_TIM1->TCR = _BV(SBIT_CNTEN); // Counter Enable
55
       LPC_TIM1->TCR = _BV(SBIT_CNTEN); // Counter Enable

+ 31
- 31
Marlin/src/HAL/LPC1768/timers.h View File

60
 
60
 
61
 #define HAL_TIMER_RATE         ((F_CPU) / 4)  // frequency of timers peripherals
61
 #define HAL_TIMER_RATE         ((F_CPU) / 4)  // frequency of timers peripherals
62
 
62
 
63
-#ifndef STEP_TIMER_NUM
64
-  #define STEP_TIMER_NUM        0  // Timer Index for Stepper
63
+#ifndef MF_TIMER_STEP
64
+  #define MF_TIMER_STEP         0  // Timer Index for Stepper
65
 #endif
65
 #endif
66
-#ifndef PULSE_TIMER_NUM
67
-  #define PULSE_TIMER_NUM       STEP_TIMER_NUM
66
+#ifndef MF_TIMER_PULSE
67
+  #define MF_TIMER_PULSE        MF_TIMER_STEP
68
 #endif
68
 #endif
69
-#ifndef TEMP_TIMER_NUM
70
-  #define TEMP_TIMER_NUM        1  // Timer Index for Temperature
69
+#ifndef MF_TIMER_TEMP
70
+  #define MF_TIMER_TEMP         1  // Timer Index for Temperature
71
 #endif
71
 #endif
72
-#ifndef PWM_TIMER_NUM
73
-  #define PWM_TIMER_NUM         3  // Timer Index for PWM
72
+#ifndef MF_TIMER_PWM
73
+  #define MF_TIMER_PWM          3  // Timer Index for PWM
74
 #endif
74
 #endif
75
 
75
 
76
 #define TEMP_TIMER_RATE        1000000
76
 #define TEMP_TIMER_RATE        1000000
84
 #define PULSE_TIMER_PRESCALE   STEPPER_TIMER_PRESCALE
84
 #define PULSE_TIMER_PRESCALE   STEPPER_TIMER_PRESCALE
85
 #define PULSE_TIMER_TICKS_PER_US STEPPER_TIMER_TICKS_PER_US
85
 #define PULSE_TIMER_TICKS_PER_US STEPPER_TIMER_TICKS_PER_US
86
 
86
 
87
-#define ENABLE_STEPPER_DRIVER_INTERRUPT() HAL_timer_enable_interrupt(STEP_TIMER_NUM)
88
-#define DISABLE_STEPPER_DRIVER_INTERRUPT() HAL_timer_disable_interrupt(STEP_TIMER_NUM)
89
-#define STEPPER_ISR_ENABLED() HAL_timer_interrupt_enabled(STEP_TIMER_NUM)
87
+#define ENABLE_STEPPER_DRIVER_INTERRUPT() HAL_timer_enable_interrupt(MF_TIMER_STEP)
88
+#define DISABLE_STEPPER_DRIVER_INTERRUPT() HAL_timer_disable_interrupt(MF_TIMER_STEP)
89
+#define STEPPER_ISR_ENABLED() HAL_timer_interrupt_enabled(MF_TIMER_STEP)
90
 
90
 
91
-#define ENABLE_TEMPERATURE_INTERRUPT() HAL_timer_enable_interrupt(TEMP_TIMER_NUM)
92
-#define DISABLE_TEMPERATURE_INTERRUPT() HAL_timer_disable_interrupt(TEMP_TIMER_NUM)
91
+#define ENABLE_TEMPERATURE_INTERRUPT() HAL_timer_enable_interrupt(MF_TIMER_TEMP)
92
+#define DISABLE_TEMPERATURE_INTERRUPT() HAL_timer_disable_interrupt(MF_TIMER_TEMP)
93
 
93
 
94
 #ifndef HAL_STEP_TIMER_ISR
94
 #ifndef HAL_STEP_TIMER_ISR
95
-  #define HAL_STEP_TIMER_ISR() _HAL_TIMER_ISR(STEP_TIMER_NUM)
95
+  #define HAL_STEP_TIMER_ISR() _HAL_TIMER_ISR(MF_TIMER_STEP)
96
 #endif
96
 #endif
97
 #ifndef HAL_TEMP_TIMER_ISR
97
 #ifndef HAL_TEMP_TIMER_ISR
98
-  #define HAL_TEMP_TIMER_ISR() _HAL_TIMER_ISR(TEMP_TIMER_NUM)
98
+  #define HAL_TEMP_TIMER_ISR() _HAL_TIMER_ISR(MF_TIMER_TEMP)
99
 #endif
99
 #endif
100
 
100
 
101
 // Timer references by index
101
 // Timer references by index
102
-#define STEP_TIMER_PTR _HAL_TIMER(STEP_TIMER_NUM)
103
-#define TEMP_TIMER_PTR _HAL_TIMER(TEMP_TIMER_NUM)
102
+#define STEP_TIMER_PTR _HAL_TIMER(MF_TIMER_STEP)
103
+#define TEMP_TIMER_PTR _HAL_TIMER(MF_TIMER_TEMP)
104
 
104
 
105
 // ------------------------
105
 // ------------------------
106
 // Public functions
106
 // Public functions
110
 
110
 
111
 FORCE_INLINE static void HAL_timer_set_compare(const uint8_t timer_num, const hal_timer_t compare) {
111
 FORCE_INLINE static void HAL_timer_set_compare(const uint8_t timer_num, const hal_timer_t compare) {
112
   switch (timer_num) {
112
   switch (timer_num) {
113
-    case 0: STEP_TIMER_PTR->MR0 = compare; break; // Stepper Timer Match Register 0
114
-    case 1: TEMP_TIMER_PTR->MR0 = compare; break; //    Temp Timer Match Register 0
113
+    case MF_TIMER_STEP: STEP_TIMER_PTR->MR0 = compare; break; // Stepper Timer Match Register 0
114
+    case MF_TIMER_TEMP: TEMP_TIMER_PTR->MR0 = compare; break; //    Temp Timer Match Register 0
115
   }
115
   }
116
 }
116
 }
117
 
117
 
118
 FORCE_INLINE static hal_timer_t HAL_timer_get_compare(const uint8_t timer_num) {
118
 FORCE_INLINE static hal_timer_t HAL_timer_get_compare(const uint8_t timer_num) {
119
   switch (timer_num) {
119
   switch (timer_num) {
120
-    case 0: return STEP_TIMER_PTR->MR0; // Stepper Timer Match Register 0
121
-    case 1: return TEMP_TIMER_PTR->MR0; //    Temp Timer Match Register 0
120
+    case MF_TIMER_STEP: return STEP_TIMER_PTR->MR0; // Stepper Timer Match Register 0
121
+    case MF_TIMER_TEMP: return TEMP_TIMER_PTR->MR0; //    Temp Timer Match Register 0
122
   }
122
   }
123
   return 0;
123
   return 0;
124
 }
124
 }
125
 
125
 
126
 FORCE_INLINE static hal_timer_t HAL_timer_get_count(const uint8_t timer_num) {
126
 FORCE_INLINE static hal_timer_t HAL_timer_get_count(const uint8_t timer_num) {
127
   switch (timer_num) {
127
   switch (timer_num) {
128
-    case 0: return STEP_TIMER_PTR->TC; // Stepper Timer Count
129
-    case 1: return TEMP_TIMER_PTR->TC; //    Temp Timer Count
128
+    case MF_TIMER_STEP: return STEP_TIMER_PTR->TC; // Stepper Timer Count
129
+    case MF_TIMER_TEMP: return TEMP_TIMER_PTR->TC; //    Temp Timer Count
130
   }
130
   }
131
   return 0;
131
   return 0;
132
 }
132
 }
133
 
133
 
134
 FORCE_INLINE static void HAL_timer_enable_interrupt(const uint8_t timer_num) {
134
 FORCE_INLINE static void HAL_timer_enable_interrupt(const uint8_t timer_num) {
135
   switch (timer_num) {
135
   switch (timer_num) {
136
-    case 0: NVIC_EnableIRQ(TIMER0_IRQn); break; // Enable interrupt handler
137
-    case 1: NVIC_EnableIRQ(TIMER1_IRQn); break; // Enable interrupt handler
136
+    case MF_TIMER_STEP: NVIC_EnableIRQ(TIMER0_IRQn); break; // Enable interrupt handler
137
+    case MF_TIMER_TEMP: NVIC_EnableIRQ(TIMER1_IRQn); break; // Enable interrupt handler
138
   }
138
   }
139
 }
139
 }
140
 
140
 
141
 FORCE_INLINE static void HAL_timer_disable_interrupt(const uint8_t timer_num) {
141
 FORCE_INLINE static void HAL_timer_disable_interrupt(const uint8_t timer_num) {
142
   switch (timer_num) {
142
   switch (timer_num) {
143
-    case 0: NVIC_DisableIRQ(TIMER0_IRQn); break; // Disable interrupt handler
144
-    case 1: NVIC_DisableIRQ(TIMER1_IRQn); break; // Disable interrupt handler
143
+    case MF_TIMER_STEP: NVIC_DisableIRQ(TIMER0_IRQn); break; // Disable interrupt handler
144
+    case MF_TIMER_TEMP: NVIC_DisableIRQ(TIMER1_IRQn); break; // Disable interrupt handler
145
   }
145
   }
146
 
146
 
147
   // We NEED memory barriers to ensure Interrupts are actually disabled!
147
   // We NEED memory barriers to ensure Interrupts are actually disabled!
157
 
157
 
158
 FORCE_INLINE static bool HAL_timer_interrupt_enabled(const uint8_t timer_num) {
158
 FORCE_INLINE static bool HAL_timer_interrupt_enabled(const uint8_t timer_num) {
159
   switch (timer_num) {
159
   switch (timer_num) {
160
-    case 0: return NVIC_GetEnableIRQ(TIMER0_IRQn); // Check if interrupt is enabled or not
161
-    case 1: return NVIC_GetEnableIRQ(TIMER1_IRQn); // Check if interrupt is enabled or not
160
+    case MF_TIMER_STEP: return NVIC_GetEnableIRQ(TIMER0_IRQn); // Check if interrupt is enabled or not
161
+    case MF_TIMER_TEMP: return NVIC_GetEnableIRQ(TIMER1_IRQn); // Check if interrupt is enabled or not
162
   }
162
   }
163
   return false;
163
   return false;
164
 }
164
 }
165
 
165
 
166
 FORCE_INLINE static void HAL_timer_isr_prologue(const uint8_t timer_num) {
166
 FORCE_INLINE static void HAL_timer_isr_prologue(const uint8_t timer_num) {
167
   switch (timer_num) {
167
   switch (timer_num) {
168
-    case 0: SBI(STEP_TIMER_PTR->IR, SBIT_CNTEN); break;
169
-    case 1: SBI(TEMP_TIMER_PTR->IR, SBIT_CNTEN); break;
168
+    case MF_TIMER_STEP: SBI(STEP_TIMER_PTR->IR, SBIT_CNTEN); break;
169
+    case MF_TIMER_TEMP: SBI(TEMP_TIMER_PTR->IR, SBIT_CNTEN); break;
170
   }
170
   }
171
 }
171
 }
172
 
172
 

+ 13
- 13
Marlin/src/HAL/NATIVE_SIM/timers.h View File

37
 
37
 
38
 #define HAL_TIMER_RATE         ((SystemCoreClock) / 4)  // frequency of timers peripherals
38
 #define HAL_TIMER_RATE         ((SystemCoreClock) / 4)  // frequency of timers peripherals
39
 
39
 
40
-#ifndef STEP_TIMER_NUM
41
-  #define STEP_TIMER_NUM        0  // Timer Index for Stepper
40
+#ifndef MF_TIMER_STEP
41
+  #define MF_TIMER_STEP         0  // Timer Index for Stepper
42
 #endif
42
 #endif
43
-#ifndef PULSE_TIMER_NUM
44
-  #define PULSE_TIMER_NUM       STEP_TIMER_NUM
43
+#ifndef MF_TIMER_PULSE
44
+  #define MF_TIMER_PULSE        MF_TIMER_STEP
45
 #endif
45
 #endif
46
-#ifndef TEMP_TIMER_NUM
47
-  #define TEMP_TIMER_NUM        1  // Timer Index for Temperature
46
+#ifndef MF_TIMER_TEMP
47
+  #define MF_TIMER_TEMP         1  // Timer Index for Temperature
48
 #endif
48
 #endif
49
-#ifndef SYSTICK_TIMER_NUM
50
-  #define SYSTICK_TIMER_NUM     2 // Timer Index for Systick
49
+#ifndef MF_TIMER_SYSTICK
50
+  #define MF_TIMER_SYSTICK      2  // Timer Index for Systick
51
 #endif
51
 #endif
52
 #define SYSTICK_TIMER_FREQUENCY 1000
52
 #define SYSTICK_TIMER_FREQUENCY 1000
53
 
53
 
62
 #define PULSE_TIMER_PRESCALE   STEPPER_TIMER_PRESCALE
62
 #define PULSE_TIMER_PRESCALE   STEPPER_TIMER_PRESCALE
63
 #define PULSE_TIMER_TICKS_PER_US STEPPER_TIMER_TICKS_PER_US
63
 #define PULSE_TIMER_TICKS_PER_US STEPPER_TIMER_TICKS_PER_US
64
 
64
 
65
-#define ENABLE_STEPPER_DRIVER_INTERRUPT() HAL_timer_enable_interrupt(STEP_TIMER_NUM)
66
-#define DISABLE_STEPPER_DRIVER_INTERRUPT() HAL_timer_disable_interrupt(STEP_TIMER_NUM)
67
-#define STEPPER_ISR_ENABLED() HAL_timer_interrupt_enabled(STEP_TIMER_NUM)
65
+#define ENABLE_STEPPER_DRIVER_INTERRUPT() HAL_timer_enable_interrupt(MF_TIMER_STEP)
66
+#define DISABLE_STEPPER_DRIVER_INTERRUPT() HAL_timer_disable_interrupt(MF_TIMER_STEP)
67
+#define STEPPER_ISR_ENABLED() HAL_timer_interrupt_enabled(MF_TIMER_STEP)
68
 
68
 
69
-#define ENABLE_TEMPERATURE_INTERRUPT() HAL_timer_enable_interrupt(TEMP_TIMER_NUM)
70
-#define DISABLE_TEMPERATURE_INTERRUPT() HAL_timer_disable_interrupt(TEMP_TIMER_NUM)
69
+#define ENABLE_TEMPERATURE_INTERRUPT() HAL_timer_enable_interrupt(MF_TIMER_TEMP)
70
+#define DISABLE_TEMPERATURE_INTERRUPT() HAL_timer_disable_interrupt(MF_TIMER_TEMP)
71
 
71
 
72
 #ifndef HAL_STEP_TIMER_ISR
72
 #ifndef HAL_STEP_TIMER_ISR
73
   #define HAL_STEP_TIMER_ISR()  extern "C" void TIMER0_IRQHandler()
73
   #define HAL_STEP_TIMER_ISR()  extern "C" void TIMER0_IRQHandler()

+ 4
- 4
Marlin/src/HAL/SAMD51/Servo.cpp View File

53
 static volatile int8_t currentServoIndex[_Nbr_16timers];    // index for the servo being pulsed for each timer (or -1 if refresh interval)
53
 static volatile int8_t currentServoIndex[_Nbr_16timers];    // index for the servo being pulsed for each timer (or -1 if refresh interval)
54
 
54
 
55
 FORCE_INLINE static uint16_t getTimerCount() {
55
 FORCE_INLINE static uint16_t getTimerCount() {
56
-  Tc * const tc = TimerConfig[SERVO_TC].pTc;
56
+  Tc * const tc = timer_config[SERVO_TC].pTc;
57
 
57
 
58
   tc->COUNT16.CTRLBSET.reg = TC_CTRLBCLR_CMD_READSYNC;
58
   tc->COUNT16.CTRLBSET.reg = TC_CTRLBCLR_CMD_READSYNC;
59
   SYNC(tc->COUNT16.SYNCBUSY.bit.CTRLB || tc->COUNT16.SYNCBUSY.bit.COUNT);
59
   SYNC(tc->COUNT16.SYNCBUSY.bit.CTRLB || tc->COUNT16.SYNCBUSY.bit.COUNT);
65
 // Interrupt handler for the TC
65
 // Interrupt handler for the TC
66
 // ----------------------------
66
 // ----------------------------
67
 HAL_SERVO_TIMER_ISR() {
67
 HAL_SERVO_TIMER_ISR() {
68
-  Tc * const tc = TimerConfig[SERVO_TC].pTc;
68
+  Tc * const tc = timer_config[SERVO_TC].pTc;
69
   const timer16_Sequence_t timer =
69
   const timer16_Sequence_t timer =
70
     #ifndef _useTimer1
70
     #ifndef _useTimer1
71
       _timer2
71
       _timer2
125
 }
125
 }
126
 
126
 
127
 void initISR(timer16_Sequence_t timer) {
127
 void initISR(timer16_Sequence_t timer) {
128
-  Tc * const tc = TimerConfig[SERVO_TC].pTc;
128
+  Tc * const tc = timer_config[SERVO_TC].pTc;
129
   const uint8_t tcChannel = TIMER_TCCHANNEL(timer);
129
   const uint8_t tcChannel = TIMER_TCCHANNEL(timer);
130
 
130
 
131
   static bool initialized = false;  // Servo TC has been initialized
131
   static bool initialized = false;  // Servo TC has been initialized
202
 }
202
 }
203
 
203
 
204
 void finISR(timer16_Sequence_t timer) {
204
 void finISR(timer16_Sequence_t timer) {
205
-  Tc * const tc = TimerConfig[SERVO_TC].pTc;
205
+  Tc * const tc = timer_config[SERVO_TC].pTc;
206
   const uint8_t tcChannel = TIMER_TCCHANNEL(timer);
206
   const uint8_t tcChannel = TIMER_TCCHANNEL(timer);
207
 
207
 
208
   // Disable the match channel interrupt request
208
   // Disable the match channel interrupt request

+ 1
- 1
Marlin/src/HAL/SAMD51/inc/SanityCheck.h View File

36
   #error "OnBoard SPI BUS can't be shared with other devices."
36
   #error "OnBoard SPI BUS can't be shared with other devices."
37
 #endif
37
 #endif
38
 
38
 
39
-#if SERVO_TC == RTC_TIMER_NUM
39
+#if SERVO_TC == MF_TIMER_RTC
40
   #error "Servos can't use RTC timer"
40
   #error "Servos can't use RTC timer"
41
 #endif
41
 #endif
42
 
42
 

+ 10
- 10
Marlin/src/HAL/SAMD51/timers.cpp View File

31
 // Local defines
31
 // Local defines
32
 // --------------------------------------------------------------------------
32
 // --------------------------------------------------------------------------
33
 
33
 
34
-#define NUM_HARDWARE_TIMERS 8
34
+#define NUM_HARDWARE_TIMERS 9
35
 
35
 
36
 // --------------------------------------------------------------------------
36
 // --------------------------------------------------------------------------
37
 // Private Variables
37
 // Private Variables
38
 // --------------------------------------------------------------------------
38
 // --------------------------------------------------------------------------
39
 
39
 
40
-const tTimerConfig TimerConfig[NUM_HARDWARE_TIMERS+1] = {
40
+const tTimerConfig timer_config[NUM_HARDWARE_TIMERS] = {
41
   { {.pTc=TC0},  TC0_IRQn, TC_PRIORITY(0) },  // 0 - stepper (assigned priority 2)
41
   { {.pTc=TC0},  TC0_IRQn, TC_PRIORITY(0) },  // 0 - stepper (assigned priority 2)
42
   { {.pTc=TC1},  TC1_IRQn, TC_PRIORITY(1) },  // 1 - stepper (needed by 32 bit timers)
42
   { {.pTc=TC1},  TC1_IRQn, TC_PRIORITY(1) },  // 1 - stepper (needed by 32 bit timers)
43
   { {.pTc=TC2},  TC2_IRQn, 5              },  // 2 - tone (reserved by framework and fixed assigned priority 5)
43
   { {.pTc=TC2},  TC2_IRQn, 5              },  // 2 - tone (reserved by framework and fixed assigned priority 5)
67
 // --------------------------------------------------------------------------
67
 // --------------------------------------------------------------------------
68
 
68
 
69
 void HAL_timer_start(const uint8_t timer_num, const uint32_t frequency) {
69
 void HAL_timer_start(const uint8_t timer_num, const uint32_t frequency) {
70
-  IRQn_Type irq = TimerConfig[timer_num].IRQ_Id;
70
+  IRQn_Type irq = timer_config[timer_num].IRQ_Id;
71
 
71
 
72
   // Disable interrupt, just in case it was already enabled
72
   // Disable interrupt, just in case it was already enabled
73
   Disable_Irq(irq);
73
   Disable_Irq(irq);
74
 
74
 
75
-  if (timer_num == RTC_TIMER_NUM) {
76
-    Rtc * const rtc = TimerConfig[timer_num].pRtc;
75
+  if (timer_num == MF_TIMER_RTC) {
76
+    Rtc * const rtc = timer_config[timer_num].pRtc;
77
 
77
 
78
     // Disable timer interrupt
78
     // Disable timer interrupt
79
     rtc->MODE0.INTENCLR.reg = RTC_MODE0_INTENCLR_CMP0;
79
     rtc->MODE0.INTENCLR.reg = RTC_MODE0_INTENCLR_CMP0;
101
     SYNC(rtc->MODE0.SYNCBUSY.bit.ENABLE);
101
     SYNC(rtc->MODE0.SYNCBUSY.bit.ENABLE);
102
   }
102
   }
103
   else {
103
   else {
104
-    Tc * const tc = TimerConfig[timer_num].pTc;
104
+    Tc * const tc = timer_config[timer_num].pTc;
105
 
105
 
106
     // Disable timer interrupt
106
     // Disable timer interrupt
107
     tc->COUNT32.INTENCLR.reg = TC_INTENCLR_OVF; // disable overflow interrupt
107
     tc->COUNT32.INTENCLR.reg = TC_INTENCLR_OVF; // disable overflow interrupt
141
   }
141
   }
142
 
142
 
143
   // Finally, enable IRQ
143
   // Finally, enable IRQ
144
-  NVIC_SetPriority(irq, TimerConfig[timer_num].priority);
144
+  NVIC_SetPriority(irq, timer_config[timer_num].priority);
145
   NVIC_EnableIRQ(irq);
145
   NVIC_EnableIRQ(irq);
146
 }
146
 }
147
 
147
 
148
 void HAL_timer_enable_interrupt(const uint8_t timer_num) {
148
 void HAL_timer_enable_interrupt(const uint8_t timer_num) {
149
-  const IRQn_Type irq = TimerConfig[timer_num].IRQ_Id;
149
+  const IRQn_Type irq = timer_config[timer_num].IRQ_Id;
150
   NVIC_EnableIRQ(irq);
150
   NVIC_EnableIRQ(irq);
151
 }
151
 }
152
 
152
 
153
 void HAL_timer_disable_interrupt(const uint8_t timer_num) {
153
 void HAL_timer_disable_interrupt(const uint8_t timer_num) {
154
-  const IRQn_Type irq = TimerConfig[timer_num].IRQ_Id;
154
+  const IRQn_Type irq = timer_config[timer_num].IRQ_Id;
155
   Disable_Irq(irq);
155
   Disable_Irq(irq);
156
 }
156
 }
157
 
157
 
161
 }
161
 }
162
 
162
 
163
 bool HAL_timer_interrupt_enabled(const uint8_t timer_num) {
163
 bool HAL_timer_interrupt_enabled(const uint8_t timer_num) {
164
-  const IRQn_Type irq = TimerConfig[timer_num].IRQ_Id;
164
+  const IRQn_Type irq = timer_config[timer_num].IRQ_Id;
165
   return NVIC_GetEnabledIRQ(irq);
165
   return NVIC_GetEnabledIRQ(irq);
166
 }
166
 }
167
 
167
 

+ 31
- 31
Marlin/src/HAL/SAMD51/timers.h View File

25
 // --------------------------------------------------------------------------
25
 // --------------------------------------------------------------------------
26
 // Defines
26
 // Defines
27
 // --------------------------------------------------------------------------
27
 // --------------------------------------------------------------------------
28
-#define RTC_TIMER_NUM       8   // This is not a TC but a RTC
29
 
28
 
30
 typedef uint32_t hal_timer_t;
29
 typedef uint32_t hal_timer_t;
31
 #define HAL_TIMER_TYPE_MAX 0xFFFFFFFF
30
 #define HAL_TIMER_TYPE_MAX 0xFFFFFFFF
32
 
31
 
33
 #define HAL_TIMER_RATE      F_CPU   // frequency of timers peripherals
32
 #define HAL_TIMER_RATE      F_CPU   // frequency of timers peripherals
34
 
33
 
35
-#ifndef STEP_TIMER_NUM
36
-  #define STEP_TIMER_NUM        0  // Timer Index for Stepper
34
+#define MF_TIMER_RTC            8   // This is not a TC but a RTC
35
+
36
+#ifndef MF_TIMER_STEP
37
+  #define MF_TIMER_STEP         0   // Timer Index for Stepper
37
 #endif
38
 #endif
38
-#ifndef PULSE_TIMER_NUM
39
-  #define PULSE_TIMER_NUM       STEP_TIMER_NUM
39
+#ifndef MF_TIMER_PULSE
40
+  #define MF_TIMER_PULSE        MF_TIMER_STEP
40
 #endif
41
 #endif
41
-#ifndef TEMP_TIMER_NUM
42
-  #define TEMP_TIMER_NUM        RTC_TIMER_NUM // Timer Index for Temperature
42
+#ifndef MF_TIMER_TEMP
43
+  #define MF_TIMER_TEMP         MF_TIMER_RTC // Timer Index for Temperature
43
 #endif
44
 #endif
44
 
45
 
45
 #define TEMP_TIMER_FREQUENCY   1000 // temperature interrupt frequency
46
 #define TEMP_TIMER_FREQUENCY   1000 // temperature interrupt frequency
52
 #define PULSE_TIMER_PRESCALE      STEPPER_TIMER_PRESCALE
53
 #define PULSE_TIMER_PRESCALE      STEPPER_TIMER_PRESCALE
53
 #define PULSE_TIMER_TICKS_PER_US  STEPPER_TIMER_TICKS_PER_US
54
 #define PULSE_TIMER_TICKS_PER_US  STEPPER_TIMER_TICKS_PER_US
54
 
55
 
55
-#define ENABLE_STEPPER_DRIVER_INTERRUPT()   HAL_timer_enable_interrupt(STEP_TIMER_NUM)
56
-#define DISABLE_STEPPER_DRIVER_INTERRUPT()  HAL_timer_disable_interrupt(STEP_TIMER_NUM)
57
-#define STEPPER_ISR_ENABLED()               HAL_timer_interrupt_enabled(STEP_TIMER_NUM)
56
+#define ENABLE_STEPPER_DRIVER_INTERRUPT()   HAL_timer_enable_interrupt(MF_TIMER_STEP)
57
+#define DISABLE_STEPPER_DRIVER_INTERRUPT()  HAL_timer_disable_interrupt(MF_TIMER_STEP)
58
+#define STEPPER_ISR_ENABLED()               HAL_timer_interrupt_enabled(MF_TIMER_STEP)
58
 
59
 
59
-#define ENABLE_TEMPERATURE_INTERRUPT()  HAL_timer_enable_interrupt(TEMP_TIMER_NUM)
60
-#define DISABLE_TEMPERATURE_INTERRUPT() HAL_timer_disable_interrupt(TEMP_TIMER_NUM)
60
+#define ENABLE_TEMPERATURE_INTERRUPT()  HAL_timer_enable_interrupt(MF_TIMER_TEMP)
61
+#define DISABLE_TEMPERATURE_INTERRUPT() HAL_timer_disable_interrupt(MF_TIMER_TEMP)
61
 
62
 
62
-#define TC_PRIORITY(t)        t == SERVO_TC ? 1                                     \
63
-                               : (t == STEP_TIMER_NUM || t == PULSE_TIMER_NUM) ? 2  \
64
-                               : (t == TEMP_TIMER_NUM) ? 6                          \
65
-                               : 7
63
+#define TC_PRIORITY(t)     (  t == SERVO_TC ? 1                              \
64
+                           : (t == MF_TIMER_STEP || t == MF_TIMER_PULSE) ? 2 \
65
+                           : (t == MF_TIMER_TEMP) ? 6 : 7 )
66
 
66
 
67
 #define _TC_HANDLER(t)          void TC##t##_Handler()
67
 #define _TC_HANDLER(t)          void TC##t##_Handler()
68
 #define TC_HANDLER(t)           _TC_HANDLER(t)
68
 #define TC_HANDLER(t)           _TC_HANDLER(t)
69
 #ifndef HAL_STEP_TIMER_ISR
69
 #ifndef HAL_STEP_TIMER_ISR
70
-  #define HAL_STEP_TIMER_ISR()  TC_HANDLER(STEP_TIMER_NUM)
70
+  #define HAL_STEP_TIMER_ISR()  TC_HANDLER(MF_TIMER_STEP)
71
 #endif
71
 #endif
72
-#if STEP_TIMER_NUM != PULSE_TIMER_NUM
73
-  #define HAL_PULSE_TIMER_ISR() TC_HANDLER(PULSE_TIMER_NUM)
72
+#if MF_TIMER_STEP != MF_TIMER_PULSE
73
+  #define HAL_PULSE_TIMER_ISR() TC_HANDLER(MF_TIMER_PULSE)
74
 #endif
74
 #endif
75
-#if TEMP_TIMER_NUM == RTC_TIMER_NUM
75
+#if MF_TIMER_TEMP == MF_TIMER_RTC
76
   #define HAL_TEMP_TIMER_ISR()  void RTC_Handler()
76
   #define HAL_TEMP_TIMER_ISR()  void RTC_Handler()
77
 #else
77
 #else
78
-  #define HAL_TEMP_TIMER_ISR()  TC_HANDLER(TEMP_TIMER_NUM)
78
+  #define HAL_TEMP_TIMER_ISR()  TC_HANDLER(MF_TIMER_TEMP)
79
 #endif
79
 #endif
80
 
80
 
81
 // --------------------------------------------------------------------------
81
 // --------------------------------------------------------------------------
95
 // Public Variables
95
 // Public Variables
96
 // --------------------------------------------------------------------------
96
 // --------------------------------------------------------------------------
97
 
97
 
98
-extern const tTimerConfig TimerConfig[];
98
+extern const tTimerConfig timer_config[];
99
 
99
 
100
 // --------------------------------------------------------------------------
100
 // --------------------------------------------------------------------------
101
 // Public functions
101
 // Public functions
104
 void HAL_timer_start(const uint8_t timer_num, const uint32_t frequency);
104
 void HAL_timer_start(const uint8_t timer_num, const uint32_t frequency);
105
 
105
 
106
 FORCE_INLINE static void HAL_timer_set_compare(const uint8_t timer_num, const hal_timer_t compare) {
106
 FORCE_INLINE static void HAL_timer_set_compare(const uint8_t timer_num, const hal_timer_t compare) {
107
-  // Should never be called with timer RTC_TIMER_NUM
108
-  Tc * const tc = TimerConfig[timer_num].pTc;
107
+  // Should never be called with timer MF_TIMER_RTC
108
+  Tc * const tc = timer_config[timer_num].pTc;
109
   tc->COUNT32.CC[0].reg = compare;
109
   tc->COUNT32.CC[0].reg = compare;
110
 }
110
 }
111
 
111
 
112
 FORCE_INLINE static hal_timer_t HAL_timer_get_compare(const uint8_t timer_num) {
112
 FORCE_INLINE static hal_timer_t HAL_timer_get_compare(const uint8_t timer_num) {
113
-  // Should never be called with timer RTC_TIMER_NUM
114
-  Tc * const tc = TimerConfig[timer_num].pTc;
113
+  // Should never be called with timer MF_TIMER_RTC
114
+  Tc * const tc = timer_config[timer_num].pTc;
115
   return (hal_timer_t)tc->COUNT32.CC[0].reg;
115
   return (hal_timer_t)tc->COUNT32.CC[0].reg;
116
 }
116
 }
117
 
117
 
118
 FORCE_INLINE static hal_timer_t HAL_timer_get_count(const uint8_t timer_num) {
118
 FORCE_INLINE static hal_timer_t HAL_timer_get_count(const uint8_t timer_num) {
119
-  // Should never be called with timer RTC_TIMER_NUM
120
-  Tc * const tc = TimerConfig[timer_num].pTc;
119
+  // Should never be called with timer MF_TIMER_RTC
120
+  Tc * const tc = timer_config[timer_num].pTc;
121
   tc->COUNT32.CTRLBSET.reg = TC_CTRLBCLR_CMD_READSYNC;
121
   tc->COUNT32.CTRLBSET.reg = TC_CTRLBCLR_CMD_READSYNC;
122
   SYNC(tc->COUNT32.SYNCBUSY.bit.CTRLB || tc->COUNT32.SYNCBUSY.bit.COUNT);
122
   SYNC(tc->COUNT32.SYNCBUSY.bit.CTRLB || tc->COUNT32.SYNCBUSY.bit.COUNT);
123
   return tc->COUNT32.COUNT.reg;
123
   return tc->COUNT32.COUNT.reg;
128
 bool HAL_timer_interrupt_enabled(const uint8_t timer_num);
128
 bool HAL_timer_interrupt_enabled(const uint8_t timer_num);
129
 
129
 
130
 FORCE_INLINE static void HAL_timer_isr_prologue(const uint8_t timer_num) {
130
 FORCE_INLINE static void HAL_timer_isr_prologue(const uint8_t timer_num) {
131
-  if (timer_num == RTC_TIMER_NUM) {
132
-    Rtc * const rtc = TimerConfig[timer_num].pRtc;
131
+  if (timer_num == MF_TIMER_RTC) {
132
+    Rtc * const rtc = timer_config[timer_num].pRtc;
133
     // Clear interrupt flag
133
     // Clear interrupt flag
134
     rtc->MODE0.INTFLAG.reg = RTC_MODE0_INTFLAG_CMP0;
134
     rtc->MODE0.INTFLAG.reg = RTC_MODE0_INTFLAG_CMP0;
135
   }
135
   }
136
   else {
136
   else {
137
-    Tc * const tc = TimerConfig[timer_num].pTc;
137
+    Tc * const tc = timer_config[timer_num].pTc;
138
     // Clear interrupt flag
138
     // Clear interrupt flag
139
     tc->COUNT32.INTFLAG.reg = TC_INTFLAG_OVF;
139
     tc->COUNT32.INTFLAG.reg = TC_INTFLAG_OVF;
140
   }
140
   }

+ 5
- 6
Marlin/src/HAL/STM32/fast_pwm.cpp View File

70
 
70
 
71
 void set_pwm_frequency(const pin_t pin, int f_desired) {
71
 void set_pwm_frequency(const pin_t pin, int f_desired) {
72
   if (!PWM_PIN(pin)) return; // Don't proceed if no hardware timer
72
   if (!PWM_PIN(pin)) return; // Don't proceed if no hardware timer
73
-  HardwareTimer *HT;
74
-  PinName pin_name = digitalPinToPinName(pin);
75
-  TIM_TypeDef *Instance = (TIM_TypeDef *)pinmap_peripheral(pin_name, PinMap_PWM); // Get HAL timer instance
76
 
73
 
77
   uint32_t index = get_timer_index(Instance);
74
   uint32_t index = get_timer_index(Instance);
78
 
75
 
83
     #endif
80
     #endif
84
   ) return;
81
   ) return;
85
 
82
 
86
-  if (HardwareTimer_Handle[index] == nullptr) // If frequency is set before duty we need to create a handle here. 
83
+  const PinName pin_name = digitalPinToPinName(pin);
84
+  TIM_TypeDef * const Instance = (TIM_TypeDef *)pinmap_peripheral(pin_name, PinMap_PWM); // Get HAL timer instance
85
+  if (HardwareTimer_Handle[index] == nullptr) // If frequency is set before duty we need to create a handle here.
87
     HardwareTimer_Handle[index]->__this = new HardwareTimer((TIM_TypeDef *)pinmap_peripheral(pin_name, PinMap_PWM));
86
     HardwareTimer_Handle[index]->__this = new HardwareTimer((TIM_TypeDef *)pinmap_peripheral(pin_name, PinMap_PWM));
88
-  HT = (HardwareTimer *)(HardwareTimer_Handle[index]->__this);
87
+  HardwareTimer * const HT = (HardwareTimer *)(HardwareTimer_Handle[index]->__this);
89
   timer_freq[index] = f_desired; // Save the last frequency so duty will not set the default for this timer number.
88
   timer_freq[index] = f_desired; // Save the last frequency so duty will not set the default for this timer number.
90
-  HT->setOverflow(f_desired, HERTZ_FORMAT);   
89
+  HT->setOverflow(f_desired, HERTZ_FORMAT);
91
 }
90
 }
92
 
91
 
93
 #endif // HAL_STM32
92
 #endif // HAL_STM32

+ 7
- 7
Marlin/src/HAL/STM32/timers.cpp View File

110
 uint32_t GetStepperTimerClkFreq() {
110
 uint32_t GetStepperTimerClkFreq() {
111
   // Timer input clocks vary between devices, and in some cases between timers on the same device.
111
   // Timer input clocks vary between devices, and in some cases between timers on the same device.
112
   // Retrieve at runtime to ensure device compatibility. Cache result to avoid repeated overhead.
112
   // Retrieve at runtime to ensure device compatibility. Cache result to avoid repeated overhead.
113
-  static uint32_t clkfreq = timer_instance[STEP_TIMER_NUM]->getTimerClkFreq();
113
+  static uint32_t clkfreq = timer_instance[MF_TIMER_STEP]->getTimerClkFreq();
114
   return clkfreq;
114
   return clkfreq;
115
 }
115
 }
116
 
116
 
118
 void HAL_timer_start(const uint8_t timer_num, const uint32_t frequency) {
118
 void HAL_timer_start(const uint8_t timer_num, const uint32_t frequency) {
119
   if (!HAL_timer_initialized(timer_num)) {
119
   if (!HAL_timer_initialized(timer_num)) {
120
     switch (timer_num) {
120
     switch (timer_num) {
121
-      case STEP_TIMER_NUM: // STEPPER TIMER - use a 32bit timer if possible
121
+      case MF_TIMER_STEP: // STEPPER TIMER - use a 32bit timer if possible
122
         timer_instance[timer_num] = new HardwareTimer(STEP_TIMER_DEV);
122
         timer_instance[timer_num] = new HardwareTimer(STEP_TIMER_DEV);
123
         /* Set the prescaler to the final desired value.
123
         /* Set the prescaler to the final desired value.
124
          * This will change the effective ISR callback frequency but when
124
          * This will change the effective ISR callback frequency but when
137
         timer_instance[timer_num]->setPrescaleFactor(STEPPER_TIMER_PRESCALE); //the -1 is done internally
137
         timer_instance[timer_num]->setPrescaleFactor(STEPPER_TIMER_PRESCALE); //the -1 is done internally
138
         timer_instance[timer_num]->setOverflow(_MIN(hal_timer_t(HAL_TIMER_TYPE_MAX), (HAL_TIMER_RATE) / (STEPPER_TIMER_PRESCALE) /* /frequency */), TICK_FORMAT);
138
         timer_instance[timer_num]->setOverflow(_MIN(hal_timer_t(HAL_TIMER_TYPE_MAX), (HAL_TIMER_RATE) / (STEPPER_TIMER_PRESCALE) /* /frequency */), TICK_FORMAT);
139
         break;
139
         break;
140
-      case TEMP_TIMER_NUM: // TEMP TIMER - any available 16bit timer
140
+      case MF_TIMER_TEMP: // TEMP TIMER - any available 16bit timer
141
         timer_instance[timer_num] = new HardwareTimer(TEMP_TIMER_DEV);
141
         timer_instance[timer_num] = new HardwareTimer(TEMP_TIMER_DEV);
142
         // The prescale factor is computed automatically for HERTZ_FORMAT
142
         // The prescale factor is computed automatically for HERTZ_FORMAT
143
         timer_instance[timer_num]->setOverflow(frequency, HERTZ_FORMAT);
143
         timer_instance[timer_num]->setOverflow(frequency, HERTZ_FORMAT);
157
     // These calls can be removed and replaced with
157
     // These calls can be removed and replaced with
158
     // timer_instance[timer_num]->setInterruptPriority
158
     // timer_instance[timer_num]->setInterruptPriority
159
     switch (timer_num) {
159
     switch (timer_num) {
160
-      case STEP_TIMER_NUM:
160
+      case MF_TIMER_STEP:
161
         timer_instance[timer_num]->setInterruptPriority(STEP_TIMER_IRQ_PRIO, 0);
161
         timer_instance[timer_num]->setInterruptPriority(STEP_TIMER_IRQ_PRIO, 0);
162
         break;
162
         break;
163
-      case TEMP_TIMER_NUM:
163
+      case MF_TIMER_TEMP:
164
         timer_instance[timer_num]->setInterruptPriority(TEMP_TIMER_IRQ_PRIO, 0);
164
         timer_instance[timer_num]->setInterruptPriority(TEMP_TIMER_IRQ_PRIO, 0);
165
         break;
165
         break;
166
     }
166
     }
170
 void HAL_timer_enable_interrupt(const uint8_t timer_num) {
170
 void HAL_timer_enable_interrupt(const uint8_t timer_num) {
171
   if (HAL_timer_initialized(timer_num) && !timer_instance[timer_num]->hasInterrupt()) {
171
   if (HAL_timer_initialized(timer_num) && !timer_instance[timer_num]->hasInterrupt()) {
172
     switch (timer_num) {
172
     switch (timer_num) {
173
-      case STEP_TIMER_NUM:
173
+      case MF_TIMER_STEP:
174
         timer_instance[timer_num]->attachInterrupt(Step_Handler);
174
         timer_instance[timer_num]->attachInterrupt(Step_Handler);
175
         break;
175
         break;
176
-      case TEMP_TIMER_NUM:
176
+      case MF_TIMER_TEMP:
177
         timer_instance[timer_num]->attachInterrupt(Temp_Handler);
177
         timer_instance[timer_num]->attachInterrupt(Temp_Handler);
178
         break;
178
         break;
179
     }
179
     }

+ 11
- 11
Marlin/src/HAL/STM32/timers.h View File

42
 
42
 
43
 #define NUM_HARDWARE_TIMERS 2
43
 #define NUM_HARDWARE_TIMERS 2
44
 
44
 
45
-#ifndef STEP_TIMER_NUM
46
-  #define STEP_TIMER_NUM        0  // Timer Index for Stepper
45
+#ifndef MF_TIMER_STEP
46
+  #define MF_TIMER_STEP         0  // Timer Index for Stepper
47
 #endif
47
 #endif
48
-#ifndef PULSE_TIMER_NUM
49
-  #define PULSE_TIMER_NUM       STEP_TIMER_NUM
48
+#ifndef MF_TIMER_PULSE
49
+  #define MF_TIMER_PULSE        MF_TIMER_STEP
50
 #endif
50
 #endif
51
-#ifndef TEMP_TIMER_NUM
52
-  #define TEMP_TIMER_NUM        1  // Timer Index for Temperature
51
+#ifndef MF_TIMER_TEMP
52
+  #define MF_TIMER_TEMP         1  // Timer Index for Temperature
53
 #endif
53
 #endif
54
 
54
 
55
 #define TEMP_TIMER_FREQUENCY 1000   // Temperature::isr() is expected to be called at around 1kHz
55
 #define TEMP_TIMER_FREQUENCY 1000   // Temperature::isr() is expected to be called at around 1kHz
64
 #define PULSE_TIMER_PRESCALE STEPPER_TIMER_PRESCALE
64
 #define PULSE_TIMER_PRESCALE STEPPER_TIMER_PRESCALE
65
 #define PULSE_TIMER_TICKS_PER_US STEPPER_TIMER_TICKS_PER_US
65
 #define PULSE_TIMER_TICKS_PER_US STEPPER_TIMER_TICKS_PER_US
66
 
66
 
67
-#define ENABLE_STEPPER_DRIVER_INTERRUPT() HAL_timer_enable_interrupt(STEP_TIMER_NUM)
68
-#define DISABLE_STEPPER_DRIVER_INTERRUPT() HAL_timer_disable_interrupt(STEP_TIMER_NUM)
69
-#define STEPPER_ISR_ENABLED() HAL_timer_interrupt_enabled(STEP_TIMER_NUM)
67
+#define ENABLE_STEPPER_DRIVER_INTERRUPT() HAL_timer_enable_interrupt(MF_TIMER_STEP)
68
+#define DISABLE_STEPPER_DRIVER_INTERRUPT() HAL_timer_disable_interrupt(MF_TIMER_STEP)
69
+#define STEPPER_ISR_ENABLED() HAL_timer_interrupt_enabled(MF_TIMER_STEP)
70
 
70
 
71
-#define ENABLE_TEMPERATURE_INTERRUPT() HAL_timer_enable_interrupt(TEMP_TIMER_NUM)
72
-#define DISABLE_TEMPERATURE_INTERRUPT() HAL_timer_disable_interrupt(TEMP_TIMER_NUM)
71
+#define ENABLE_TEMPERATURE_INTERRUPT() HAL_timer_enable_interrupt(MF_TIMER_TEMP)
72
+#define DISABLE_TEMPERATURE_INTERRUPT() HAL_timer_disable_interrupt(MF_TIMER_TEMP)
73
 
73
 
74
 extern void Step_Handler();
74
 extern void Step_Handler();
75
 extern void Temp_Handler();
75
 extern void Temp_Handler();

+ 2
- 2
Marlin/src/HAL/STM32F1/HAL.h View File

266
 
266
 
267
 #ifndef PWM_FREQUENCY
267
 #ifndef PWM_FREQUENCY
268
   #define PWM_FREQUENCY      1000 // Default PWM Frequency
268
   #define PWM_FREQUENCY      1000 // Default PWM Frequency
269
-#endif  
269
+#endif
270
 #define HAL_CAN_SET_PWM_FREQ      // This HAL supports PWM Frequency adjustment
270
 #define HAL_CAN_SET_PWM_FREQ      // This HAL supports PWM Frequency adjustment
271
 
271
 
272
 /**
272
 /**
281
  *  Set the PWM duty cycle of the provided pin to the provided value
281
  *  Set the PWM duty cycle of the provided pin to the provided value
282
  *  Optionally allows inverting the duty cycle [default = false]
282
  *  Optionally allows inverting the duty cycle [default = false]
283
  *  Optionally allows changing the maximum size of the provided value to enable finer PWM duty control [default = 255]
283
  *  Optionally allows changing the maximum size of the provided value to enable finer PWM duty control [default = 255]
284
- *  The timer must be pre-configured with set_pwm_frequency() if the default frequency is not desired.   
284
+ *  The timer must be pre-configured with set_pwm_frequency() if the default frequency is not desired.
285
  */
285
  */
286
 void set_pwm_duty(const pin_t pin, const uint16_t v, const uint16_t v_size=255, const bool invert=false);
286
 void set_pwm_duty(const pin_t pin, const uint16_t v, const uint16_t v_size=255, const bool invert=false);

+ 9
- 9
Marlin/src/HAL/STM32F1/Servo.cpp View File

60
 #define US_TO_ANGLE(us)    int16_t(map((us), SERVO_DEFAULT_MIN_PW, SERVO_DEFAULT_MAX_PW, minAngle, maxAngle))
60
 #define US_TO_ANGLE(us)    int16_t(map((us), SERVO_DEFAULT_MIN_PW, SERVO_DEFAULT_MAX_PW, minAngle, maxAngle))
61
 
61
 
62
 void libServo::servoWrite(uint8_t inPin, uint16_t duty_cycle) {
62
 void libServo::servoWrite(uint8_t inPin, uint16_t duty_cycle) {
63
-  #ifdef SERVO0_TIMER_NUM
63
+  #ifdef MF_TIMER_SERVO0
64
     if (servoIndex == 0) {
64
     if (servoIndex == 0) {
65
       pwmSetDuty(duty_cycle);
65
       pwmSetDuty(duty_cycle);
66
       return;
66
       return;
74
 
74
 
75
 libServo::libServo() {
75
 libServo::libServo() {
76
   servoIndex = ServoCount < MAX_SERVOS ? ServoCount++ : INVALID_SERVO;
76
   servoIndex = ServoCount < MAX_SERVOS ? ServoCount++ : INVALID_SERVO;
77
-  timer_set_interrupt_priority(SERVO0_TIMER_NUM, SERVO0_TIMER_IRQ_PRIO);
77
+  HAL_timer_set_interrupt_priority(MF_TIMER_SERVO0, SERVO0_TIMER_IRQ_PRIO);
78
 }
78
 }
79
 
79
 
80
 bool libServo::attach(const int32_t inPin, const int32_t inMinAngle, const int32_t inMaxAngle) {
80
 bool libServo::attach(const int32_t inPin, const int32_t inMinAngle, const int32_t inMaxAngle) {
85
   maxAngle = inMaxAngle;
85
   maxAngle = inMaxAngle;
86
   angle = -1;
86
   angle = -1;
87
 
87
 
88
-  #ifdef SERVO0_TIMER_NUM
88
+  #ifdef MF_TIMER_SERVO0
89
     if (servoIndex == 0 && setupSoftPWM(inPin)) {
89
     if (servoIndex == 0 && setupSoftPWM(inPin)) {
90
       pin = inPin; // set attached()
90
       pin = inPin; // set attached()
91
       return true;
91
       return true;
119
 
119
 
120
 int32_t libServo::read() const {
120
 int32_t libServo::read() const {
121
   if (attached()) {
121
   if (attached()) {
122
-    #ifdef SERVO0_TIMER_NUM
122
+    #ifdef MF_TIMER_SERVO0
123
       if (servoIndex == 0) return angle;
123
       if (servoIndex == 0) return angle;
124
     #endif
124
     #endif
125
     timer_dev *tdev = PIN_MAP[pin].timer_device;
125
     timer_dev *tdev = PIN_MAP[pin].timer_device;
141
   }
141
   }
142
 }
142
 }
143
 
143
 
144
-#ifdef SERVO0_TIMER_NUM
144
+#ifdef MF_TIMER_SERVO0
145
   extern "C" void Servo_IRQHandler() {
145
   extern "C" void Servo_IRQHandler() {
146
-    static timer_dev *tdev = get_timer_dev(SERVO0_TIMER_NUM);
146
+    static timer_dev *tdev = HAL_get_timer_dev(MF_TIMER_SERVO0);
147
     uint16_t SR = timer_get_status(tdev);
147
     uint16_t SR = timer_get_status(tdev);
148
     if (SR & TIMER_SR_CC1IF) { // channel 1 off
148
     if (SR & TIMER_SR_CC1IF) { // channel 1 off
149
       #ifdef SERVO0_PWM_OD
149
       #ifdef SERVO0_PWM_OD
164
   }
164
   }
165
 
165
 
166
   bool libServo::setupSoftPWM(const int32_t inPin) {
166
   bool libServo::setupSoftPWM(const int32_t inPin) {
167
-    timer_dev *tdev = get_timer_dev(SERVO0_TIMER_NUM);
167
+    timer_dev *tdev = HAL_get_timer_dev(MF_TIMER_SERVO0);
168
     if (!tdev) return false;
168
     if (!tdev) return false;
169
     #ifdef SERVO0_PWM_OD
169
     #ifdef SERVO0_PWM_OD
170
       OUT_WRITE_OD(inPin, 1);
170
       OUT_WRITE_OD(inPin, 1);
189
   }
189
   }
190
 
190
 
191
   void libServo::pwmSetDuty(const uint16_t duty_cycle) {
191
   void libServo::pwmSetDuty(const uint16_t duty_cycle) {
192
-    timer_dev *tdev = get_timer_dev(SERVO0_TIMER_NUM);
192
+    timer_dev *tdev = HAL_get_timer_dev(MF_TIMER_SERVO0);
193
     timer_set_compare(tdev, 1, duty_cycle);
193
     timer_set_compare(tdev, 1, duty_cycle);
194
     timer_generate_update(tdev);
194
     timer_generate_update(tdev);
195
     if (duty_cycle) {
195
     if (duty_cycle) {
208
   }
208
   }
209
 
209
 
210
   void libServo::pauseSoftPWM() { // detach
210
   void libServo::pauseSoftPWM() { // detach
211
-    timer_dev *tdev = get_timer_dev(SERVO0_TIMER_NUM);
211
+    timer_dev *tdev = HAL_get_timer_dev(MF_TIMER_SERVO0);
212
     timer_pause(tdev);
212
     timer_pause(tdev);
213
     pwmSetDuty(0);
213
     pwmSetDuty(0);
214
   }
214
   }

+ 4
- 5
Marlin/src/HAL/STM32F1/fast_pwm.cpp View File

35
   uint16_t max_val = timer->regs.bas->ARR * v / v_size;
35
   uint16_t max_val = timer->regs.bas->ARR * v / v_size;
36
   if (invert) max_val = v_size - max_val;
36
   if (invert) max_val = v_size - max_val;
37
   pwmWrite(pin, max_val);
37
   pwmWrite(pin, max_val);
38
-
39
 }
38
 }
40
 
39
 
41
 void set_pwm_frequency(const pin_t pin, int f_desired) {
40
 void set_pwm_frequency(const pin_t pin, int f_desired) {
45
   uint8_t channel = PIN_MAP[pin].timer_channel;
44
   uint8_t channel = PIN_MAP[pin].timer_channel;
46
 
45
 
47
   // Protect used timers
46
   // Protect used timers
48
-  if (timer == get_timer_dev(TEMP_TIMER_NUM)) return;
49
-  if (timer == get_timer_dev(STEP_TIMER_NUM)) return;
50
-  #if PULSE_TIMER_NUM != STEP_TIMER_NUM
51
-    if (timer == get_timer_dev(PULSE_TIMER_NUM)) return;
47
+  if (timer == HAL_get_timer_dev(MF_TIMER_TEMP)) return;
48
+  if (timer == HAL_get_timer_dev(MF_TIMER_STEP)) return;
49
+  #if MF_TIMER_PULSE != MF_TIMER_STEP
50
+    if (timer == HAL_get_timer_dev(MF_TIMER_PULSE)) return;
52
   #endif
51
   #endif
53
 
52
 
54
   if (!(timer->regs.bas->SR & TIMER_CR1_CEN))   // Ensure the timer is enabled
53
   if (!(timer->regs.bas->SR & TIMER_CR1_CEN))   // Ensure the timer is enabled

+ 13
- 17
Marlin/src/HAL/STM32F1/timers.cpp View File

47
  * TODO: Calculate Timer prescale value, so we get the 32bit to adjust
47
  * TODO: Calculate Timer prescale value, so we get the 32bit to adjust
48
  */
48
  */
49
 
49
 
50
-
51
-
52
-
53
-void timer_set_interrupt_priority(uint_fast8_t timer_num, uint_fast8_t priority) {
50
+void HAL_timer_set_interrupt_priority(uint_fast8_t timer_num, uint_fast8_t priority) {
54
   nvic_irq_num irq_num;
51
   nvic_irq_num irq_num;
55
   switch (timer_num) {
52
   switch (timer_num) {
56
     case 1: irq_num = NVIC_TIMER1_CC; break;
53
     case 1: irq_num = NVIC_TIMER1_CC; break;
73
   nvic_irq_set_priority(irq_num, priority);
70
   nvic_irq_set_priority(irq_num, priority);
74
 }
71
 }
75
 
72
 
76
-
77
 void HAL_timer_start(const uint8_t timer_num, const uint32_t frequency) {
73
 void HAL_timer_start(const uint8_t timer_num, const uint32_t frequency) {
78
   /**
74
   /**
79
    * Give the Stepper ISR a higher priority (lower number)
75
    * Give the Stepper ISR a higher priority (lower number)
81
    */
77
    */
82
 
78
 
83
   switch (timer_num) {
79
   switch (timer_num) {
84
-    case STEP_TIMER_NUM:
80
+    case MF_TIMER_STEP:
85
       timer_pause(STEP_TIMER_DEV);
81
       timer_pause(STEP_TIMER_DEV);
86
       timer_set_mode(STEP_TIMER_DEV, STEP_TIMER_CHAN, TIMER_OUTPUT_COMPARE); // counter
82
       timer_set_mode(STEP_TIMER_DEV, STEP_TIMER_CHAN, TIMER_OUTPUT_COMPARE); // counter
87
       timer_set_count(STEP_TIMER_DEV, 0);
83
       timer_set_count(STEP_TIMER_DEV, 0);
91
       timer_set_compare(STEP_TIMER_DEV, STEP_TIMER_CHAN, _MIN(hal_timer_t(HAL_TIMER_TYPE_MAX), (STEPPER_TIMER_RATE) / frequency));
87
       timer_set_compare(STEP_TIMER_DEV, STEP_TIMER_CHAN, _MIN(hal_timer_t(HAL_TIMER_TYPE_MAX), (STEPPER_TIMER_RATE) / frequency));
92
       timer_no_ARR_preload_ARPE(STEP_TIMER_DEV); // Need to be sure no preload on ARR register
88
       timer_no_ARR_preload_ARPE(STEP_TIMER_DEV); // Need to be sure no preload on ARR register
93
       timer_attach_interrupt(STEP_TIMER_DEV, STEP_TIMER_CHAN, stepTC_Handler);
89
       timer_attach_interrupt(STEP_TIMER_DEV, STEP_TIMER_CHAN, stepTC_Handler);
94
-      timer_set_interrupt_priority(STEP_TIMER_NUM, STEP_TIMER_IRQ_PRIO);
90
+      HAL_timer_set_interrupt_priority(MF_TIMER_STEP, STEP_TIMER_IRQ_PRIO);
95
       timer_generate_update(STEP_TIMER_DEV);
91
       timer_generate_update(STEP_TIMER_DEV);
96
       timer_resume(STEP_TIMER_DEV);
92
       timer_resume(STEP_TIMER_DEV);
97
       break;
93
       break;
98
-    case TEMP_TIMER_NUM:
94
+    case MF_TIMER_TEMP:
99
       timer_pause(TEMP_TIMER_DEV);
95
       timer_pause(TEMP_TIMER_DEV);
100
       timer_set_mode(TEMP_TIMER_DEV, TEMP_TIMER_CHAN, TIMER_OUTPUT_COMPARE);
96
       timer_set_mode(TEMP_TIMER_DEV, TEMP_TIMER_CHAN, TIMER_OUTPUT_COMPARE);
101
       timer_set_count(TEMP_TIMER_DEV, 0);
97
       timer_set_count(TEMP_TIMER_DEV, 0);
103
       timer_set_reload(TEMP_TIMER_DEV, 0xFFFF);
99
       timer_set_reload(TEMP_TIMER_DEV, 0xFFFF);
104
       timer_set_compare(TEMP_TIMER_DEV, TEMP_TIMER_CHAN, _MIN(hal_timer_t(HAL_TIMER_TYPE_MAX), (F_CPU) / (TEMP_TIMER_PRESCALE) / frequency));
100
       timer_set_compare(TEMP_TIMER_DEV, TEMP_TIMER_CHAN, _MIN(hal_timer_t(HAL_TIMER_TYPE_MAX), (F_CPU) / (TEMP_TIMER_PRESCALE) / frequency));
105
       timer_attach_interrupt(TEMP_TIMER_DEV, TEMP_TIMER_CHAN, tempTC_Handler);
101
       timer_attach_interrupt(TEMP_TIMER_DEV, TEMP_TIMER_CHAN, tempTC_Handler);
106
-      timer_set_interrupt_priority(TEMP_TIMER_NUM, TEMP_TIMER_IRQ_PRIO);
102
+      HAL_timer_set_interrupt_priority(MF_TIMER_TEMP, TEMP_TIMER_IRQ_PRIO);
107
       timer_generate_update(TEMP_TIMER_DEV);
103
       timer_generate_update(TEMP_TIMER_DEV);
108
       timer_resume(TEMP_TIMER_DEV);
104
       timer_resume(TEMP_TIMER_DEV);
109
       break;
105
       break;
112
 
108
 
113
 void HAL_timer_enable_interrupt(const uint8_t timer_num) {
109
 void HAL_timer_enable_interrupt(const uint8_t timer_num) {
114
   switch (timer_num) {
110
   switch (timer_num) {
115
-    case STEP_TIMER_NUM: ENABLE_STEPPER_DRIVER_INTERRUPT(); break;
116
-    case TEMP_TIMER_NUM: ENABLE_TEMPERATURE_INTERRUPT(); break;
111
+    case MF_TIMER_STEP: ENABLE_STEPPER_DRIVER_INTERRUPT(); break;
112
+    case MF_TIMER_TEMP: ENABLE_TEMPERATURE_INTERRUPT(); break;
117
   }
113
   }
118
 }
114
 }
119
 
115
 
120
 void HAL_timer_disable_interrupt(const uint8_t timer_num) {
116
 void HAL_timer_disable_interrupt(const uint8_t timer_num) {
121
   switch (timer_num) {
117
   switch (timer_num) {
122
-    case STEP_TIMER_NUM: DISABLE_STEPPER_DRIVER_INTERRUPT(); break;
123
-    case TEMP_TIMER_NUM: DISABLE_TEMPERATURE_INTERRUPT(); break;
118
+    case MF_TIMER_STEP: DISABLE_STEPPER_DRIVER_INTERRUPT(); break;
119
+    case MF_TIMER_TEMP: DISABLE_TEMPERATURE_INTERRUPT(); break;
124
   }
120
   }
125
 }
121
 }
126
 
122
 
127
-static inline bool timer_irq_enabled(const timer_dev * const dev, const uint8_t interrupt) {
123
+static inline bool HAL_timer_irq_enabled(const timer_dev * const dev, const uint8_t interrupt) {
128
   return bool(*bb_perip(&(dev->regs).gen->DIER, interrupt));
124
   return bool(*bb_perip(&(dev->regs).gen->DIER, interrupt));
129
 }
125
 }
130
 
126
 
131
 bool HAL_timer_interrupt_enabled(const uint8_t timer_num) {
127
 bool HAL_timer_interrupt_enabled(const uint8_t timer_num) {
132
   switch (timer_num) {
128
   switch (timer_num) {
133
-    case STEP_TIMER_NUM: return timer_irq_enabled(STEP_TIMER_DEV, STEP_TIMER_CHAN);
134
-    case TEMP_TIMER_NUM: return timer_irq_enabled(TEMP_TIMER_DEV, TEMP_TIMER_CHAN);
129
+    case MF_TIMER_STEP: return HAL_timer_irq_enabled(STEP_TIMER_DEV, STEP_TIMER_CHAN);
130
+    case MF_TIMER_TEMP: return HAL_timer_irq_enabled(TEMP_TIMER_DEV, TEMP_TIMER_CHAN);
135
   }
131
   }
136
   return false;
132
   return false;
137
 }
133
 }
138
 
134
 
139
-timer_dev* get_timer_dev(int number) {
135
+timer_dev* HAL_get_timer_dev(int number) {
140
   switch (number) {
136
   switch (number) {
141
     #if STM32_HAVE_TIMER(1)
137
     #if STM32_HAVE_TIMER(1)
142
       case 1: return &timer1;
138
       case 1: return &timer1;

+ 35
- 35
Marlin/src/HAL/STM32F1/timers.h View File

65
  *   - Otherwise it uses Timer 8 on boards with STM32_HIGH_DENSITY
65
  *   - Otherwise it uses Timer 8 on boards with STM32_HIGH_DENSITY
66
  *     or Timer 4 on other boards.
66
  *     or Timer 4 on other boards.
67
  */
67
  */
68
-#ifndef STEP_TIMER_NUM
68
+#ifndef MF_TIMER_STEP
69
   #if defined(MCU_STM32F103CB) || defined(MCU_STM32F103C8)
69
   #if defined(MCU_STM32F103CB) || defined(MCU_STM32F103C8)
70
-    #define STEP_TIMER_NUM      4  // For C8/CB boards, use timer 4
70
+    #define MF_TIMER_STEP       4  // For C8/CB boards, use timer 4
71
   #else
71
   #else
72
-    #define STEP_TIMER_NUM      5  // for other boards, five is fine.
72
+    #define MF_TIMER_STEP       5  // for other boards, five is fine.
73
   #endif
73
   #endif
74
 #endif
74
 #endif
75
-#ifndef PULSE_TIMER_NUM
76
-  #define PULSE_TIMER_NUM       STEP_TIMER_NUM
75
+#ifndef MF_TIMER_PULSE
76
+  #define MF_TIMER_PULSE        MF_TIMER_STEP
77
 #endif
77
 #endif
78
-#ifndef TEMP_TIMER_NUM
79
-  #define TEMP_TIMER_NUM        2  // Timer Index for Temperature
80
-  //#define TEMP_TIMER_NUM      4  // 2->4, Timer 2 for Stepper Current PWM
78
+#ifndef MF_TIMER_TEMP
79
+  #define MF_TIMER_TEMP         2  // Timer Index for Temperature
80
+  //#define MF_TIMER_TEMP       4  // 2->4, Timer 2 for Stepper Current PWM
81
 #endif
81
 #endif
82
 
82
 
83
 #if MB(BTT_SKR_MINI_E3_V1_0, BTT_SKR_E3_DIP, BTT_SKR_MINI_E3_V1_2, MKS_ROBIN_LITE, MKS_ROBIN_E3D, MKS_ROBIN_E3)
83
 #if MB(BTT_SKR_MINI_E3_V1_0, BTT_SKR_E3_DIP, BTT_SKR_MINI_E3_V1_2, MKS_ROBIN_LITE, MKS_ROBIN_E3D, MKS_ROBIN_E3)
84
   // SKR Mini E3 boards use PA8 as FAN_PIN, so TIMER 1 is used for Fan PWM.
84
   // SKR Mini E3 boards use PA8 as FAN_PIN, so TIMER 1 is used for Fan PWM.
85
   #ifdef STM32_HIGH_DENSITY
85
   #ifdef STM32_HIGH_DENSITY
86
-    #define SERVO0_TIMER_NUM 8  // tone.cpp uses Timer 4
86
+    #define MF_TIMER_SERVO0  8  // tone.cpp uses Timer 4
87
   #else
87
   #else
88
-    #define SERVO0_TIMER_NUM 3  // tone.cpp uses Timer 8
88
+    #define MF_TIMER_SERVO0  3  // tone.cpp uses Timer 8
89
   #endif
89
   #endif
90
 #else
90
 #else
91
-  #define SERVO0_TIMER_NUM 1  // SERVO0 or BLTOUCH
91
+  #define MF_TIMER_SERVO0  1  // SERVO0 or BLTOUCH
92
 #endif
92
 #endif
93
 
93
 
94
 #define STEP_TIMER_IRQ_PRIO 2
94
 #define STEP_TIMER_IRQ_PRIO 2
98
 #define TEMP_TIMER_PRESCALE     1000 // prescaler for setting Temp timer, 72Khz
98
 #define TEMP_TIMER_PRESCALE     1000 // prescaler for setting Temp timer, 72Khz
99
 #define TEMP_TIMER_FREQUENCY    1000 // temperature interrupt frequency
99
 #define TEMP_TIMER_FREQUENCY    1000 // temperature interrupt frequency
100
 
100
 
101
-#define STEPPER_TIMER_PRESCALE 18             // prescaler for setting stepper timer, 4Mhz
102
-#define STEPPER_TIMER_RATE     (HAL_TIMER_RATE / STEPPER_TIMER_PRESCALE)   // frequency of stepper timer
103
-#define STEPPER_TIMER_TICKS_PER_US ((STEPPER_TIMER_RATE) / 1000000) // stepper timer ticks per µs
101
+#define STEPPER_TIMER_PRESCALE      18                                          // prescaler for setting stepper timer, 4Mhz
102
+#define STEPPER_TIMER_RATE          (HAL_TIMER_RATE / STEPPER_TIMER_PRESCALE)   // frequency of stepper timer
103
+#define STEPPER_TIMER_TICKS_PER_US  ((STEPPER_TIMER_RATE) / 1000000)            // stepper timer ticks per µs
104
 
104
 
105
-#define PULSE_TIMER_RATE       STEPPER_TIMER_RATE   // frequency of pulse timer
106
-#define PULSE_TIMER_PRESCALE   STEPPER_TIMER_PRESCALE
107
-#define PULSE_TIMER_TICKS_PER_US STEPPER_TIMER_TICKS_PER_US
105
+#define PULSE_TIMER_RATE            STEPPER_TIMER_RATE   // frequency of pulse timer
106
+#define PULSE_TIMER_PRESCALE        STEPPER_TIMER_PRESCALE
107
+#define PULSE_TIMER_TICKS_PER_US    STEPPER_TIMER_TICKS_PER_US
108
 
108
 
109
-timer_dev* get_timer_dev(int number);
110
-#define TIMER_DEV(num) get_timer_dev(num)
111
-#define STEP_TIMER_DEV TIMER_DEV(STEP_TIMER_NUM)
112
-#define TEMP_TIMER_DEV TIMER_DEV(TEMP_TIMER_NUM)
109
+timer_dev* HAL_get_timer_dev(int number);
110
+#define TIMER_DEV(num) HAL_get_timer_dev(num)
111
+#define STEP_TIMER_DEV TIMER_DEV(MF_TIMER_STEP)
112
+#define TEMP_TIMER_DEV TIMER_DEV(MF_TIMER_TEMP)
113
 
113
 
114
 #define ENABLE_STEPPER_DRIVER_INTERRUPT() timer_enable_irq(STEP_TIMER_DEV, STEP_TIMER_CHAN)
114
 #define ENABLE_STEPPER_DRIVER_INTERRUPT() timer_enable_irq(STEP_TIMER_DEV, STEP_TIMER_CHAN)
115
 #define DISABLE_STEPPER_DRIVER_INTERRUPT() timer_disable_irq(STEP_TIMER_DEV, STEP_TIMER_CHAN)
115
 #define DISABLE_STEPPER_DRIVER_INTERRUPT() timer_disable_irq(STEP_TIMER_DEV, STEP_TIMER_CHAN)
116
-#define STEPPER_ISR_ENABLED() HAL_timer_interrupt_enabled(STEP_TIMER_NUM)
116
+#define STEPPER_ISR_ENABLED() HAL_timer_interrupt_enabled(MF_TIMER_STEP)
117
 
117
 
118
 #define ENABLE_TEMPERATURE_INTERRUPT() timer_enable_irq(TEMP_TIMER_DEV, TEMP_TIMER_CHAN)
118
 #define ENABLE_TEMPERATURE_INTERRUPT() timer_enable_irq(TEMP_TIMER_DEV, TEMP_TIMER_CHAN)
119
 #define DISABLE_TEMPERATURE_INTERRUPT() timer_disable_irq(TEMP_TIMER_DEV, TEMP_TIMER_CHAN)
119
 #define DISABLE_TEMPERATURE_INTERRUPT() timer_disable_irq(TEMP_TIMER_DEV, TEMP_TIMER_CHAN)
138
 // Public Variables
138
 // Public Variables
139
 // ------------------------
139
 // ------------------------
140
 
140
 
141
-//static HardwareTimer StepperTimer(STEP_TIMER_NUM);
142
-//static HardwareTimer TempTimer(TEMP_TIMER_NUM);
141
+//static HardwareTimer StepperTimer(MF_TIMER_STEP);
142
+//static HardwareTimer TempTimer(MF_TIMER_TEMP);
143
 
143
 
144
 // ------------------------
144
 // ------------------------
145
 // Public functions
145
 // Public functions
163
 
163
 
164
 FORCE_INLINE static void HAL_timer_set_compare(const uint8_t timer_num, const hal_timer_t compare) {
164
 FORCE_INLINE static void HAL_timer_set_compare(const uint8_t timer_num, const hal_timer_t compare) {
165
   switch (timer_num) {
165
   switch (timer_num) {
166
-  case STEP_TIMER_NUM:
166
+  case MF_TIMER_STEP:
167
     // NOTE: WE have set ARPE = 0, which means the Auto reload register is not preloaded
167
     // NOTE: WE have set ARPE = 0, which means the Auto reload register is not preloaded
168
     // and there is no need to use any compare, as in the timer mode used, setting ARR to the compare value
168
     // and there is no need to use any compare, as in the timer mode used, setting ARR to the compare value
169
     // will result in exactly the same effect, ie triggering an interrupt, and on top, set counter to 0
169
     // will result in exactly the same effect, ie triggering an interrupt, and on top, set counter to 0
170
     timer_set_reload(STEP_TIMER_DEV, compare); // We reload direct ARR as needed during counting up
170
     timer_set_reload(STEP_TIMER_DEV, compare); // We reload direct ARR as needed during counting up
171
     break;
171
     break;
172
-  case TEMP_TIMER_NUM:
172
+  case MF_TIMER_TEMP:
173
     timer_set_compare(TEMP_TIMER_DEV, TEMP_TIMER_CHAN, compare);
173
     timer_set_compare(TEMP_TIMER_DEV, TEMP_TIMER_CHAN, compare);
174
     break;
174
     break;
175
   }
175
   }
177
 
177
 
178
 FORCE_INLINE static void HAL_timer_isr_prologue(const uint8_t timer_num) {
178
 FORCE_INLINE static void HAL_timer_isr_prologue(const uint8_t timer_num) {
179
   switch (timer_num) {
179
   switch (timer_num) {
180
-  case STEP_TIMER_NUM:
181
-    // No counter to clear
182
-    timer_generate_update(STEP_TIMER_DEV);
183
-    return;
184
-  case TEMP_TIMER_NUM:
185
-    timer_set_count(TEMP_TIMER_DEV, 0);
186
-    timer_generate_update(TEMP_TIMER_DEV);
187
-    return;
180
+    case MF_TIMER_STEP:
181
+      // No counter to clear
182
+      timer_generate_update(STEP_TIMER_DEV);
183
+      return;
184
+    case MF_TIMER_TEMP:
185
+      timer_set_count(TEMP_TIMER_DEV, 0);
186
+      timer_generate_update(TEMP_TIMER_DEV);
187
+      return;
188
   }
188
   }
189
 }
189
 }
190
 
190
 
196
   bb_peri_set_bit(&(dev->regs).gen->CR1, TIMER_CR1_ARPE_BIT, 0);
196
   bb_peri_set_bit(&(dev->regs).gen->CR1, TIMER_CR1_ARPE_BIT, 0);
197
 }
197
 }
198
 
198
 
199
-void timer_set_interrupt_priority(uint_fast8_t timer_num, uint_fast8_t priority);
199
+void HAL_timer_set_interrupt_priority(uint_fast8_t timer_num, uint_fast8_t priority);
200
 
200
 
201
 #define TIMER_OC_NO_PRELOAD 0 // Need to disable preload also on compare registers.
201
 #define TIMER_OC_NO_PRELOAD 0 // Need to disable preload also on compare registers.

+ 10
- 10
Marlin/src/HAL/TEENSY31_32/timers.cpp View File

47
 
47
 
48
 void HAL_timer_start(const uint8_t timer_num, const uint32_t frequency) {
48
 void HAL_timer_start(const uint8_t timer_num, const uint32_t frequency) {
49
   switch (timer_num) {
49
   switch (timer_num) {
50
-    case 0:
50
+    case MF_TIMER_STEP:
51
       FTM0_MODE = FTM_MODE_WPDIS | FTM_MODE_FTMEN;
51
       FTM0_MODE = FTM_MODE_WPDIS | FTM_MODE_FTMEN;
52
       FTM0_SC = 0x00; // Set this to zero before changing the modulus
52
       FTM0_SC = 0x00; // Set this to zero before changing the modulus
53
       FTM0_CNT = 0x0000; // Reset the count to zero
53
       FTM0_CNT = 0x0000; // Reset the count to zero
56
       FTM0_SC = (FTM_SC_CLKS(0b1) & FTM_SC_CLKS_MASK) | (FTM_SC_PS(FTM0_TIMER_PRESCALE_BITS) & FTM_SC_PS_MASK); // Bus clock 60MHz divided by prescaler 8
56
       FTM0_SC = (FTM_SC_CLKS(0b1) & FTM_SC_CLKS_MASK) | (FTM_SC_PS(FTM0_TIMER_PRESCALE_BITS) & FTM_SC_PS_MASK); // Bus clock 60MHz divided by prescaler 8
57
       FTM0_C0SC = FTM_CSC_CHIE | FTM_CSC_MSA | FTM_CSC_ELSA;
57
       FTM0_C0SC = FTM_CSC_CHIE | FTM_CSC_MSA | FTM_CSC_ELSA;
58
       break;
58
       break;
59
-    case 1:
59
+    case MF_TIMER_TEMP:
60
       FTM1_MODE = FTM_MODE_WPDIS | FTM_MODE_FTMEN; // Disable write protection, Enable FTM1
60
       FTM1_MODE = FTM_MODE_WPDIS | FTM_MODE_FTMEN; // Disable write protection, Enable FTM1
61
       FTM1_SC = 0x00; // Set this to zero before changing the modulus
61
       FTM1_SC = 0x00; // Set this to zero before changing the modulus
62
       FTM1_CNT = 0x0000; // Reset the count to zero
62
       FTM1_CNT = 0x0000; // Reset the count to zero
70
 
70
 
71
 void HAL_timer_enable_interrupt(const uint8_t timer_num) {
71
 void HAL_timer_enable_interrupt(const uint8_t timer_num) {
72
   switch (timer_num) {
72
   switch (timer_num) {
73
-    case 0: NVIC_ENABLE_IRQ(IRQ_FTM0); break;
74
-    case 1: NVIC_ENABLE_IRQ(IRQ_FTM1); break;
73
+    case MF_TIMER_STEP: NVIC_ENABLE_IRQ(IRQ_FTM0); break;
74
+    case MF_TIMER_TEMP: NVIC_ENABLE_IRQ(IRQ_FTM1); break;
75
   }
75
   }
76
 }
76
 }
77
 
77
 
78
 void HAL_timer_disable_interrupt(const uint8_t timer_num) {
78
 void HAL_timer_disable_interrupt(const uint8_t timer_num) {
79
   switch (timer_num) {
79
   switch (timer_num) {
80
-    case 0: NVIC_DISABLE_IRQ(IRQ_FTM0); break;
81
-    case 1: NVIC_DISABLE_IRQ(IRQ_FTM1); break;
80
+    case MF_TIMER_STEP: NVIC_DISABLE_IRQ(IRQ_FTM0); break;
81
+    case MF_TIMER_TEMP: NVIC_DISABLE_IRQ(IRQ_FTM1); break;
82
   }
82
   }
83
 
83
 
84
   // We NEED memory barriers to ensure Interrupts are actually disabled!
84
   // We NEED memory barriers to ensure Interrupts are actually disabled!
89
 
89
 
90
 bool HAL_timer_interrupt_enabled(const uint8_t timer_num) {
90
 bool HAL_timer_interrupt_enabled(const uint8_t timer_num) {
91
   switch (timer_num) {
91
   switch (timer_num) {
92
-    case 0: return NVIC_IS_ENABLED(IRQ_FTM0);
93
-    case 1: return NVIC_IS_ENABLED(IRQ_FTM1);
92
+    case MF_TIMER_STEP: return NVIC_IS_ENABLED(IRQ_FTM0);
93
+    case MF_TIMER_TEMP: return NVIC_IS_ENABLED(IRQ_FTM1);
94
   }
94
   }
95
   return false;
95
   return false;
96
 }
96
 }
97
 
97
 
98
 void HAL_timer_isr_prologue(const uint8_t timer_num) {
98
 void HAL_timer_isr_prologue(const uint8_t timer_num) {
99
   switch (timer_num) {
99
   switch (timer_num) {
100
-    case 0:
100
+    case MF_TIMER_STEP:
101
       FTM0_CNT = 0x0000;
101
       FTM0_CNT = 0x0000;
102
       FTM0_SC &= ~FTM_SC_TOF; // Clear FTM Overflow flag
102
       FTM0_SC &= ~FTM_SC_TOF; // Clear FTM Overflow flag
103
       FTM0_C0SC &= ~FTM_CSC_CHF; // Clear FTM Channel Compare flag
103
       FTM0_C0SC &= ~FTM_CSC_CHF; // Clear FTM Channel Compare flag
104
       break;
104
       break;
105
-    case 1:
105
+    case MF_TIMER_TEMP:
106
       FTM1_CNT = 0x0000;
106
       FTM1_CNT = 0x0000;
107
       FTM1_SC &= ~FTM_SC_TOF; // Clear FTM Overflow flag
107
       FTM1_SC &= ~FTM_SC_TOF; // Clear FTM Overflow flag
108
       FTM1_C0SC &= ~FTM_CSC_CHF; // Clear FTM Channel Compare flag
108
       FTM1_C0SC &= ~FTM_CSC_CHF; // Clear FTM Channel Compare flag

+ 17
- 17
Marlin/src/HAL/TEENSY31_32/timers.h View File

46
 
46
 
47
 #define HAL_TIMER_RATE         (FTM0_TIMER_RATE)
47
 #define HAL_TIMER_RATE         (FTM0_TIMER_RATE)
48
 
48
 
49
-#ifndef STEP_TIMER_NUM
50
-  #define STEP_TIMER_NUM        0  // Timer Index for Stepper
49
+#ifndef MF_TIMER_STEP
50
+  #define MF_TIMER_STEP         0  // Timer Index for Stepper
51
 #endif
51
 #endif
52
-#ifndef PULSE_TIMER_NUM
53
-  #define PULSE_TIMER_NUM       STEP_TIMER_NUM
52
+#ifndef MF_TIMER_PULSE
53
+  #define MF_TIMER_PULSE        MF_TIMER_STEP
54
 #endif
54
 #endif
55
-#ifndef TEMP_TIMER_NUM
56
-  #define TEMP_TIMER_NUM        1  // Timer Index for Temperature
55
+#ifndef MF_TIMER_TEMP
56
+  #define MF_TIMER_TEMP         1  // Timer Index for Temperature
57
 #endif
57
 #endif
58
 
58
 
59
 #define TEMP_TIMER_FREQUENCY    1000
59
 #define TEMP_TIMER_FREQUENCY    1000
66
 #define PULSE_TIMER_PRESCALE   STEPPER_TIMER_PRESCALE
66
 #define PULSE_TIMER_PRESCALE   STEPPER_TIMER_PRESCALE
67
 #define PULSE_TIMER_TICKS_PER_US STEPPER_TIMER_TICKS_PER_US
67
 #define PULSE_TIMER_TICKS_PER_US STEPPER_TIMER_TICKS_PER_US
68
 
68
 
69
-#define ENABLE_STEPPER_DRIVER_INTERRUPT() HAL_timer_enable_interrupt(STEP_TIMER_NUM)
70
-#define DISABLE_STEPPER_DRIVER_INTERRUPT() HAL_timer_disable_interrupt(STEP_TIMER_NUM)
71
-#define STEPPER_ISR_ENABLED() HAL_timer_interrupt_enabled(STEP_TIMER_NUM)
69
+#define ENABLE_STEPPER_DRIVER_INTERRUPT() HAL_timer_enable_interrupt(MF_TIMER_STEP)
70
+#define DISABLE_STEPPER_DRIVER_INTERRUPT() HAL_timer_disable_interrupt(MF_TIMER_STEP)
71
+#define STEPPER_ISR_ENABLED() HAL_timer_interrupt_enabled(MF_TIMER_STEP)
72
 
72
 
73
-#define ENABLE_TEMPERATURE_INTERRUPT() HAL_timer_enable_interrupt(TEMP_TIMER_NUM)
74
-#define DISABLE_TEMPERATURE_INTERRUPT() HAL_timer_disable_interrupt(TEMP_TIMER_NUM)
73
+#define ENABLE_TEMPERATURE_INTERRUPT() HAL_timer_enable_interrupt(MF_TIMER_TEMP)
74
+#define DISABLE_TEMPERATURE_INTERRUPT() HAL_timer_disable_interrupt(MF_TIMER_TEMP)
75
 
75
 
76
 #ifndef HAL_STEP_TIMER_ISR
76
 #ifndef HAL_STEP_TIMER_ISR
77
   #define HAL_STEP_TIMER_ISR() extern "C" void ftm0_isr() //void TC3_Handler()
77
   #define HAL_STEP_TIMER_ISR() extern "C" void ftm0_isr() //void TC3_Handler()
84
 
84
 
85
 FORCE_INLINE static void HAL_timer_set_compare(const uint8_t timer_num, const hal_timer_t compare) {
85
 FORCE_INLINE static void HAL_timer_set_compare(const uint8_t timer_num, const hal_timer_t compare) {
86
   switch (timer_num) {
86
   switch (timer_num) {
87
-    case 0: FTM0_C0V = compare; break;
88
-    case 1: FTM1_C0V = compare; break;
87
+    case MF_TIMER_STEP: FTM0_C0V = compare; break;
88
+    case MF_TIMER_TEMP: FTM1_C0V = compare; break;
89
   }
89
   }
90
 }
90
 }
91
 
91
 
92
 FORCE_INLINE static hal_timer_t HAL_timer_get_compare(const uint8_t timer_num) {
92
 FORCE_INLINE static hal_timer_t HAL_timer_get_compare(const uint8_t timer_num) {
93
   switch (timer_num) {
93
   switch (timer_num) {
94
-    case 0: return FTM0_C0V;
95
-    case 1: return FTM1_C0V;
94
+    case MF_TIMER_STEP: return FTM0_C0V;
95
+    case MF_TIMER_TEMP: return FTM1_C0V;
96
   }
96
   }
97
   return 0;
97
   return 0;
98
 }
98
 }
99
 
99
 
100
 FORCE_INLINE static hal_timer_t HAL_timer_get_count(const uint8_t timer_num) {
100
 FORCE_INLINE static hal_timer_t HAL_timer_get_count(const uint8_t timer_num) {
101
   switch (timer_num) {
101
   switch (timer_num) {
102
-    case 0: return FTM0_CNT;
103
-    case 1: return FTM1_CNT;
102
+    case MF_TIMER_STEP: return FTM0_CNT;
103
+    case MF_TIMER_TEMP: return FTM1_CNT;
104
   }
104
   }
105
   return 0;
105
   return 0;
106
 }
106
 }

+ 10
- 10
Marlin/src/HAL/TEENSY35_36/timers.cpp View File

47
 
47
 
48
 void HAL_timer_start(const uint8_t timer_num, const uint32_t frequency) {
48
 void HAL_timer_start(const uint8_t timer_num, const uint32_t frequency) {
49
   switch (timer_num) {
49
   switch (timer_num) {
50
-    case 0:
50
+    case MF_TIMER_STEP:
51
       FTM0_MODE = FTM_MODE_WPDIS | FTM_MODE_FTMEN;
51
       FTM0_MODE = FTM_MODE_WPDIS | FTM_MODE_FTMEN;
52
       FTM0_SC = 0x00; // Set this to zero before changing the modulus
52
       FTM0_SC = 0x00; // Set this to zero before changing the modulus
53
       FTM0_CNT = 0x0000; // Reset the count to zero
53
       FTM0_CNT = 0x0000; // Reset the count to zero
56
       FTM0_SC = (FTM_SC_CLKS(0b1) & FTM_SC_CLKS_MASK) | (FTM_SC_PS(FTM0_TIMER_PRESCALE_BITS) & FTM_SC_PS_MASK); // Bus clock 60MHz divided by prescaler 8
56
       FTM0_SC = (FTM_SC_CLKS(0b1) & FTM_SC_CLKS_MASK) | (FTM_SC_PS(FTM0_TIMER_PRESCALE_BITS) & FTM_SC_PS_MASK); // Bus clock 60MHz divided by prescaler 8
57
       FTM0_C0SC = FTM_CSC_CHIE | FTM_CSC_MSA | FTM_CSC_ELSA;
57
       FTM0_C0SC = FTM_CSC_CHIE | FTM_CSC_MSA | FTM_CSC_ELSA;
58
       break;
58
       break;
59
-    case 1:
59
+    case MF_TIMER_TEMP:
60
       FTM1_MODE = FTM_MODE_WPDIS | FTM_MODE_FTMEN; // Disable write protection, Enable FTM1
60
       FTM1_MODE = FTM_MODE_WPDIS | FTM_MODE_FTMEN; // Disable write protection, Enable FTM1
61
       FTM1_SC = 0x00; // Set this to zero before changing the modulus
61
       FTM1_SC = 0x00; // Set this to zero before changing the modulus
62
       FTM1_CNT = 0x0000; // Reset the count to zero
62
       FTM1_CNT = 0x0000; // Reset the count to zero
70
 
70
 
71
 void HAL_timer_enable_interrupt(const uint8_t timer_num) {
71
 void HAL_timer_enable_interrupt(const uint8_t timer_num) {
72
   switch (timer_num) {
72
   switch (timer_num) {
73
-    case 0: NVIC_ENABLE_IRQ(IRQ_FTM0); break;
74
-    case 1: NVIC_ENABLE_IRQ(IRQ_FTM1); break;
73
+    case MF_TIMER_STEP: NVIC_ENABLE_IRQ(IRQ_FTM0); break;
74
+    case MF_TIMER_TEMP: NVIC_ENABLE_IRQ(IRQ_FTM1); break;
75
   }
75
   }
76
 }
76
 }
77
 
77
 
78
 void HAL_timer_disable_interrupt(const uint8_t timer_num) {
78
 void HAL_timer_disable_interrupt(const uint8_t timer_num) {
79
   switch (timer_num) {
79
   switch (timer_num) {
80
-    case 0: NVIC_DISABLE_IRQ(IRQ_FTM0); break;
81
-    case 1: NVIC_DISABLE_IRQ(IRQ_FTM1); break;
80
+    case MF_TIMER_STEP: NVIC_DISABLE_IRQ(IRQ_FTM0); break;
81
+    case MF_TIMER_TEMP: NVIC_DISABLE_IRQ(IRQ_FTM1); break;
82
   }
82
   }
83
 
83
 
84
   // We NEED memory barriers to ensure Interrupts are actually disabled!
84
   // We NEED memory barriers to ensure Interrupts are actually disabled!
89
 
89
 
90
 bool HAL_timer_interrupt_enabled(const uint8_t timer_num) {
90
 bool HAL_timer_interrupt_enabled(const uint8_t timer_num) {
91
   switch (timer_num) {
91
   switch (timer_num) {
92
-    case 0: return NVIC_IS_ENABLED(IRQ_FTM0);
93
-    case 1: return NVIC_IS_ENABLED(IRQ_FTM1);
92
+    case MF_TIMER_STEP: return NVIC_IS_ENABLED(IRQ_FTM0);
93
+    case MF_TIMER_TEMP: return NVIC_IS_ENABLED(IRQ_FTM1);
94
   }
94
   }
95
   return false;
95
   return false;
96
 }
96
 }
97
 
97
 
98
 void HAL_timer_isr_prologue(const uint8_t timer_num) {
98
 void HAL_timer_isr_prologue(const uint8_t timer_num) {
99
   switch (timer_num) {
99
   switch (timer_num) {
100
-    case 0:
100
+    case MF_TIMER_STEP:
101
       FTM0_CNT = 0x0000;
101
       FTM0_CNT = 0x0000;
102
       FTM0_SC &= ~FTM_SC_TOF; // Clear FTM Overflow flag
102
       FTM0_SC &= ~FTM_SC_TOF; // Clear FTM Overflow flag
103
       FTM0_C0SC &= ~FTM_CSC_CHF; // Clear FTM Channel Compare flag
103
       FTM0_C0SC &= ~FTM_CSC_CHF; // Clear FTM Channel Compare flag
104
       break;
104
       break;
105
-    case 1:
105
+    case MF_TIMER_TEMP:
106
       FTM1_CNT = 0x0000;
106
       FTM1_CNT = 0x0000;
107
       FTM1_SC &= ~FTM_SC_TOF; // Clear FTM Overflow flag
107
       FTM1_SC &= ~FTM_SC_TOF; // Clear FTM Overflow flag
108
       FTM1_C0SC &= ~FTM_CSC_CHF; // Clear FTM Channel Compare flag
108
       FTM1_C0SC &= ~FTM_CSC_CHF; // Clear FTM Channel Compare flag

+ 17
- 17
Marlin/src/HAL/TEENSY35_36/timers.h View File

45
 
45
 
46
 #define HAL_TIMER_RATE         (FTM0_TIMER_RATE)
46
 #define HAL_TIMER_RATE         (FTM0_TIMER_RATE)
47
 
47
 
48
-#ifndef STEP_TIMER_NUM
49
-  #define STEP_TIMER_NUM        0  // Timer Index for Stepper
48
+#ifndef MF_TIMER_STEP
49
+  #define MF_TIMER_STEP         0  // Timer Index for Stepper
50
 #endif
50
 #endif
51
-#ifndef PULSE_TIMER_NUM
52
-  #define PULSE_TIMER_NUM       STEP_TIMER_NUM
51
+#ifndef MF_TIMER_PULSE
52
+  #define MF_TIMER_PULSE        MF_TIMER_STEP
53
 #endif
53
 #endif
54
-#ifndef TEMP_TIMER_NUM
55
-  #define TEMP_TIMER_NUM        1  // Timer Index for Temperature
54
+#ifndef MF_TIMER_TEMP
55
+  #define MF_TIMER_TEMP         1  // Timer Index for Temperature
56
 #endif
56
 #endif
57
 
57
 
58
 #define TEMP_TIMER_FREQUENCY    1000
58
 #define TEMP_TIMER_FREQUENCY    1000
65
 #define PULSE_TIMER_PRESCALE   STEPPER_TIMER_PRESCALE
65
 #define PULSE_TIMER_PRESCALE   STEPPER_TIMER_PRESCALE
66
 #define PULSE_TIMER_TICKS_PER_US STEPPER_TIMER_TICKS_PER_US
66
 #define PULSE_TIMER_TICKS_PER_US STEPPER_TIMER_TICKS_PER_US
67
 
67
 
68
-#define ENABLE_STEPPER_DRIVER_INTERRUPT() HAL_timer_enable_interrupt(STEP_TIMER_NUM)
69
-#define DISABLE_STEPPER_DRIVER_INTERRUPT() HAL_timer_disable_interrupt(STEP_TIMER_NUM)
70
-#define STEPPER_ISR_ENABLED() HAL_timer_interrupt_enabled(STEP_TIMER_NUM)
68
+#define ENABLE_STEPPER_DRIVER_INTERRUPT() HAL_timer_enable_interrupt(MF_TIMER_STEP)
69
+#define DISABLE_STEPPER_DRIVER_INTERRUPT() HAL_timer_disable_interrupt(MF_TIMER_STEP)
70
+#define STEPPER_ISR_ENABLED() HAL_timer_interrupt_enabled(MF_TIMER_STEP)
71
 
71
 
72
-#define ENABLE_TEMPERATURE_INTERRUPT() HAL_timer_enable_interrupt(TEMP_TIMER_NUM)
73
-#define DISABLE_TEMPERATURE_INTERRUPT() HAL_timer_disable_interrupt(TEMP_TIMER_NUM)
72
+#define ENABLE_TEMPERATURE_INTERRUPT() HAL_timer_enable_interrupt(MF_TIMER_TEMP)
73
+#define DISABLE_TEMPERATURE_INTERRUPT() HAL_timer_disable_interrupt(MF_TIMER_TEMP)
74
 
74
 
75
 #ifndef HAL_STEP_TIMER_ISR
75
 #ifndef HAL_STEP_TIMER_ISR
76
   #define HAL_STEP_TIMER_ISR() extern "C" void ftm0_isr() //void TC3_Handler()
76
   #define HAL_STEP_TIMER_ISR() extern "C" void ftm0_isr() //void TC3_Handler()
83
 
83
 
84
 FORCE_INLINE static void HAL_timer_set_compare(const uint8_t timer_num, const hal_timer_t compare) {
84
 FORCE_INLINE static void HAL_timer_set_compare(const uint8_t timer_num, const hal_timer_t compare) {
85
   switch (timer_num) {
85
   switch (timer_num) {
86
-    case 0: FTM0_C0V = compare; break;
87
-    case 1: FTM1_C0V = compare; break;
86
+    case MF_TIMER_STEP: FTM0_C0V = compare; break;
87
+    case MF_TIMER_TEMP: FTM1_C0V = compare; break;
88
   }
88
   }
89
 }
89
 }
90
 
90
 
91
 FORCE_INLINE static hal_timer_t HAL_timer_get_compare(const uint8_t timer_num) {
91
 FORCE_INLINE static hal_timer_t HAL_timer_get_compare(const uint8_t timer_num) {
92
   switch (timer_num) {
92
   switch (timer_num) {
93
-    case 0: return FTM0_C0V;
94
-    case 1: return FTM1_C0V;
93
+    case MF_TIMER_STEP: return FTM0_C0V;
94
+    case MF_TIMER_TEMP: return FTM1_C0V;
95
   }
95
   }
96
   return 0;
96
   return 0;
97
 }
97
 }
98
 
98
 
99
 FORCE_INLINE static hal_timer_t HAL_timer_get_count(const uint8_t timer_num) {
99
 FORCE_INLINE static hal_timer_t HAL_timer_get_count(const uint8_t timer_num) {
100
   switch (timer_num) {
100
   switch (timer_num) {
101
-    case 0: return FTM0_CNT;
102
-    case 1: return FTM1_CNT;
101
+    case MF_TIMER_STEP: return FTM0_CNT;
102
+    case MF_TIMER_TEMP: return FTM1_CNT;
103
   }
103
   }
104
   return 0;
104
   return 0;
105
 }
105
 }

+ 10
- 18
Marlin/src/HAL/TEENSY40_41/timers.cpp View File

30
 
30
 
31
 void HAL_timer_start(const uint8_t timer_num, const uint32_t frequency) {
31
 void HAL_timer_start(const uint8_t timer_num, const uint32_t frequency) {
32
   switch (timer_num) {
32
   switch (timer_num) {
33
-    case 0:
33
+    case MF_TIMER_STEP:
34
       CCM_CSCMR1 &= ~CCM_CSCMR1_PERCLK_CLK_SEL; // turn off 24mhz mode
34
       CCM_CSCMR1 &= ~CCM_CSCMR1_PERCLK_CLK_SEL; // turn off 24mhz mode
35
       CCM_CCGR1 |= CCM_CCGR1_GPT1_BUS(CCM_CCGR_ON);
35
       CCM_CCGR1 |= CCM_CCGR1_GPT1_BUS(CCM_CCGR_ON);
36
 
36
 
48
       attachInterruptVector(IRQ_GPT1, &stepTC_Handler);
48
       attachInterruptVector(IRQ_GPT1, &stepTC_Handler);
49
       NVIC_SET_PRIORITY(IRQ_GPT1, 16);
49
       NVIC_SET_PRIORITY(IRQ_GPT1, 16);
50
       break;
50
       break;
51
-    case 1:
51
+    case MF_TIMER_TEMP:
52
       CCM_CSCMR1 &= ~CCM_CSCMR1_PERCLK_CLK_SEL; // turn off 24mhz mode
52
       CCM_CSCMR1 &= ~CCM_CSCMR1_PERCLK_CLK_SEL; // turn off 24mhz mode
53
       CCM_CCGR0 |= CCM_CCGR0_GPT2_BUS(CCM_CCGR_ON);
53
       CCM_CCGR0 |= CCM_CCGR0_GPT2_BUS(CCM_CCGR_ON);
54
 
54
 
71
 
71
 
72
 void HAL_timer_enable_interrupt(const uint8_t timer_num) {
72
 void HAL_timer_enable_interrupt(const uint8_t timer_num) {
73
   switch (timer_num) {
73
   switch (timer_num) {
74
-    case 0:
75
-      NVIC_ENABLE_IRQ(IRQ_GPT1);
76
-      break;
77
-    case 1:
78
-      NVIC_ENABLE_IRQ(IRQ_GPT2);
79
-      break;
74
+    case MF_TIMER_STEP: NVIC_ENABLE_IRQ(IRQ_GPT1); break;
75
+    case MF_TIMER_TEMP: NVIC_ENABLE_IRQ(IRQ_GPT2); break;
80
   }
76
   }
81
 }
77
 }
82
 
78
 
83
 void HAL_timer_disable_interrupt(const uint8_t timer_num) {
79
 void HAL_timer_disable_interrupt(const uint8_t timer_num) {
84
   switch (timer_num) {
80
   switch (timer_num) {
85
-    case 0: NVIC_DISABLE_IRQ(IRQ_GPT1); break;
86
-    case 1: NVIC_DISABLE_IRQ(IRQ_GPT2); break;
81
+    case MF_TIMER_STEP: NVIC_DISABLE_IRQ(IRQ_GPT1); break;
82
+    case MF_TIMER_TEMP: NVIC_DISABLE_IRQ(IRQ_GPT2); break;
87
   }
83
   }
88
 
84
 
89
   // We NEED memory barriers to ensure Interrupts are actually disabled!
85
   // We NEED memory barriers to ensure Interrupts are actually disabled!
93
 
89
 
94
 bool HAL_timer_interrupt_enabled(const uint8_t timer_num) {
90
 bool HAL_timer_interrupt_enabled(const uint8_t timer_num) {
95
   switch (timer_num) {
91
   switch (timer_num) {
96
-    case 0: return (NVIC_IS_ENABLED(IRQ_GPT1));
97
-    case 1: return (NVIC_IS_ENABLED(IRQ_GPT2));
92
+    case MF_TIMER_STEP: return (NVIC_IS_ENABLED(IRQ_GPT1));
93
+    case MF_TIMER_TEMP: return (NVIC_IS_ENABLED(IRQ_GPT2));
98
   }
94
   }
99
   return false;
95
   return false;
100
 }
96
 }
101
 
97
 
102
 void HAL_timer_isr_prologue(const uint8_t timer_num) {
98
 void HAL_timer_isr_prologue(const uint8_t timer_num) {
103
   switch (timer_num) {
99
   switch (timer_num) {
104
-    case 0:
105
-      GPT1_SR = GPT_IR_OF1IE;  // clear OF3 bit
106
-      break;
107
-    case 1:
108
-      GPT2_SR = GPT_IR_OF1IE;  // clear OF3 bit
109
-      break;
100
+    case MF_TIMER_STEP: GPT1_SR = GPT_IR_OF1IE; break; // clear OF3 bit
101
+    case MF_TIMER_TEMP: GPT2_SR = GPT_IR_OF1IE; break; // clear OF3 bit
110
   }
102
   }
111
   asm volatile("dsb");
103
   asm volatile("dsb");
112
 }
104
 }

+ 17
- 21
Marlin/src/HAL/TEENSY40_41/timers.h View File

43
 #define GPT1_TIMER_RATE (GPT_TIMER_RATE / GPT1_TIMER_PRESCALE) // 75MHz
43
 #define GPT1_TIMER_RATE (GPT_TIMER_RATE / GPT1_TIMER_PRESCALE) // 75MHz
44
 #define GPT2_TIMER_RATE (GPT_TIMER_RATE / GPT2_TIMER_PRESCALE) // 15MHz
44
 #define GPT2_TIMER_RATE (GPT_TIMER_RATE / GPT2_TIMER_PRESCALE) // 15MHz
45
 
45
 
46
-#ifndef STEP_TIMER_NUM
47
-  #define STEP_TIMER_NUM        0  // Timer Index for Stepper
46
+#ifndef MF_TIMER_STEP
47
+  #define MF_TIMER_STEP         0  // Timer Index for Stepper
48
 #endif
48
 #endif
49
-#ifndef PULSE_TIMER_NUM
50
-  #define PULSE_TIMER_NUM       STEP_TIMER_NUM
49
+#ifndef MF_TIMER_PULSE
50
+  #define MF_TIMER_PULSE        MF_TIMER_STEP
51
 #endif
51
 #endif
52
-#ifndef TEMP_TIMER_NUM
53
-  #define TEMP_TIMER_NUM        1  // Timer Index for Temperature
52
+#ifndef MF_TIMER_TEMP
53
+  #define MF_TIMER_TEMP         1  // Timer Index for Temperature
54
 #endif
54
 #endif
55
 
55
 
56
 #define TEMP_TIMER_RATE        1000000
56
 #define TEMP_TIMER_RATE        1000000
64
 #define PULSE_TIMER_PRESCALE   STEPPER_TIMER_PRESCALE
64
 #define PULSE_TIMER_PRESCALE   STEPPER_TIMER_PRESCALE
65
 #define PULSE_TIMER_TICKS_PER_US STEPPER_TIMER_TICKS_PER_US
65
 #define PULSE_TIMER_TICKS_PER_US STEPPER_TIMER_TICKS_PER_US
66
 
66
 
67
-#define ENABLE_STEPPER_DRIVER_INTERRUPT() HAL_timer_enable_interrupt(STEP_TIMER_NUM)
68
-#define DISABLE_STEPPER_DRIVER_INTERRUPT() HAL_timer_disable_interrupt(STEP_TIMER_NUM)
69
-#define STEPPER_ISR_ENABLED() HAL_timer_interrupt_enabled(STEP_TIMER_NUM)
67
+#define ENABLE_STEPPER_DRIVER_INTERRUPT() HAL_timer_enable_interrupt(MF_TIMER_STEP)
68
+#define DISABLE_STEPPER_DRIVER_INTERRUPT() HAL_timer_disable_interrupt(MF_TIMER_STEP)
69
+#define STEPPER_ISR_ENABLED() HAL_timer_interrupt_enabled(MF_TIMER_STEP)
70
 
70
 
71
-#define ENABLE_TEMPERATURE_INTERRUPT() HAL_timer_enable_interrupt(TEMP_TIMER_NUM)
72
-#define DISABLE_TEMPERATURE_INTERRUPT() HAL_timer_disable_interrupt(TEMP_TIMER_NUM)
71
+#define ENABLE_TEMPERATURE_INTERRUPT() HAL_timer_enable_interrupt(MF_TIMER_TEMP)
72
+#define DISABLE_TEMPERATURE_INTERRUPT() HAL_timer_disable_interrupt(MF_TIMER_TEMP)
73
 
73
 
74
 #ifndef HAL_STEP_TIMER_ISR
74
 #ifndef HAL_STEP_TIMER_ISR
75
   #define HAL_STEP_TIMER_ISR() extern "C" void stepTC_Handler() // GPT1_Handler()
75
   #define HAL_STEP_TIMER_ISR() extern "C" void stepTC_Handler() // GPT1_Handler()
87
 
87
 
88
 FORCE_INLINE static void HAL_timer_set_compare(const uint8_t timer_num, const hal_timer_t compare) {
88
 FORCE_INLINE static void HAL_timer_set_compare(const uint8_t timer_num, const hal_timer_t compare) {
89
   switch (timer_num) {
89
   switch (timer_num) {
90
-    case 0:
91
-      GPT1_OCR1 = compare - 1;
92
-      break;
93
-    case 1:
94
-      GPT2_OCR1 = compare - 1;
95
-      break;
90
+    case MF_TIMER_STEP: GPT1_OCR1 = compare - 1; break;
91
+    case MF_TIMER_TEMP: GPT2_OCR1 = compare - 1; break;
96
   }
92
   }
97
 }
93
 }
98
 
94
 
99
 FORCE_INLINE static hal_timer_t HAL_timer_get_compare(const uint8_t timer_num) {
95
 FORCE_INLINE static hal_timer_t HAL_timer_get_compare(const uint8_t timer_num) {
100
   switch (timer_num) {
96
   switch (timer_num) {
101
-    case 0: return GPT1_OCR1;
102
-    case 1: return GPT2_OCR1;
97
+    case MF_TIMER_STEP: return GPT1_OCR1;
98
+    case MF_TIMER_TEMP: return GPT2_OCR1;
103
   }
99
   }
104
   return 0;
100
   return 0;
105
 }
101
 }
106
 
102
 
107
 FORCE_INLINE static hal_timer_t HAL_timer_get_count(const uint8_t timer_num) {
103
 FORCE_INLINE static hal_timer_t HAL_timer_get_count(const uint8_t timer_num) {
108
   switch (timer_num) {
104
   switch (timer_num) {
109
-    case 0: return GPT1_CNT;
110
-    case 1: return GPT2_CNT;
105
+    case MF_TIMER_STEP: return GPT1_CNT;
106
+    case MF_TIMER_TEMP: return GPT2_CNT;
111
   }
107
   }
112
   return 0;
108
   return 0;
113
 }
109
 }

+ 2
- 2
Marlin/src/feature/easythreed_ui.cpp View File

88
 
88
 
89
 //
89
 //
90
 // Filament Load/Unload Button
90
 // Filament Load/Unload Button
91
-// Load/Unload buttons are a 3 position switch with a common center ground. 
91
+// Load/Unload buttons are a 3 position switch with a common center ground.
92
 //
92
 //
93
 void EasythreedUI::loadButton() {
93
 void EasythreedUI::loadButton() {
94
   if (printingIsActive()) return;
94
   if (printingIsActive()) return;
208
             print_key_flag = PF_RESUME;                             // The "Print" button now resumes the print
208
             print_key_flag = PF_RESUME;                             // The "Print" button now resumes the print
209
             break;
209
             break;
210
             }
210
             }
211
-          case PF_RESUME: {                                         // Resume printing 
211
+          case PF_RESUME: {                                         // Resume printing
212
             if (printingIsActive()) break;
212
             if (printingIsActive()) break;
213
             blink_interval_ms = LED_BLINK_2;                        // Blink the indicator LED at 1 second intervals
213
             blink_interval_ms = LED_BLINK_2;                        // Blink the indicator LED at 1 second intervals
214
             queue.inject(F("M24"));                                 // Queue resume
214
             queue.inject(F("M24"));                                 // Queue resume

+ 1
- 1
Marlin/src/module/planner.h View File

875
           || TERN0(EXTERNAL_CLOSED_LOOP_CONTROLLER, CLOSED_LOOP_WAITING())
875
           || TERN0(EXTERNAL_CLOSED_LOOP_CONTROLLER, CLOSED_LOOP_WAITING())
876
       );
876
       );
877
     }
877
     }
878
-    
878
+
879
     // Block until all buffered steps are executed / cleaned
879
     // Block until all buffered steps are executed / cleaned
880
     static void synchronize();
880
     static void synchronize();
881
 
881
 

+ 10
- 10
Marlin/src/module/stepper.cpp View File

464
 #define PULSE_LOW_TICK_COUNT hal_timer_t(NS_TO_PULSE_TIMER_TICKS(_MIN_PULSE_LOW_NS - _MIN(_MIN_PULSE_LOW_NS, TIMER_SETUP_NS)))
464
 #define PULSE_LOW_TICK_COUNT hal_timer_t(NS_TO_PULSE_TIMER_TICKS(_MIN_PULSE_LOW_NS - _MIN(_MIN_PULSE_LOW_NS, TIMER_SETUP_NS)))
465
 
465
 
466
 #define USING_TIMED_PULSE() hal_timer_t start_pulse_count = 0
466
 #define USING_TIMED_PULSE() hal_timer_t start_pulse_count = 0
467
-#define START_TIMED_PULSE(DIR) (start_pulse_count = HAL_timer_get_count(PULSE_TIMER_NUM))
468
-#define AWAIT_TIMED_PULSE(DIR) while (PULSE_##DIR##_TICK_COUNT > HAL_timer_get_count(PULSE_TIMER_NUM) - start_pulse_count) { }
467
+#define START_TIMED_PULSE(DIR) (start_pulse_count = HAL_timer_get_count(MF_TIMER_PULSE))
468
+#define AWAIT_TIMED_PULSE(DIR) while (PULSE_##DIR##_TICK_COUNT > HAL_timer_get_count(MF_TIMER_PULSE) - start_pulse_count) { }
469
 #define START_HIGH_PULSE()  START_TIMED_PULSE(HIGH)
469
 #define START_HIGH_PULSE()  START_TIMED_PULSE(HIGH)
470
 #define AWAIT_HIGH_PULSE()  AWAIT_TIMED_PULSE(HIGH)
470
 #define AWAIT_HIGH_PULSE()  AWAIT_TIMED_PULSE(HIGH)
471
 #define START_LOW_PULSE()   START_TIMED_PULSE(LOW)
471
 #define START_LOW_PULSE()   START_TIMED_PULSE(LOW)
1454
  */
1454
  */
1455
 
1455
 
1456
 HAL_STEP_TIMER_ISR() {
1456
 HAL_STEP_TIMER_ISR() {
1457
-  HAL_timer_isr_prologue(STEP_TIMER_NUM);
1457
+  HAL_timer_isr_prologue(MF_TIMER_STEP);
1458
 
1458
 
1459
   Stepper::isr();
1459
   Stepper::isr();
1460
 
1460
 
1461
-  HAL_timer_isr_epilogue(STEP_TIMER_NUM);
1461
+  HAL_timer_isr_epilogue(MF_TIMER_STEP);
1462
 }
1462
 }
1463
 
1463
 
1464
 #ifdef CPU_32_BIT
1464
 #ifdef CPU_32_BIT
1480
   // Program timer compare for the maximum period, so it does NOT
1480
   // Program timer compare for the maximum period, so it does NOT
1481
   // flag an interrupt while this ISR is running - So changes from small
1481
   // flag an interrupt while this ISR is running - So changes from small
1482
   // periods to big periods are respected and the timer does not reset to 0
1482
   // periods to big periods are respected and the timer does not reset to 0
1483
-  HAL_timer_set_compare(STEP_TIMER_NUM, hal_timer_t(HAL_TIMER_TYPE_MAX));
1483
+  HAL_timer_set_compare(MF_TIMER_STEP, hal_timer_t(HAL_TIMER_TYPE_MAX));
1484
 
1484
 
1485
   // Count of ticks for the next ISR
1485
   // Count of ticks for the next ISR
1486
   hal_timer_t next_isr_ticks = 0;
1486
   hal_timer_t next_isr_ticks = 0;
1584
      * On AVR the ISR epilogue+prologue is estimated at 100 instructions - Give 8µs as margin
1584
      * On AVR the ISR epilogue+prologue is estimated at 100 instructions - Give 8µs as margin
1585
      * On ARM the ISR epilogue+prologue is estimated at 20 instructions - Give 1µs as margin
1585
      * On ARM the ISR epilogue+prologue is estimated at 20 instructions - Give 1µs as margin
1586
      */
1586
      */
1587
-    min_ticks = HAL_timer_get_count(STEP_TIMER_NUM) + hal_timer_t(
1587
+    min_ticks = HAL_timer_get_count(MF_TIMER_STEP) + hal_timer_t(
1588
       #ifdef __AVR__
1588
       #ifdef __AVR__
1589
         8
1589
         8
1590
       #else
1590
       #else
1608
   // sure that the time has not arrived yet - Warrantied by the scheduler
1608
   // sure that the time has not arrived yet - Warrantied by the scheduler
1609
 
1609
 
1610
   // Set the next ISR to fire at the proper time
1610
   // Set the next ISR to fire at the proper time
1611
-  HAL_timer_set_compare(STEP_TIMER_NUM, hal_timer_t(next_isr_ticks));
1611
+  HAL_timer_set_compare(MF_TIMER_STEP, hal_timer_t(next_isr_ticks));
1612
 
1612
 
1613
   // Don't forget to finally reenable interrupts
1613
   // Don't forget to finally reenable interrupts
1614
   ENABLE_ISRS();
1614
   ENABLE_ISRS();
2769
   #endif
2769
   #endif
2770
 
2770
 
2771
   #if DISABLED(I2S_STEPPER_STREAM)
2771
   #if DISABLED(I2S_STEPPER_STREAM)
2772
-    HAL_timer_start(STEP_TIMER_NUM, 122); // Init Stepper ISR to 122 Hz for quick starting
2772
+    HAL_timer_start(MF_TIMER_STEP, 122); // Init Stepper ISR to 122 Hz for quick starting
2773
     wake_up();
2773
     wake_up();
2774
     sei();
2774
     sei();
2775
   #endif
2775
   #endif
2980
   #define EXTRA_CYCLES_BABYSTEP (STEP_PULSE_CYCLES - (CYCLES_EATEN_BABYSTEP))
2980
   #define EXTRA_CYCLES_BABYSTEP (STEP_PULSE_CYCLES - (CYCLES_EATEN_BABYSTEP))
2981
 
2981
 
2982
   #if EXTRA_CYCLES_BABYSTEP > 20
2982
   #if EXTRA_CYCLES_BABYSTEP > 20
2983
-    #define _SAVE_START() const hal_timer_t pulse_start = HAL_timer_get_count(PULSE_TIMER_NUM)
2984
-    #define _PULSE_WAIT() while (EXTRA_CYCLES_BABYSTEP > (uint32_t)(HAL_timer_get_count(PULSE_TIMER_NUM) - pulse_start) * (PULSE_TIMER_PRESCALE)) { /* nada */ }
2983
+    #define _SAVE_START() const hal_timer_t pulse_start = HAL_timer_get_count(MF_TIMER_PULSE)
2984
+    #define _PULSE_WAIT() while (EXTRA_CYCLES_BABYSTEP > (uint32_t)(HAL_timer_get_count(MF_TIMER_PULSE) - pulse_start) * (PULSE_TIMER_PRESCALE)) { /* nada */ }
2985
   #else
2985
   #else
2986
     #define _SAVE_START() NOOP
2986
     #define _SAVE_START() NOOP
2987
     #if EXTRA_CYCLES_BABYSTEP > 0
2987
     #if EXTRA_CYCLES_BABYSTEP > 0

+ 3
- 3
Marlin/src/module/temperature.cpp View File

2387
     HAL_ANALOG_SELECT(POWER_MONITOR_VOLTAGE_PIN);
2387
     HAL_ANALOG_SELECT(POWER_MONITOR_VOLTAGE_PIN);
2388
   #endif
2388
   #endif
2389
 
2389
 
2390
-  HAL_timer_start(TEMP_TIMER_NUM, TEMP_TIMER_FREQUENCY);
2390
+  HAL_timer_start(MF_TIMER_TEMP, TEMP_TIMER_FREQUENCY);
2391
   ENABLE_TEMPERATURE_INTERRUPT();
2391
   ENABLE_TEMPERATURE_INTERRUPT();
2392
 
2392
 
2393
   #if HAS_AUTO_FAN_0
2393
   #if HAS_AUTO_FAN_0
2968
  *  - Call planner.isr to count down its "ignore" time
2968
  *  - Call planner.isr to count down its "ignore" time
2969
  */
2969
  */
2970
 HAL_TEMP_TIMER_ISR() {
2970
 HAL_TEMP_TIMER_ISR() {
2971
-  HAL_timer_isr_prologue(TEMP_TIMER_NUM);
2971
+  HAL_timer_isr_prologue(MF_TIMER_TEMP);
2972
 
2972
 
2973
   Temperature::isr();
2973
   Temperature::isr();
2974
 
2974
 
2975
-  HAL_timer_isr_epilogue(TEMP_TIMER_NUM);
2975
+  HAL_timer_isr_epilogue(MF_TIMER_TEMP);
2976
 }
2976
 }
2977
 
2977
 
2978
 #if ENABLED(SLOW_PWM_HEATERS) && !defined(MIN_STATE_TIME)
2978
 #if ENABLED(SLOW_PWM_HEATERS) && !defined(MIN_STATE_TIME)

+ 1
- 2
Marlin/src/pins/sam/pins_ARCHIM1.h View File

46
 //
46
 //
47
 // Timers
47
 // Timers
48
 //
48
 //
49
-// These are already defined in DUE, so must be undefined first
50
-#define STEP_TIMER_NUM                         3
49
+#define MF_TIMER_STEP  3
51
 #define HAL_STEP_TIMER_ISR()  void TC3_Handler()
50
 #define HAL_STEP_TIMER_ISR()  void TC3_Handler()
52
 
51
 
53
 //
52
 //

+ 2
- 2
Marlin/src/pins/stm32f0/pins_MALYAN_M300.h View File

45
 //
45
 //
46
 // Timers
46
 // Timers
47
 //
47
 //
48
-#define STEP_TIMER                             6
49
-#define TEMP_TIMER                             7
48
+#define STEP_TIMER  6
49
+#define TEMP_TIMER  7
50
 
50
 
51
 //
51
 //
52
 // Limit Switches
52
 // Limit Switches

+ 1
- 1
Marlin/src/pins/stm32f1/pins_FLSUN_HISPEED.h View File

41
 #define BOARD_NO_NATIVE_USB
41
 #define BOARD_NO_NATIVE_USB
42
 
42
 
43
 // Avoid conflict with TIMER_SERVO when using the STM32 HAL
43
 // Avoid conflict with TIMER_SERVO when using the STM32 HAL
44
-#define TEMP_TIMER                             5
44
+#define TEMP_TIMER  5
45
 
45
 
46
 //
46
 //
47
 // Release PB4 (Y_ENABLE_PIN) from JTAG NRST role
47
 // Release PB4 (Y_ENABLE_PIN) from JTAG NRST role

+ 2
- 2
Marlin/src/pins/stm32f1/pins_MALYAN_M200.h View File

47
 // On STM32F103:
47
 // On STM32F103:
48
 // PB3, PB6, PB7, and PB8 can be used with pwm, which rules out TIM2 and TIM4.
48
 // PB3, PB6, PB7, and PB8 can be used with pwm, which rules out TIM2 and TIM4.
49
 // On STM32F070, 16 and 17 are in use, but 1 and 3 are available.
49
 // On STM32F070, 16 and 17 are in use, but 1 and 3 are available.
50
-#define STEP_TIMER                             1
51
-#define TEMP_TIMER                             3
50
+#define STEP_TIMER  1
51
+#define TEMP_TIMER  3
52
 
52
 
53
 //
53
 //
54
 // Limit Switches
54
 // Limit Switches

+ 1
- 1
Marlin/src/pins/stm32f1/pins_MKS_ROBIN_E3P.h View File

39
 #define MKS_HARDWARE_TEST_ONLY_E0
39
 #define MKS_HARDWARE_TEST_ONLY_E0
40
 
40
 
41
 // Avoid conflict with TIMER_SERVO when using the STM32 HAL
41
 // Avoid conflict with TIMER_SERVO when using the STM32 HAL
42
-#define TEMP_TIMER                             5
42
+#define TEMP_TIMER  5
43
 
43
 
44
 //
44
 //
45
 // Release PB4 (Y_ENABLE_PIN) from JTAG NRST role
45
 // Release PB4 (Y_ENABLE_PIN) from JTAG NRST role

+ 1
- 1
Marlin/src/pins/stm32f1/pins_MKS_ROBIN_NANO_V2.h View File

39
 #define USES_DIAG_PINS
39
 #define USES_DIAG_PINS
40
 
40
 
41
 // Avoid conflict with TIMER_SERVO when using the STM32 HAL
41
 // Avoid conflict with TIMER_SERVO when using the STM32 HAL
42
-#define TEMP_TIMER                             5
42
+#define TEMP_TIMER  5
43
 
43
 
44
 //
44
 //
45
 // Release PB4 (Y_ENABLE_PIN) from JTAG NRST role
45
 // Release PB4 (Y_ENABLE_PIN) from JTAG NRST role

+ 1
- 1
Marlin/src/pins/stm32f1/pins_MKS_ROBIN_NANO_common.h View File

32
 #define BOARD_NO_NATIVE_USB
32
 #define BOARD_NO_NATIVE_USB
33
 
33
 
34
 // Avoid conflict with TIMER_SERVO when using the STM32 HAL
34
 // Avoid conflict with TIMER_SERVO when using the STM32 HAL
35
-#define TEMP_TIMER                             5
35
+#define TEMP_TIMER  5
36
 
36
 
37
 //
37
 //
38
 // EEPROM
38
 // EEPROM

+ 1
- 1
Marlin/src/pins/stm32f4/pins_BTT_OCTOPUS_V1_common.h View File

33
 #define I2C_SDA_PIN                         PB9
33
 #define I2C_SDA_PIN                         PB9
34
 
34
 
35
 // Avoid conflict with TIMER_TONE
35
 // Avoid conflict with TIMER_TONE
36
-#define STEP_TIMER                            10
36
+#define STEP_TIMER 10
37
 
37
 
38
 //
38
 //
39
 // Servos
39
 // Servos

+ 1
- 1
Marlin/src/pins/stm32f4/pins_BTT_SKR_V2_0_common.h View File

50
 #define HAS_OTG_USB_HOST_SUPPORT                  // USB Flash Drive support
50
 #define HAS_OTG_USB_HOST_SUPPORT                  // USB Flash Drive support
51
 
51
 
52
 // Avoid conflict with TIMER_TONE
52
 // Avoid conflict with TIMER_TONE
53
-#define STEP_TIMER                            10
53
+#define STEP_TIMER 10
54
 
54
 
55
 //
55
 //
56
 // Servos
56
 // Servos

+ 2
- 2
Marlin/src/pins/stm32f4/pins_FLYF407ZG.h View File

33
 #define DEFAULT_MACHINE_NAME BOARD_INFO_NAME
33
 #define DEFAULT_MACHINE_NAME BOARD_INFO_NAME
34
 
34
 
35
 // Avoid conflict with fans and TIMER_TONE
35
 // Avoid conflict with fans and TIMER_TONE
36
-#define TEMP_TIMER                             3
37
-#define STEP_TIMER                             5
36
+#define TEMP_TIMER  3
37
+#define STEP_TIMER  5
38
 
38
 
39
 //
39
 //
40
 // EEPROM Emulation
40
 // EEPROM Emulation

+ 2
- 2
Marlin/src/pins/stm32f4/pins_LERDGE_S.h View File

31
 #define BOARD_INFO_NAME      "Lerdge S"
31
 #define BOARD_INFO_NAME      "Lerdge S"
32
 #define DEFAULT_MACHINE_NAME "LERDGE"
32
 #define DEFAULT_MACHINE_NAME "LERDGE"
33
 
33
 
34
-#define STEP_TIMER                             4
35
-#define TEMP_TIMER                             2
34
+#define STEP_TIMER  4
35
+#define TEMP_TIMER  2
36
 
36
 
37
 #define HAS_OTG_USB_HOST_SUPPORT                  // USB Flash Drive support
37
 #define HAS_OTG_USB_HOST_SUPPORT                  // USB Flash Drive support
38
 
38
 

+ 2
- 2
Marlin/src/pins/stm32f4/pins_LERDGE_X.h View File

31
 #define BOARD_INFO_NAME      "Lerdge X"
31
 #define BOARD_INFO_NAME      "Lerdge X"
32
 #define DEFAULT_MACHINE_NAME "LERDGE"
32
 #define DEFAULT_MACHINE_NAME "LERDGE"
33
 
33
 
34
-#define STEP_TIMER                             4
35
-#define TEMP_TIMER                             2
34
+#define STEP_TIMER  4
35
+#define TEMP_TIMER  2
36
 
36
 
37
 #define I2C_EEPROM
37
 #define I2C_EEPROM
38
 #define I2C_SCL_PIN                         PB8
38
 #define I2C_SCL_PIN                         PB8

+ 1
- 1
Marlin/src/pins/stm32f4/pins_MKS_MONSTER8.h View File

38
 //#define DISABLE_DEBUG
38
 //#define DISABLE_DEBUG
39
 
39
 
40
 // Avoid conflict with TIMER_TONE
40
 // Avoid conflict with TIMER_TONE
41
-#define STEP_TIMER                            10
41
+#define STEP_TIMER 10
42
 
42
 
43
 // Use one of these or SDCard-based Emulation will be used
43
 // Use one of these or SDCard-based Emulation will be used
44
 //#define SRAM_EEPROM_EMULATION                   // Use BackSRAM-based EEPROM emulation
44
 //#define SRAM_EEPROM_EMULATION                   // Use BackSRAM-based EEPROM emulation

+ 1
- 1
Marlin/src/pins/stm32f4/pins_MKS_ROBIN_NANO_V3_common.h View File

29
 #define HAS_OTG_USB_HOST_SUPPORT                  // USB Flash Drive support
29
 #define HAS_OTG_USB_HOST_SUPPORT                  // USB Flash Drive support
30
 
30
 
31
 // Avoid conflict with TIMER_TONE
31
 // Avoid conflict with TIMER_TONE
32
-#define STEP_TIMER                            10
32
+#define STEP_TIMER 10
33
 
33
 
34
 // Use one of these or SDCard-based Emulation will be used
34
 // Use one of these or SDCard-based Emulation will be used
35
 //#define SRAM_EEPROM_EMULATION                   // Use BackSRAM-based EEPROM emulation
35
 //#define SRAM_EEPROM_EMULATION                   // Use BackSRAM-based EEPROM emulation

+ 2
- 2
Marlin/src/pins/stm32f4/pins_RUMBA32_common.h View File

45
 //              This will be difficult to solve from the Arduino IDE, without modifying the RUMBA32 variant
45
 //              This will be difficult to solve from the Arduino IDE, without modifying the RUMBA32 variant
46
 //              included with the STM32 framework.
46
 //              included with the STM32 framework.
47
 
47
 
48
-#define STEP_TIMER                            10
49
-#define TEMP_TIMER                            14
48
+#define STEP_TIMER 10
49
+#define TEMP_TIMER 14
50
 
50
 
51
 //
51
 //
52
 // Limit Switches
52
 // Limit Switches

+ 2
- 2
Marlin/src/pins/stm32f7/pins_NUCLEO_F767ZI.h View File

57
  * TIM14 - TEMP_TIMER (Marlin)
57
  * TIM14 - TEMP_TIMER (Marlin)
58
  *
58
  *
59
  */
59
  */
60
-#define STEP_TIMER                             4
61
-#define TEMP_TIMER                            14
60
+#define STEP_TIMER  4
61
+#define TEMP_TIMER 14
62
 
62
 
63
 /**
63
 /**
64
  * These pin assignments are arbitrary and intending for testing purposes.
64
  * These pin assignments are arbitrary and intending for testing purposes.

+ 1
- 1
Marlin/src/pins/stm32f7/pins_REMRAM_V1.h View File

134
 // Timers
134
 // Timers
135
 //
135
 //
136
 
136
 
137
-#define STEP_TIMER                             2
137
+#define STEP_TIMER  2

Loading…
Cancel
Save