Browse Source

♻️ Move watchdog to MarlinHAL

Scott Lahteine 2 years ago
parent
commit
52eefa90e1
62 changed files with 505 additions and 1101 deletions
  1. 53
    0
      Marlin/src/HAL/AVR/HAL.cpp
  2. 4
    1
      Marlin/src/HAL/AVR/HAL.h
  3. 0
    70
      Marlin/src/HAL/AVR/watchdog.cpp
  4. 0
    31
      Marlin/src/HAL/AVR/watchdog.h
  5. 94
    1
      Marlin/src/HAL/DUE/HAL.cpp
  6. 7
    4
      Marlin/src/HAL/DUE/HAL.h
  7. 0
    114
      Marlin/src/HAL/DUE/watchdog.cpp
  8. 0
    33
      Marlin/src/HAL/DUE/watchdog.h
  9. 25
    0
      Marlin/src/HAL/ESP32/HAL.cpp
  10. 7
    4
      Marlin/src/HAL/ESP32/HAL.h
  11. 0
    42
      Marlin/src/HAL/ESP32/watchdog.cpp
  12. 0
    38
      Marlin/src/HAL/ESP32/watchdog.h
  13. 0
    4
      Marlin/src/HAL/HAL.h
  14. 7
    3
      Marlin/src/HAL/LINUX/HAL.h
  15. 0
    37
      Marlin/src/HAL/LINUX/watchdog.cpp
  16. 0
    25
      Marlin/src/HAL/LINUX/watchdog.h
  17. 47
    7
      Marlin/src/HAL/LPC1768/HAL.cpp
  18. 8
    3
      Marlin/src/HAL/LPC1768/HAL.h
  19. 0
    72
      Marlin/src/HAL/LPC1768/watchdog.cpp
  20. 0
    28
      Marlin/src/HAL/LPC1768/watchdog.h
  21. 4
    1
      Marlin/src/HAL/NATIVE_SIM/HAL.h
  22. 0
    27
      Marlin/src/HAL/NATIVE_SIM/watchdog.h
  23. 34
    0
      Marlin/src/HAL/SAMD51/HAL.cpp
  24. 4
    1
      Marlin/src/HAL/SAMD51/HAL.h
  25. 0
    54
      Marlin/src/HAL/SAMD51/watchdog.cpp
  26. 0
    31
      Marlin/src/HAL/SAMD51/watchdog.h
  27. 23
    0
      Marlin/src/HAL/STM32/HAL.cpp
  28. 6
    3
      Marlin/src/HAL/STM32/HAL.h
  29. 1
    2
      Marlin/src/HAL/STM32/MinSerial.cpp
  30. 4
    4
      Marlin/src/HAL/STM32/sdio.cpp
  31. 0
    52
      Marlin/src/HAL/STM32/watchdog.cpp
  32. 0
    25
      Marlin/src/HAL/STM32/watchdog.h
  33. 41
    0
      Marlin/src/HAL/STM32F1/HAL.cpp
  34. 4
    1
      Marlin/src/HAL/STM32F1/HAL.h
  35. 1
    2
      Marlin/src/HAL/STM32F1/MinSerial.cpp
  36. 0
    66
      Marlin/src/HAL/STM32F1/watchdog.cpp
  37. 0
    35
      Marlin/src/HAL/STM32F1/watchdog.h
  38. 22
    0
      Marlin/src/HAL/TEENSY31_32/HAL.cpp
  39. 4
    1
      Marlin/src/HAL/TEENSY31_32/HAL.h
  40. 0
    40
      Marlin/src/HAL/TEENSY31_32/watchdog.cpp
  41. 0
    34
      Marlin/src/HAL/TEENSY31_32/watchdog.h
  42. 22
    0
      Marlin/src/HAL/TEENSY35_36/HAL.cpp
  43. 4
    1
      Marlin/src/HAL/TEENSY35_36/HAL.h
  44. 0
    40
      Marlin/src/HAL/TEENSY35_36/watchdog.cpp
  45. 0
    30
      Marlin/src/HAL/TEENSY35_36/watchdog.h
  46. 25
    0
      Marlin/src/HAL/TEENSY40_41/HAL.cpp
  47. 4
    1
      Marlin/src/HAL/TEENSY40_41/HAL.h
  48. 0
    52
      Marlin/src/HAL/TEENSY40_41/watchdog.cpp
  49. 0
    30
      Marlin/src/HAL/TEENSY40_41/watchdog.h
  50. 4
    4
      Marlin/src/MarlinCore.cpp
  51. 5
    5
      Marlin/src/gcode/config/M43.cpp
  52. 0
    1
      Marlin/src/gcode/feature/L6470/M916-M918.cpp
  53. 2
    2
      Marlin/src/gcode/gcode_d.cpp
  54. 1
    1
      Marlin/src/lcd/e3v2/proui/meshviewer.cpp
  55. 1
    1
      Marlin/src/lcd/extui/mks_ui/draw_print_file.cpp
  56. 2
    2
      Marlin/src/lcd/extui/mks_ui/draw_z_offset_wizard.cpp
  57. 11
    11
      Marlin/src/lcd/extui/mks_ui/pic_manager.cpp
  58. 6
    6
      Marlin/src/lcd/extui/mks_ui/tft_lvgl_configuration.cpp
  59. 6
    6
      Marlin/src/lcd/extui/mks_ui/wifi_module.cpp
  60. 3
    3
      Marlin/src/lcd/extui/mks_ui/wifi_upload.cpp
  61. 5
    5
      Marlin/src/module/temperature.cpp
  62. 4
    4
      Marlin/src/sd/Sd2Card.cpp

+ 53
- 0
Marlin/src/HAL/AVR/HAL.cpp View File

@@ -23,6 +23,7 @@
23 23
 
24 24
 #include "../../inc/MarlinConfig.h"
25 25
 #include "HAL.h"
26
+#include <avr/wdt.h>
26 27
 
27 28
 #ifdef USBCON
28 29
   DefaultSerial1 MSerial0(false, Serial);
@@ -89,6 +90,58 @@ void MarlinHAL::reboot() {
89 90
 }
90 91
 
91 92
 // ------------------------
93
+// Watchdog Timer
94
+// ------------------------
95
+
96
+#if ENABLED(USE_WATCHDOG)
97
+
98
+  #include <avr/wdt.h>
99
+  #include "../../MarlinCore.h"
100
+
101
+  // Initialize watchdog with 8s timeout, if possible. Otherwise, make it 4s.
102
+  void MarlinHAL::watchdog_init() {
103
+    #if ENABLED(WATCHDOG_DURATION_8S) && defined(WDTO_8S)
104
+      #define WDTO_NS WDTO_8S
105
+    #else
106
+      #define WDTO_NS WDTO_4S
107
+    #endif
108
+    #if ENABLED(WATCHDOG_RESET_MANUAL)
109
+      // Enable the watchdog timer, but only for the interrupt.
110
+      // Take care, as this requires the correct order of operation, with interrupts disabled.
111
+      // See the datasheet of any AVR chip for details.
112
+      wdt_reset();
113
+      cli();
114
+      _WD_CONTROL_REG = _BV(_WD_CHANGE_BIT) | _BV(WDE);
115
+      _WD_CONTROL_REG = _BV(WDIE) | (WDTO_NS & 0x07) | ((WDTO_NS & 0x08) << 2); // WDTO_NS directly does not work. bit 0-2 are consecutive in the register but the highest value bit is at bit 5
116
+                                                                                // So worked for up to WDTO_2S
117
+      sei();
118
+      wdt_reset();
119
+    #else
120
+      wdt_enable(WDTO_NS); // The function handles the upper bit correct.
121
+    #endif
122
+    //delay(10000); // test it!
123
+  }
124
+
125
+  //===========================================================================
126
+  //=================================== ISR ===================================
127
+  //===========================================================================
128
+
129
+  // Watchdog timer interrupt, called if main program blocks >4sec and manual reset is enabled.
130
+  #if ENABLED(WATCHDOG_RESET_MANUAL)
131
+    ISR(WDT_vect) {
132
+      sei();  // With the interrupt driven serial we need to allow interrupts.
133
+      SERIAL_ERROR_MSG(STR_WATCHDOG_FIRED);
134
+      minkill();  // interrupt-safe final kill and infinite loop
135
+    }
136
+  #endif
137
+
138
+  // Reset watchdog. MUST be called at least every 4 seconds after the
139
+  // first watchdog_init or AVR will go into emergency procedures.
140
+  void MarlinHAL::watchdog_refresh() { wdt_reset(); }
141
+
142
+#endif // USE_WATCHDOG
143
+
144
+// ------------------------
92 145
 // Free Memory Accessor
93 146
 // ------------------------
94 147
 

+ 4
- 1
Marlin/src/HAL/AVR/HAL.h View File

@@ -26,7 +26,6 @@
26 26
 #include "../shared/Marduino.h"
27 27
 #include "../shared/HAL_SPI.h"
28 28
 #include "fastio.h"
29
-#include "watchdog.h"
30 29
 #include "math.h"
31 30
 
32 31
 #ifdef USBCON
@@ -189,6 +188,10 @@ public:
189 188
   // Earliest possible init, before setup()
190 189
   MarlinHAL() {}
191 190
 
191
+  // Watchdog
192
+  static void watchdog_init()    IF_DISABLED(USE_WATCHDOG, {});
193
+  static void watchdog_refresh() IF_DISABLED(USE_WATCHDOG, {});
194
+
192 195
   static void init();          // Called early in setup()
193 196
   static void init_board() {}  // Called less early in setup()
194 197
   static void reboot();        // Restart the firmware from 0x0

+ 0
- 70
Marlin/src/HAL/AVR/watchdog.cpp View File

@@ -1,70 +0,0 @@
1
-/**
2
- * Marlin 3D Printer Firmware
3
- * Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
4
- *
5
- * Based on Sprinter and grbl.
6
- * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm
7
- *
8
- * This program is free software: you can redistribute it and/or modify
9
- * it under the terms of the GNU General Public License as published by
10
- * the Free Software Foundation, either version 3 of the License, or
11
- * (at your option) any later version.
12
- *
13
- * This program is distributed in the hope that it will be useful,
14
- * but WITHOUT ANY WARRANTY; without even the implied warranty of
15
- * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the
16
- * GNU General Public License for more details.
17
- *
18
- * You should have received a copy of the GNU General Public License
19
- * along with this program.  If not, see <https://www.gnu.org/licenses/>.
20
- *
21
- */
22
-#ifdef __AVR__
23
-
24
-#include "../../inc/MarlinConfig.h"
25
-
26
-#if ENABLED(USE_WATCHDOG)
27
-
28
-#include "watchdog.h"
29
-
30
-#include "../../MarlinCore.h"
31
-
32
-// Initialize watchdog with 8s timeout, if possible. Otherwise, make it 4s.
33
-void watchdog_init() {
34
-  #if ENABLED(WATCHDOG_DURATION_8S) && defined(WDTO_8S)
35
-    #define WDTO_NS WDTO_8S
36
-  #else
37
-    #define WDTO_NS WDTO_4S
38
-  #endif
39
-  #if ENABLED(WATCHDOG_RESET_MANUAL)
40
-    // Enable the watchdog timer, but only for the interrupt.
41
-    // Take care, as this requires the correct order of operation, with interrupts disabled.
42
-    // See the datasheet of any AVR chip for details.
43
-    wdt_reset();
44
-    cli();
45
-    _WD_CONTROL_REG = _BV(_WD_CHANGE_BIT) | _BV(WDE);
46
-    _WD_CONTROL_REG = _BV(WDIE) | (WDTO_NS & 0x07) | ((WDTO_NS & 0x08) << 2); // WDTO_NS directly does not work. bit 0-2 are consecutive in the register but the highest value bit is at bit 5
47
-                                                                              // So worked for up to WDTO_2S
48
-    sei();
49
-    wdt_reset();
50
-  #else
51
-    wdt_enable(WDTO_NS); // The function handles the upper bit correct.
52
-  #endif
53
-  //delay(10000); // test it!
54
-}
55
-
56
-//===========================================================================
57
-//=================================== ISR ===================================
58
-//===========================================================================
59
-
60
-// Watchdog timer interrupt, called if main program blocks >4sec and manual reset is enabled.
61
-#if ENABLED(WATCHDOG_RESET_MANUAL)
62
-  ISR(WDT_vect) {
63
-    sei();  // With the interrupt driven serial we need to allow interrupts.
64
-    SERIAL_ERROR_MSG(STR_WATCHDOG_FIRED);
65
-    minkill();  // interrupt-safe final kill and infinite loop
66
-  }
67
-#endif
68
-
69
-#endif // USE_WATCHDOG
70
-#endif // __AVR__

+ 0
- 31
Marlin/src/HAL/AVR/watchdog.h View File

@@ -1,31 +0,0 @@
1
-/**
2
- * Marlin 3D Printer Firmware
3
- * Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
4
- *
5
- * Based on Sprinter and grbl.
6
- * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm
7
- *
8
- * This program is free software: you can redistribute it and/or modify
9
- * it under the terms of the GNU General Public License as published by
10
- * the Free Software Foundation, either version 3 of the License, or
11
- * (at your option) any later version.
12
- *
13
- * This program is distributed in the hope that it will be useful,
14
- * but WITHOUT ANY WARRANTY; without even the implied warranty of
15
- * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the
16
- * GNU General Public License for more details.
17
- *
18
- * You should have received a copy of the GNU General Public License
19
- * along with this program.  If not, see <https://www.gnu.org/licenses/>.
20
- *
21
- */
22
-#pragma once
23
-
24
-#include <avr/wdt.h>
25
-
26
-// Initialize watchdog with a 4 second interrupt time
27
-void watchdog_init();
28
-
29
-// Reset watchdog. MUST be called at least every 4 seconds after the
30
-// first watchdog_init or AVR will go into emergency procedures.
31
-inline void HAL_watchdog_refresh() { wdt_reset(); }

+ 94
- 1
Marlin/src/HAL/DUE/HAL.cpp View File

@@ -25,7 +25,7 @@
25 25
 #ifdef ARDUINO_ARCH_SAM
26 26
 
27 27
 #include "../../inc/MarlinConfig.h"
28
-#include "HAL.h"
28
+#include "../../MarlinCore.h"
29 29
 
30 30
 #include <Wire.h>
31 31
 #include "usb/usb_task.h"
@@ -74,6 +74,99 @@ uint8_t MarlinHAL::get_reset_source() {
74 74
 void MarlinHAL::reboot() { rstc_start_software_reset(RSTC); }
75 75
 
76 76
 // ------------------------
77
+// Watchdog Timer
78
+// ------------------------
79
+
80
+#if ENABLED(USE_WATCHDOG)
81
+
82
+  // Initialize watchdog - On SAM3X, Watchdog was already configured
83
+  //  and enabled or disabled at startup, so no need to reconfigure it
84
+  //  here.
85
+  void MarlinHAL::watchdog_init() { WDT_Restart(WDT); } // Reset watchdog to start clean
86
+
87
+  // Reset watchdog. MUST be called at least every 4 seconds after the
88
+  // first watchdog_init or AVR will go into emergency procedures.
89
+  void MarlinHAL::watchdog_refresh() { watchdogReset(); }
90
+
91
+#endif
92
+
93
+// Override Arduino runtime to either config or disable the watchdog
94
+//
95
+// We need to configure the watchdog as soon as possible in the boot
96
+// process, because watchdog initialization at hardware reset on SAM3X8E
97
+// is unreliable, and there is risk of unintended resets if we delay
98
+// that initialization to a later time.
99
+void watchdogSetup() {
100
+
101
+  #if ENABLED(USE_WATCHDOG)
102
+
103
+    // 4 seconds timeout
104
+    uint32_t timeout = TERN(WATCHDOG_DURATION_8S, 8000, 4000);
105
+
106
+    // Calculate timeout value in WDT counter ticks: This assumes
107
+    // the slow clock is running at 32.768 kHz watchdog
108
+    // frequency is therefore 32768 / 128 = 256 Hz
109
+    timeout = (timeout << 8) / 1000;
110
+    if (timeout == 0)
111
+      timeout = 1;
112
+    else if (timeout > 0xFFF)
113
+      timeout = 0xFFF;
114
+
115
+    // We want to enable the watchdog with the specified timeout
116
+    uint32_t value =
117
+      WDT_MR_WDV(timeout) |               // With the specified timeout
118
+      WDT_MR_WDD(timeout) |               // and no invalid write window
119
+    #if !(SAMV70 || SAMV71 || SAME70 || SAMS70)
120
+      WDT_MR_WDRPROC   |                  // WDT fault resets processor only - We want
121
+                                          // to keep PIO controller state
122
+    #endif
123
+      WDT_MR_WDDBGHLT  |                  // WDT stops in debug state.
124
+      WDT_MR_WDIDLEHLT;                   // WDT stops in idle state.
125
+
126
+    #if ENABLED(WATCHDOG_RESET_MANUAL)
127
+      // We enable the watchdog timer, but only for the interrupt.
128
+
129
+      // Configure WDT to only trigger an interrupt
130
+      value |= WDT_MR_WDFIEN;             // Enable WDT fault interrupt.
131
+
132
+      // Disable WDT interrupt (just in case, to avoid triggering it!)
133
+      NVIC_DisableIRQ(WDT_IRQn);
134
+
135
+      // We NEED memory barriers to ensure Interrupts are actually disabled!
136
+      // ( https://dzone.com/articles/nvic-disabling-interrupts-on-arm-cortex-m-and-the )
137
+      __DSB();
138
+      __ISB();
139
+
140
+      // Initialize WDT with the given parameters
141
+      WDT_Enable(WDT, value);
142
+
143
+      // Configure and enable WDT interrupt.
144
+      NVIC_ClearPendingIRQ(WDT_IRQn);
145
+      NVIC_SetPriority(WDT_IRQn, 0); // Use highest priority, so we detect all kinds of lockups
146
+      NVIC_EnableIRQ(WDT_IRQn);
147
+
148
+    #else
149
+
150
+      // a WDT fault triggers a reset
151
+      value |= WDT_MR_WDRSTEN;
152
+
153
+      // Initialize WDT with the given parameters
154
+      WDT_Enable(WDT, value);
155
+
156
+    #endif
157
+
158
+    // Reset the watchdog
159
+    WDT_Restart(WDT);
160
+
161
+  #else
162
+
163
+    // Make sure to completely disable the Watchdog
164
+    WDT_Disable(WDT);
165
+
166
+  #endif
167
+}
168
+
169
+// ------------------------
77 170
 // Free Memory Accessor
78 171
 // ------------------------
79 172
 

+ 7
- 4
Marlin/src/HAL/DUE/HAL.h View File

@@ -32,7 +32,6 @@
32 32
 #include "../shared/math_32bit.h"
33 33
 #include "../shared/HAL_SPI.h"
34 34
 #include "fastio.h"
35
-#include "watchdog.h"
36 35
 
37 36
 #include <stdint.h>
38 37
 
@@ -176,9 +175,13 @@ public:
176 175
   // Earliest possible init, before setup()
177 176
   MarlinHAL() {}
178 177
 
179
-  static void init();       // Called early in setup()
180
-  static void init_board(); // Called less early in setup()
181
-  static void reboot();     // Software reset
178
+  // Watchdog
179
+  static void watchdog_init()    IF_DISABLED(USE_WATCHDOG, {});
180
+  static void watchdog_refresh() IF_DISABLED(USE_WATCHDOG, {});
181
+
182
+  static void init();          // Called early in setup()
183
+  static void init_board();    // Called less early in setup()
184
+  static void reboot();        // Restart the firmware
182 185
 
183 186
   // Interrupts
184 187
   static bool isr_state() { return !__get_PRIMASK(); }

+ 0
- 114
Marlin/src/HAL/DUE/watchdog.cpp View File

@@ -1,114 +0,0 @@
1
-/**
2
- * Marlin 3D Printer Firmware
3
- * Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
4
- *
5
- * Based on Sprinter and grbl.
6
- * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm
7
- *
8
- * This program is free software: you can redistribute it and/or modify
9
- * it under the terms of the GNU General Public License as published by
10
- * the Free Software Foundation, either version 3 of the License, or
11
- * (at your option) any later version.
12
- *
13
- * This program is distributed in the hope that it will be useful,
14
- * but WITHOUT ANY WARRANTY; without even the implied warranty of
15
- * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the
16
- * GNU General Public License for more details.
17
- *
18
- * You should have received a copy of the GNU General Public License
19
- * along with this program.  If not, see <https://www.gnu.org/licenses/>.
20
- *
21
- */
22
-#ifdef ARDUINO_ARCH_SAM
23
-
24
-#include "../../inc/MarlinConfig.h"
25
-#include "../../MarlinCore.h"
26
-#include "watchdog.h"
27
-
28
-// Override Arduino runtime to either config or disable the watchdog
29
-//
30
-// We need to configure the watchdog as soon as possible in the boot
31
-// process, because watchdog initialization at hardware reset on SAM3X8E
32
-// is unreliable, and there is risk of unintended resets if we delay
33
-// that initialization to a later time.
34
-void watchdogSetup() {
35
-
36
-  #if ENABLED(USE_WATCHDOG)
37
-
38
-    // 4 seconds timeout
39
-    uint32_t timeout = TERN(WATCHDOG_DURATION_8S, 8000, 4000);
40
-
41
-    // Calculate timeout value in WDT counter ticks: This assumes
42
-    // the slow clock is running at 32.768 kHz watchdog
43
-    // frequency is therefore 32768 / 128 = 256 Hz
44
-    timeout = (timeout << 8) / 1000;
45
-    if (timeout == 0)
46
-      timeout = 1;
47
-    else if (timeout > 0xFFF)
48
-      timeout = 0xFFF;
49
-
50
-    // We want to enable the watchdog with the specified timeout
51
-    uint32_t value =
52
-      WDT_MR_WDV(timeout) |               // With the specified timeout
53
-      WDT_MR_WDD(timeout) |               // and no invalid write window
54
-    #if !(SAMV70 || SAMV71 || SAME70 || SAMS70)
55
-      WDT_MR_WDRPROC   |                  // WDT fault resets processor only - We want
56
-                                          // to keep PIO controller state
57
-    #endif
58
-      WDT_MR_WDDBGHLT  |                  // WDT stops in debug state.
59
-      WDT_MR_WDIDLEHLT;                   // WDT stops in idle state.
60
-
61
-    #if ENABLED(WATCHDOG_RESET_MANUAL)
62
-      // We enable the watchdog timer, but only for the interrupt.
63
-
64
-      // Configure WDT to only trigger an interrupt
65
-      value |= WDT_MR_WDFIEN;             // Enable WDT fault interrupt.
66
-
67
-      // Disable WDT interrupt (just in case, to avoid triggering it!)
68
-      NVIC_DisableIRQ(WDT_IRQn);
69
-
70
-      // We NEED memory barriers to ensure Interrupts are actually disabled!
71
-      // ( https://dzone.com/articles/nvic-disabling-interrupts-on-arm-cortex-m-and-the )
72
-      __DSB();
73
-      __ISB();
74
-
75
-      // Initialize WDT with the given parameters
76
-      WDT_Enable(WDT, value);
77
-
78
-      // Configure and enable WDT interrupt.
79
-      NVIC_ClearPendingIRQ(WDT_IRQn);
80
-      NVIC_SetPriority(WDT_IRQn, 0); // Use highest priority, so we detect all kinds of lockups
81
-      NVIC_EnableIRQ(WDT_IRQn);
82
-
83
-    #else
84
-
85
-      // a WDT fault triggers a reset
86
-      value |= WDT_MR_WDRSTEN;
87
-
88
-      // Initialize WDT with the given parameters
89
-      WDT_Enable(WDT, value);
90
-
91
-    #endif
92
-
93
-    // Reset the watchdog
94
-    WDT_Restart(WDT);
95
-
96
-  #else
97
-
98
-    // Make sure to completely disable the Watchdog
99
-    WDT_Disable(WDT);
100
-
101
-  #endif
102
-}
103
-
104
-#if ENABLED(USE_WATCHDOG)
105
-  // Initialize watchdog - On SAM3X, Watchdog was already configured
106
-  //  and enabled or disabled at startup, so no need to reconfigure it
107
-  //  here.
108
-  void watchdog_init() {
109
-    // Reset watchdog to start clean
110
-    WDT_Restart(WDT);
111
-  }
112
-#endif // USE_WATCHDOG
113
-
114
-#endif

+ 0
- 33
Marlin/src/HAL/DUE/watchdog.h View File

@@ -1,33 +0,0 @@
1
-/**
2
- * Marlin 3D Printer Firmware
3
- * Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
4
- *
5
- * Based on Sprinter and grbl.
6
- * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm
7
- *
8
- * This program is free software: you can redistribute it and/or modify
9
- * it under the terms of the GNU General Public License as published by
10
- * the Free Software Foundation, either version 3 of the License, or
11
- * (at your option) any later version.
12
- *
13
- * This program is distributed in the hope that it will be useful,
14
- * but WITHOUT ANY WARRANTY; without even the implied warranty of
15
- * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the
16
- * GNU General Public License for more details.
17
- *
18
- * You should have received a copy of the GNU General Public License
19
- * along with this program.  If not, see <https://www.gnu.org/licenses/>.
20
- *
21
- */
22
-#pragma once
23
-
24
-// Arduino Due core now has watchdog support
25
-
26
-#include "HAL.h"
27
-
28
-// Initialize watchdog with a 4 second interrupt time
29
-void watchdog_init();
30
-
31
-// Reset watchdog. MUST be called at least every 4 seconds after the
32
-// first watchdog_init or AVR will go into emergency procedures.
33
-inline void HAL_watchdog_refresh() { watchdogReset(); }

+ 25
- 0
Marlin/src/HAL/ESP32/HAL.cpp View File

@@ -180,6 +180,31 @@ void _delay_ms(int delay_ms) { delay(delay_ms); }
180 180
 int MarlinHAL::freeMemory() { return ESP.getFreeHeap(); }
181 181
 
182 182
 // ------------------------
183
+// Watchdog Timer
184
+// ------------------------
185
+
186
+#if ENABLED(USE_WATCHDOG)
187
+
188
+  #define WDT_TIMEOUT_US TERN(WATCHDOG_DURATION_8S, 8000000, 4000000) // 4 or 8 second timeout
189
+
190
+  extern "C" {
191
+    esp_err_t esp_task_wdt_reset();
192
+  }
193
+
194
+  void watchdogSetup() {
195
+    // do whatever. don't remove this function.
196
+  }
197
+
198
+  void MarlinHAL::watchdog_init() {
199
+    // TODO
200
+  }
201
+
202
+  // Reset watchdog.
203
+  void MarlinHAL::watchdog_refresh() { esp_task_wdt_reset(); }
204
+
205
+#endif
206
+
207
+// ------------------------
183 208
 // ADC
184 209
 // ------------------------
185 210
 

+ 7
- 4
Marlin/src/HAL/ESP32/HAL.h View File

@@ -32,7 +32,6 @@
32 32
 #include "../shared/HAL_SPI.h"
33 33
 
34 34
 #include "fastio.h"
35
-#include "watchdog.h"
36 35
 #include "i2s.h"
37 36
 
38 37
 #if ENABLED(WIFISUPPORT)
@@ -172,9 +171,13 @@ public:
172 171
   // Earliest possible init, before setup()
173 172
   MarlinHAL() {}
174 173
 
175
-  static void init() {}  // Called early in setup()
176
-  static void init_board();     // Called less early in setup()
177
-  static void reboot();         // Restart the firmware
174
+  // Watchdog
175
+  static void watchdog_init()    IF_DISABLED(USE_WATCHDOG, {});
176
+  static void watchdog_refresh() IF_DISABLED(USE_WATCHDOG, {});
177
+
178
+  static void init() {}        // Called early in setup()
179
+  static void init_board();    // Called less early in setup()
180
+  static void reboot();        // Restart the firmware
178 181
 
179 182
   // Interrupts
180 183
   static portMUX_TYPE spinlock;

+ 0
- 42
Marlin/src/HAL/ESP32/watchdog.cpp View File

@@ -1,42 +0,0 @@
1
-/**
2
- * Marlin 3D Printer Firmware
3
- * Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
4
- *
5
- * Based on Sprinter and grbl.
6
- * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm
7
- *
8
- * This program is free software: you can redistribute it and/or modify
9
- * it under the terms of the GNU General Public License as published by
10
- * the Free Software Foundation, either version 3 of the License, or
11
- * (at your option) any later version.
12
- *
13
- * This program is distributed in the hope that it will be useful,
14
- * but WITHOUT ANY WARRANTY; without even the implied warranty of
15
- * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the
16
- * GNU General Public License for more details.
17
- *
18
- * You should have received a copy of the GNU General Public License
19
- * along with this program.  If not, see <https://www.gnu.org/licenses/>.
20
- *
21
- */
22
-#ifdef ARDUINO_ARCH_ESP32
23
-
24
-#include "../../inc/MarlinConfig.h"
25
-
26
-#if ENABLED(USE_WATCHDOG)
27
-
28
-#define WDT_TIMEOUT_US TERN(WATCHDOG_DURATION_8S, 8000000, 4000000) // 4 or 8 second timeout
29
-
30
-#include "watchdog.h"
31
-
32
-void watchdogSetup() {
33
-  // do whatever. don't remove this function.
34
-}
35
-
36
-void watchdog_init() {
37
-  // TODO
38
-}
39
-
40
-#endif // USE_WATCHDOG
41
-
42
-#endif // ARDUINO_ARCH_ESP32

+ 0
- 38
Marlin/src/HAL/ESP32/watchdog.h View File

@@ -1,38 +0,0 @@
1
-/**
2
- * Marlin 3D Printer Firmware
3
- * Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
4
- *
5
- * Based on Sprinter and grbl.
6
- * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm
7
- *
8
- * This program is free software: you can redistribute it and/or modify
9
- * it under the terms of the GNU General Public License as published by
10
- * the Free Software Foundation, either version 3 of the License, or
11
- * (at your option) any later version.
12
- *
13
- * This program is distributed in the hope that it will be useful,
14
- * but WITHOUT ANY WARRANTY; without even the implied warranty of
15
- * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the
16
- * GNU General Public License for more details.
17
- *
18
- * You should have received a copy of the GNU General Public License
19
- * along with this program.  If not, see <https://www.gnu.org/licenses/>.
20
- *
21
- */
22
-#pragma once
23
-
24
-#ifdef __cplusplus
25
-  extern "C" {
26
-#endif
27
-
28
-  esp_err_t esp_task_wdt_reset();
29
-
30
-#ifdef __cplusplus
31
-  }
32
-#endif
33
-
34
-// Initialize watchdog with a 4 second interrupt time
35
-void watchdog_init();
36
-
37
-// Reset watchdog.
38
-inline void HAL_watchdog_refresh() { esp_task_wdt_reset(); }

+ 0
- 4
Marlin/src/HAL/HAL.h View File

@@ -45,7 +45,3 @@ extern MarlinHAL hal;
45 45
 #ifndef PGMSTR
46 46
   #define PGMSTR(NAM,STR) const char NAM[] = STR
47 47
 #endif
48
-
49
-inline void watchdog_refresh() {
50
-  TERN_(USE_WATCHDOG, HAL_watchdog_refresh());
51
-}

+ 7
- 3
Marlin/src/HAL/LINUX/HAL.h View File

@@ -21,6 +21,8 @@
21 21
  */
22 22
 #pragma once
23 23
 
24
+#include "../../inc/MarlinConfigPre.h"
25
+
24 26
 #include <iostream>
25 27
 #include <stdint.h>
26 28
 #include <stdarg.h>
@@ -29,12 +31,10 @@
29 31
 #include <algorithm>
30 32
 
31 33
 #include "hardware/Clock.h"
32
-
33 34
 #include "../shared/Marduino.h"
34 35
 #include "../shared/math_32bit.h"
35 36
 #include "../shared/HAL_SPI.h"
36 37
 #include "fastio.h"
37
-#include "watchdog.h"
38 38
 #include "serial.h"
39 39
 
40 40
 // ------------------------
@@ -106,9 +106,13 @@ public:
106 106
   // Earliest possible init, before setup()
107 107
   MarlinHAL() {}
108 108
 
109
+  // Watchdog
110
+  static void watchdog_init() {}
111
+  static void watchdog_refresh() {}
112
+
109 113
   static void init() {}        // Called early in setup()
110 114
   static void init_board() {}  // Called less early in setup()
111
-  static void reboot();               // Reset the application state and GPIO
115
+  static void reboot();        // Reset the application state and GPIO
112 116
 
113 117
   // Interrupts
114 118
   static bool isr_state() { return true; }

+ 0
- 37
Marlin/src/HAL/LINUX/watchdog.cpp View File

@@ -1,37 +0,0 @@
1
-/**
2
- * Marlin 3D Printer Firmware
3
- * Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
4
- *
5
- * Based on Sprinter and grbl.
6
- * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm
7
- *
8
- * This program is free software: you can redistribute it and/or modify
9
- * it under the terms of the GNU General Public License as published by
10
- * the Free Software Foundation, either version 3 of the License, or
11
- * (at your option) any later version.
12
- *
13
- * This program is distributed in the hope that it will be useful,
14
- * but WITHOUT ANY WARRANTY; without even the implied warranty of
15
- * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the
16
- * GNU General Public License for more details.
17
- *
18
- * You should have received a copy of the GNU General Public License
19
- * along with this program.  If not, see <https://www.gnu.org/licenses/>.
20
- *
21
- */
22
-#ifdef __PLAT_LINUX__
23
-
24
-#include "../../inc/MarlinConfig.h"
25
-
26
-#if ENABLED(USE_WATCHDOG)
27
-
28
-#include "watchdog.h"
29
-
30
-#define WDT_TIMEOUT_US TERN(WATCHDOG_DURATION_8S, 8000000, 4000000) // 4 or 8 second timeout
31
-
32
-void watchdog_init() {}
33
-void HAL_watchdog_refresh() {}
34
-
35
-#endif
36
-
37
-#endif // __PLAT_LINUX__

+ 0
- 25
Marlin/src/HAL/LINUX/watchdog.h View File

@@ -1,25 +0,0 @@
1
-/**
2
- * Marlin 3D Printer Firmware
3
- * Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
4
- *
5
- * Based on Sprinter and grbl.
6
- * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm
7
- *
8
- * This program is free software: you can redistribute it and/or modify
9
- * it under the terms of the GNU General Public License as published by
10
- * the Free Software Foundation, either version 3 of the License, or
11
- * (at your option) any later version.
12
- *
13
- * This program is distributed in the hope that it will be useful,
14
- * but WITHOUT ANY WARRANTY; without even the implied warranty of
15
- * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the
16
- * GNU General Public License for more details.
17
- *
18
- * You should have received a copy of the GNU General Public License
19
- * along with this program.  If not, see <https://www.gnu.org/licenses/>.
20
- *
21
- */
22
-#pragma once
23
-
24
-void watchdog_init();
25
-void HAL_watchdog_refresh();

+ 47
- 7
Marlin/src/HAL/LPC1768/HAL.cpp View File

@@ -25,10 +25,6 @@
25 25
 #include "../shared/Delay.h"
26 26
 #include "../../../gcode/parser.h"
27 27
 
28
-#if ENABLED(USE_WATCHDOG)
29
-  #include "watchdog.h"
30
-#endif
31
-
32 28
 DefaultSerial1 USBSerial(false, UsbSerial);
33 29
 
34 30
 uint32_t MarlinHAL::adc_result = 0;
@@ -61,9 +57,7 @@ uint8_t MarlinHAL::get_reset_source() {
61 57
   return RST_POWER_ON;
62 58
 }
63 59
 
64
-void MarlinHAL::clear_reset_source() {
65
-  TERN_(USE_WATCHDOG, watchdog_clear_timeout_flag());
66
-}
60
+void MarlinHAL::clear_reset_source() { watchdog_clear_timeout_flag(); }
67 61
 
68 62
 void flashFirmware(const int16_t) {
69 63
   delay(500);          // Give OS time to disconnect
@@ -72,6 +66,52 @@ void flashFirmware(const int16_t) {
72 66
   hal.reboot();
73 67
 }
74 68
 
69
+#if ENABLED(USE_WATCHDOG)
70
+
71
+  #include <lpc17xx_wdt.h>
72
+
73
+  #define WDT_TIMEOUT_US TERN(WATCHDOG_DURATION_8S, 8000000, 4000000) // 4 or 8 second timeout
74
+
75
+  void MarlinHAL::watchdog_init() {
76
+    #if ENABLED(WATCHDOG_RESET_MANUAL)
77
+      // We enable the watchdog timer, but only for the interrupt.
78
+
79
+      // Configure WDT to only trigger an interrupt
80
+      // Disable WDT interrupt (just in case, to avoid triggering it!)
81
+      NVIC_DisableIRQ(WDT_IRQn);
82
+
83
+      // We NEED memory barriers to ensure Interrupts are actually disabled!
84
+      // ( https://dzone.com/articles/nvic-disabling-interrupts-on-arm-cortex-m-and-the )
85
+      __DSB();
86
+      __ISB();
87
+
88
+      // Configure WDT to only trigger an interrupt
89
+      // Initialize WDT with the given parameters
90
+      WDT_Init(WDT_CLKSRC_IRC, WDT_MODE_INT_ONLY);
91
+
92
+      // Configure and enable WDT interrupt.
93
+      NVIC_ClearPendingIRQ(WDT_IRQn);
94
+      NVIC_SetPriority(WDT_IRQn, 0); // Use highest priority, so we detect all kinds of lockups
95
+      NVIC_EnableIRQ(WDT_IRQn);
96
+    #else
97
+      WDT_Init(WDT_CLKSRC_IRC, WDT_MODE_RESET);
98
+    #endif
99
+    WDT_Start(WDT_TIMEOUT_US);
100
+  }
101
+
102
+  void MarlinHAL::watchdog_refresh() {
103
+    WDT_Feed();
104
+    #if DISABLED(PINS_DEBUGGING) && PIN_EXISTS(LED)
105
+      TOGGLE(LED_PIN);  // heartbeat indicator
106
+    #endif
107
+  }
108
+
109
+  // Timeout state
110
+  bool MarlinHAL::watchdog_timed_out() { return TEST(WDT_ReadTimeOutFlag(), 0); }
111
+  void MarlinHAL::watchdog_clear_timeout_flag() { WDT_ClrTimeOutFlag(); }
112
+
113
+#endif // USE_WATCHDOG
114
+
75 115
 // For M42/M43, scan command line for pin code
76 116
 //   return index into pin map array if found and the pin is valid.
77 117
 //   return dval if not found or not a valid pin.

+ 8
- 3
Marlin/src/HAL/LPC1768/HAL.h View File

@@ -38,7 +38,6 @@ extern "C" volatile uint32_t _millis;
38 38
 #include "../shared/math_32bit.h"
39 39
 #include "../shared/HAL_SPI.h"
40 40
 #include "fastio.h"
41
-#include "watchdog.h"
42 41
 #include "MarlinSerial.h"
43 42
 
44 43
 #include <adc.h>
@@ -199,9 +198,9 @@ public:
199 198
   // Earliest possible init, before setup()
200 199
   MarlinHAL() {}
201 200
 
202
-  static void init();                 // Called early in setup()
201
+  static void init();          // Called early in setup()
203 202
   static void init_board() {}  // Called less early in setup()
204
-  static void reboot();               // Restart the firmware from 0x0
203
+  static void reboot();        // Restart the firmware from 0x0
205 204
 
206 205
   // Interrupts
207 206
   static bool isr_state() { return !__get_PRIMASK(); }
@@ -210,6 +209,12 @@ public:
210 209
 
211 210
   static void delay_ms(const int ms) { _delay_ms(ms); }
212 211
 
212
+  // Watchdog
213
+  static void watchdog_init() IF_DISABLED(USE_WATCHDOG, {});
214
+  static void watchdog_refresh() IF_DISABLED(USE_WATCHDOG, {});
215
+  static bool watchdog_timed_out() IF_DISABLED(USE_WATCHDOG, { return false; });
216
+  static void watchdog_clear_timeout_flag() IF_DISABLED(USE_WATCHDOG, {});
217
+
213 218
   // Tasks, called from idle()
214 219
   static void idletask();
215 220
 

+ 0
- 72
Marlin/src/HAL/LPC1768/watchdog.cpp View File

@@ -1,72 +0,0 @@
1
-/**
2
- * Marlin 3D Printer Firmware
3
- * Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
4
- *
5
- * Based on Sprinter and grbl.
6
- * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm
7
- *
8
- * This program is free software: you can redistribute it and/or modify
9
- * it under the terms of the GNU General Public License as published by
10
- * the Free Software Foundation, either version 3 of the License, or
11
- * (at your option) any later version.
12
- *
13
- * This program is distributed in the hope that it will be useful,
14
- * but WITHOUT ANY WARRANTY; without even the implied warranty of
15
- * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the
16
- * GNU General Public License for more details.
17
- *
18
- * You should have received a copy of the GNU General Public License
19
- * along with this program.  If not, see <https://www.gnu.org/licenses/>.
20
- *
21
- */
22
-#ifdef TARGET_LPC1768
23
-
24
-#include "../../inc/MarlinConfig.h"
25
-
26
-#if ENABLED(USE_WATCHDOG)
27
-
28
-#include <lpc17xx_wdt.h>
29
-#include "watchdog.h"
30
-
31
-#define WDT_TIMEOUT_US TERN(WATCHDOG_DURATION_8S, 8000000, 4000000) // 4 or 8 second timeout
32
-
33
-void watchdog_init() {
34
-  #if ENABLED(WATCHDOG_RESET_MANUAL)
35
-    // We enable the watchdog timer, but only for the interrupt.
36
-
37
-    // Configure WDT to only trigger an interrupt
38
-    // Disable WDT interrupt (just in case, to avoid triggering it!)
39
-    NVIC_DisableIRQ(WDT_IRQn);
40
-
41
-    // We NEED memory barriers to ensure Interrupts are actually disabled!
42
-    // ( https://dzone.com/articles/nvic-disabling-interrupts-on-arm-cortex-m-and-the )
43
-    __DSB();
44
-    __ISB();
45
-
46
-    // Configure WDT to only trigger an interrupt
47
-    // Initialize WDT with the given parameters
48
-    WDT_Init(WDT_CLKSRC_IRC, WDT_MODE_INT_ONLY);
49
-
50
-    // Configure and enable WDT interrupt.
51
-    NVIC_ClearPendingIRQ(WDT_IRQn);
52
-    NVIC_SetPriority(WDT_IRQn, 0); // Use highest priority, so we detect all kinds of lockups
53
-    NVIC_EnableIRQ(WDT_IRQn);
54
-  #else
55
-    WDT_Init(WDT_CLKSRC_IRC, WDT_MODE_RESET);
56
-  #endif
57
-  WDT_Start(WDT_TIMEOUT_US);
58
-}
59
-
60
-void HAL_watchdog_refresh() {
61
-  WDT_Feed();
62
-  #if DISABLED(PINS_DEBUGGING) && PIN_EXISTS(LED)
63
-    TOGGLE(LED_PIN);  // heartbeat indicator
64
-  #endif
65
-}
66
-
67
-// Timeout state
68
-bool watchdog_timed_out() { return TEST(WDT_ReadTimeOutFlag(), 0); }
69
-void watchdog_clear_timeout_flag() { WDT_ClrTimeOutFlag(); }
70
-
71
-#endif // USE_WATCHDOG
72
-#endif // TARGET_LPC1768

+ 0
- 28
Marlin/src/HAL/LPC1768/watchdog.h View File

@@ -1,28 +0,0 @@
1
-/**
2
- * Marlin 3D Printer Firmware
3
- * Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
4
- *
5
- * Based on Sprinter and grbl.
6
- * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm
7
- *
8
- * This program is free software: you can redistribute it and/or modify
9
- * it under the terms of the GNU General Public License as published by
10
- * the Free Software Foundation, either version 3 of the License, or
11
- * (at your option) any later version.
12
- *
13
- * This program is distributed in the hope that it will be useful,
14
- * but WITHOUT ANY WARRANTY; without even the implied warranty of
15
- * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the
16
- * GNU General Public License for more details.
17
- *
18
- * You should have received a copy of the GNU General Public License
19
- * along with this program.  If not, see <https://www.gnu.org/licenses/>.
20
- *
21
- */
22
-#pragma once
23
-
24
-void watchdog_init();
25
-void HAL_watchdog_refresh();
26
-
27
-bool watchdog_timed_out();
28
-void watchdog_clear_timeout_flag();

+ 4
- 1
Marlin/src/HAL/NATIVE_SIM/HAL.h View File

@@ -45,7 +45,6 @@ uint8_t _getc();
45 45
 #include "../shared/math_32bit.h"
46 46
 #include "../shared/HAL_SPI.h"
47 47
 #include "fastio.h"
48
-#include "watchdog.h"
49 48
 #include "serial.h"
50 49
 
51 50
 // ------------------------
@@ -208,6 +207,10 @@ public:
208 207
   // Earliest possible init, before setup()
209 208
   MarlinHAL() {}
210 209
 
210
+  // Watchdog
211
+  static void watchdog_init()    IF_DISABLED(USE_WATCHDOG, {});
212
+  static void watchdog_refresh() IF_DISABLED(USE_WATCHDOG, {});
213
+
211 214
   static void init() {}        // Called early in setup()
212 215
   static void init_board() {}  // Called less early in setup()
213 216
   static void reboot();        // Restart the firmware from 0x0

+ 0
- 27
Marlin/src/HAL/NATIVE_SIM/watchdog.h View File

@@ -1,27 +0,0 @@
1
-/**
2
- * Marlin 3D Printer Firmware
3
- * Copyright (c) 2021 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
4
- *
5
- * Based on Sprinter and grbl.
6
- * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm
7
- *
8
- * This program is free software: you can redistribute it and/or modify
9
- * it under the terms of the GNU General Public License as published by
10
- * the Free Software Foundation, either version 3 of the License, or
11
- * (at your option) any later version.
12
- *
13
- * This program is distributed in the hope that it will be useful,
14
- * but WITHOUT ANY WARRANTY; without even the implied warranty of
15
- * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the
16
- * GNU General Public License for more details.
17
- *
18
- * You should have received a copy of the GNU General Public License
19
- * along with this program.  If not, see <https://www.gnu.org/licenses/>.
20
- *
21
- */
22
-#pragma once
23
-
24
-#define WDT_TIMEOUT   4000000 // 4 second timeout
25
-
26
-void watchdog_init();
27
-void HAL_watchdog_refresh();

+ 34
- 0
Marlin/src/HAL/SAMD51/HAL.cpp View File

@@ -203,6 +203,40 @@ enum ADCIndex {
203 203
   ADC_COUNT
204 204
 };
205 205
 
206
+#if ENABLED(USE_WATCHDOG)
207
+
208
+  #define WDT_TIMEOUT_REG TERN(WATCHDOG_DURATION_8S, WDT_CONFIG_PER_CYC8192, WDT_CONFIG_PER_CYC4096) // 4 or 8 second timeout
209
+
210
+  void MarlinHAL::watchdog_init() {
211
+    // The low-power oscillator used by the WDT runs at 32,768 Hz with
212
+    // a 1:32 prescale, thus 1024 Hz, though probably not super precise.
213
+
214
+    // Setup WDT clocks
215
+    MCLK->APBAMASK.bit.OSC32KCTRL_ = true;
216
+    MCLK->APBAMASK.bit.WDT_ = true;
217
+    OSC32KCTRL->OSCULP32K.bit.EN1K = true;  // Enable out 1K (this is what WDT uses)
218
+
219
+    WDT->CTRLA.bit.ENABLE = false;          // Disable watchdog for config
220
+    SYNC(WDT->SYNCBUSY.bit.ENABLE);
221
+
222
+    WDT->INTENCLR.reg = WDT_INTENCLR_EW;    // Disable early warning interrupt
223
+    WDT->CONFIG.reg = WDT_TIMEOUT_REG;      // Set a 4s or 8s period for chip reset
224
+
225
+    hal.watchdog_refresh();
226
+
227
+    WDT->CTRLA.reg = WDT_CTRLA_ENABLE;      // Start watchdog now in normal mode
228
+    SYNC(WDT->SYNCBUSY.bit.ENABLE);
229
+  }
230
+
231
+  // Reset watchdog. MUST be called at least every 4 seconds after the
232
+  // first watchdog_init or SAMD will go into emergency procedures.
233
+  void MarlinHAL::watchdog_refresh() {
234
+    SYNC(WDT->SYNCBUSY.bit.CLEAR);        // Test first if previous is 'ongoing' to save time waiting for command execution
235
+    WDT->CLEAR.reg = WDT_CLEAR_CLEAR_KEY;
236
+  }
237
+
238
+#endif
239
+
206 240
 // ------------------------
207 241
 // Types
208 242
 // ------------------------

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

@@ -26,7 +26,6 @@
26 26
 #include "../shared/math_32bit.h"
27 27
 #include "../shared/HAL_SPI.h"
28 28
 #include "fastio.h"
29
-#include "watchdog.h"
30 29
 
31 30
 #ifdef ADAFRUIT_GRAND_CENTRAL_M4
32 31
   #include "MarlinSerial_AGCM4.h"
@@ -157,6 +156,10 @@ public:
157 156
   // Earliest possible init, before setup()
158 157
   MarlinHAL() {}
159 158
 
159
+  // Watchdog
160
+  static void watchdog_init()    IF_DISABLED(USE_WATCHDOG, {});
161
+  static void watchdog_refresh() IF_DISABLED(USE_WATCHDOG, {});
162
+
160 163
   static void init();          // Called early in setup()
161 164
   static void init_board() {}  // Called less early in setup()
162 165
   static void reboot();        // Restart the firmware from 0x0

+ 0
- 54
Marlin/src/HAL/SAMD51/watchdog.cpp View File

@@ -1,54 +0,0 @@
1
-/**
2
- * Marlin 3D Printer Firmware
3
- *
4
- * Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
5
- * SAMD51 HAL developed by Giuliano Zaro (AKA GMagician)
6
- *
7
- * This program is free software: you can redistribute it and/or modify
8
- * it under the terms of the GNU General Public License as published by
9
- * the Free Software Foundation, either version 3 of the License, or
10
- * (at your option) any later version.
11
- *
12
- * This program is distributed in the hope that it will be useful,
13
- * but WITHOUT ANY WARRANTY; without even the implied warranty of
14
- * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the
15
- * GNU General Public License for more details.
16
- *
17
- * You should have received a copy of the GNU General Public License
18
- * along with this program.  If not, see <https://www.gnu.org/licenses/>.
19
- *
20
- */
21
-#ifdef __SAMD51__
22
-
23
-#include "../../inc/MarlinConfig.h"
24
-
25
-#if ENABLED(USE_WATCHDOG)
26
-
27
-#include "watchdog.h"
28
-
29
-#define WDT_TIMEOUT_REG TERN(WATCHDOG_DURATION_8S, WDT_CONFIG_PER_CYC8192, WDT_CONFIG_PER_CYC4096) // 4 or 8 second timeout
30
-
31
-void watchdog_init() {
32
-  // The low-power oscillator used by the WDT runs at 32,768 Hz with
33
-  // a 1:32 prescale, thus 1024 Hz, though probably not super precise.
34
-
35
-  // Setup WDT clocks
36
-  MCLK->APBAMASK.bit.OSC32KCTRL_ = true;
37
-  MCLK->APBAMASK.bit.WDT_ = true;
38
-  OSC32KCTRL->OSCULP32K.bit.EN1K = true;      // Enable out 1K (this is what WDT uses)
39
-
40
-  WDT->CTRLA.bit.ENABLE = false;              // Disable watchdog for config
41
-  SYNC(WDT->SYNCBUSY.bit.ENABLE);
42
-
43
-  WDT->INTENCLR.reg = WDT_INTENCLR_EW;        // Disable early warning interrupt
44
-  WDT->CONFIG.reg = WDT_TIMEOUT_REG;          // Set a 4s or 8s period for chip reset
45
-
46
-  HAL_watchdog_refresh();
47
-
48
-  WDT->CTRLA.reg = WDT_CTRLA_ENABLE;          // Start watchdog now in normal mode
49
-  SYNC(WDT->SYNCBUSY.bit.ENABLE);
50
-}
51
-
52
-#endif // USE_WATCHDOG
53
-
54
-#endif // __SAMD51__

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

@@ -1,31 +0,0 @@
1
-/**
2
- * Marlin 3D Printer Firmware
3
- *
4
- * Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
5
- * SAMD51 HAL developed by Giuliano Zaro (AKA GMagician)
6
- *
7
- * This program is free software: you can redistribute it and/or modify
8
- * it under the terms of the GNU General Public License as published by
9
- * the Free Software Foundation, either version 3 of the License, or
10
- * (at your option) any later version.
11
- *
12
- * This program is distributed in the hope that it will be useful,
13
- * but WITHOUT ANY WARRANTY; without even the implied warranty of
14
- * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the
15
- * GNU General Public License for more details.
16
- *
17
- * You should have received a copy of the GNU General Public License
18
- * along with this program.  If not, see <https://www.gnu.org/licenses/>.
19
- *
20
- */
21
-#pragma once
22
-
23
-// Initialize watchdog with a 4 second interrupt time
24
-void watchdog_init();
25
-
26
-// Reset watchdog. MUST be called at least every 4 seconds after the
27
-// first watchdog_init or SAMD will go into emergency procedures.
28
-inline void HAL_watchdog_refresh() {
29
-  SYNC(WDT->SYNCBUSY.bit.CLEAR);        // Test first if previous is 'ongoing' to save time waiting for command execution
30
-  WDT->CLEAR.reg = WDT_CLEAR_CLEAR_KEY;
31
-}

+ 23
- 0
Marlin/src/HAL/STM32/HAL.cpp View File

@@ -140,6 +140,29 @@ uint8_t MarlinHAL::get_reset_source() {
140 140
 
141 141
 void MarlinHAL::clear_reset_source() { __HAL_RCC_CLEAR_RESET_FLAGS(); }
142 142
 
143
+// ------------------------
144
+// Watchdog Timer
145
+// ------------------------
146
+
147
+#if ENABLED(USE_WATCHDOG)
148
+
149
+  #define WDT_TIMEOUT_US TERN(WATCHDOG_DURATION_8S, 8000000, 4000000) // 4 or 8 second timeout
150
+
151
+  #include <IWatchdog.h>
152
+
153
+  void MarlinHAL::watchdog_init() {
154
+    IF_DISABLED(DISABLE_WATCHDOG_INIT, IWatchdog.begin(WDT_TIMEOUT_US));
155
+  }
156
+
157
+  void MarlinHAL::watchdog_refresh() {
158
+    IWatchdog.reload();
159
+    #if DISABLED(PINS_DEBUGGING) && PIN_EXISTS(LED)
160
+      TOGGLE(LED_PIN);  // heartbeat indicator
161
+    #endif
162
+  }
163
+
164
+#endif
165
+
143 166
 extern "C" {
144 167
   extern unsigned int _ebss; // end of bss section
145 168
 }

+ 6
- 3
Marlin/src/HAL/STM32/HAL.h View File

@@ -30,7 +30,6 @@
30 30
 #include "../shared/HAL_SPI.h"
31 31
 #include "fastio.h"
32 32
 #include "Servo.h"
33
-#include "watchdog.h"
34 33
 #include "MarlinSerial.h"
35 34
 
36 35
 #include "../../inc/MarlinConfigPre.h"
@@ -218,9 +217,13 @@ public:
218 217
   // Earliest possible init, before setup()
219 218
   MarlinHAL() {}
220 219
 
221
-  static void init();                 // Called early in setup()
220
+  // Watchdog
221
+  static void watchdog_init()    IF_DISABLED(USE_WATCHDOG, {});
222
+  static void watchdog_refresh() IF_DISABLED(USE_WATCHDOG, {});
223
+
224
+  static void init();          // Called early in setup()
222 225
   static void init_board() {}  // Called less early in setup()
223
-  static void reboot();               // Restart the firmware from 0x0
226
+  static void reboot();        // Restart the firmware from 0x0
224 227
 
225 228
   // Interrupts
226 229
   static bool isr_state() { return !__get_PRIMASK(); }

+ 1
- 2
Marlin/src/HAL/STM32/MinSerial.cpp View File

@@ -29,7 +29,6 @@
29 29
 #if ENABLED(POSTMORTEM_DEBUGGING)
30 30
 
31 31
 #include "../shared/MinSerial.h"
32
-#include "watchdog.h"
33 32
 
34 33
 /* Instruction Synchronization Barrier */
35 34
 #define isb() __asm__ __volatile__ ("isb" : : : "memory")
@@ -120,7 +119,7 @@ static void TX(char c) {
120 119
   #if WITHIN(SERIAL_PORT, 1, 6)
121 120
     constexpr uint32_t usart_sr_txe = _BV(7);
122 121
     while (!(regs->SR & usart_sr_txe)) {
123
-      TERN_(USE_WATCHDOG, HAL_watchdog_refresh());
122
+      hal.watchdog_refresh();
124 123
       sw_barrier();
125 124
     }
126 125
     regs->DR = c;

+ 4
- 4
Marlin/src/HAL/STM32/sdio.cpp View File

@@ -208,7 +208,7 @@ bool SDIO_Init() {
208 208
 
209 209
   uint8_t retry_Cnt = retryCnt;
210 210
   for (;;) {
211
-    TERN_(USE_WATCHDOG, HAL_watchdog_refresh());
211
+    hal.watchdog_refresh();
212 212
     status = (bool) HAL_SD_Init(&hsd);
213 213
     if (!status) break;
214 214
     if (!--retry_Cnt) return false;   // return failing status if retries are exhausted
@@ -219,7 +219,7 @@ bool SDIO_Init() {
219 219
   #if PINS_EXIST(SDIO_D1, SDIO_D2, SDIO_D3) // go to 4 bit wide mode if pins are defined
220 220
     retry_Cnt = retryCnt;
221 221
     for (;;) {
222
-      TERN_(USE_WATCHDOG, HAL_watchdog_refresh());
222
+      hal.watchdog_refresh();
223 223
       if (!HAL_SD_ConfigWideBusOperation(&hsd, SDIO_BUS_WIDE_4B)) break;  // some cards are only 1 bit wide so a pass here is not required
224 224
       if (!--retry_Cnt) break;
225 225
     }
@@ -228,7 +228,7 @@ bool SDIO_Init() {
228 228
       SD_LowLevel_Init();
229 229
       retry_Cnt = retryCnt;
230 230
       for (;;) {
231
-        TERN_(USE_WATCHDOG, HAL_watchdog_refresh());
231
+        hal.watchdog_refresh();
232 232
         status = (bool) HAL_SD_Init(&hsd);
233 233
         if (!status) break;
234 234
         if (!--retry_Cnt) return false;   // return failing status if retries are exhausted
@@ -243,7 +243,7 @@ bool SDIO_Init() {
243 243
 static bool SDIO_ReadWriteBlock_DMA(uint32_t block, const uint8_t *src, uint8_t *dst) {
244 244
   if (HAL_SD_GetCardState(&hsd) != HAL_SD_CARD_TRANSFER) return false;
245 245
 
246
-  TERN_(USE_WATCHDOG, HAL_watchdog_refresh());
246
+  hal.watchdog_refresh();
247 247
 
248 248
   HAL_StatusTypeDef ret;
249 249
   if (src) {

+ 0
- 52
Marlin/src/HAL/STM32/watchdog.cpp View File

@@ -1,52 +0,0 @@
1
-/**
2
- * Marlin 3D Printer Firmware
3
- * Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
4
- *
5
- * Based on Sprinter and grbl.
6
- * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm
7
- *
8
- * This program is free software: you can redistribute it and/or modify
9
- * it under the terms of the GNU General Public License as published by
10
- * the Free Software Foundation, either version 3 of the License, or
11
- * (at your option) any later version.
12
- *
13
- * This program is distributed in the hope that it will be useful,
14
- * but WITHOUT ANY WARRANTY; without even the implied warranty of
15
- * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the
16
- * GNU General Public License for more details.
17
- *
18
- * You should have received a copy of the GNU General Public License
19
- * along with this program.  If not, see <https://www.gnu.org/licenses/>.
20
- *
21
- */
22
-
23
-#include "../platforms.h"
24
-
25
-#ifdef HAL_STM32
26
-
27
-#include "../../inc/MarlinConfigPre.h"
28
-
29
-#if ENABLED(USE_WATCHDOG)
30
-
31
-#define WDT_TIMEOUT_US TERN(WATCHDOG_DURATION_8S, 8000000, 4000000) // 4 or 8 second timeout
32
-
33
-#include "../../inc/MarlinConfig.h"
34
-
35
-#include "watchdog.h"
36
-#include <IWatchdog.h>
37
-
38
-void watchdog_init() {
39
-  #if DISABLED(DISABLE_WATCHDOG_INIT)
40
-    IWatchdog.begin(WDT_TIMEOUT_US);
41
-  #endif
42
-}
43
-
44
-void HAL_watchdog_refresh() {
45
-  IWatchdog.reload();
46
-  #if DISABLED(PINS_DEBUGGING) && PIN_EXISTS(LED)
47
-    TOGGLE(LED_PIN);  // heartbeat indicator
48
-  #endif
49
-}
50
-
51
-#endif // USE_WATCHDOG
52
-#endif // HAL_STM32

+ 0
- 25
Marlin/src/HAL/STM32/watchdog.h View File

@@ -1,25 +0,0 @@
1
-/**
2
- * Marlin 3D Printer Firmware
3
- * Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
4
- *
5
- * Based on Sprinter and grbl.
6
- * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm
7
- *
8
- * This program is free software: you can redistribute it and/or modify
9
- * it under the terms of the GNU General Public License as published by
10
- * the Free Software Foundation, either version 3 of the License, or
11
- * (at your option) any later version.
12
- *
13
- * This program is distributed in the hope that it will be useful,
14
- * but WITHOUT ANY WARRANTY; without even the implied warranty of
15
- * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the
16
- * GNU General Public License for more details.
17
- *
18
- * You should have received a copy of the GNU General Public License
19
- * along with this program.  If not, see <https://www.gnu.org/licenses/>.
20
- *
21
- */
22
-#pragma once
23
-
24
-void watchdog_init();
25
-void HAL_watchdog_refresh();

+ 41
- 0
Marlin/src/HAL/STM32F1/HAL.cpp View File

@@ -114,6 +114,47 @@
114 114
 #endif
115 115
 
116 116
 // ------------------------
117
+// Watchdog Timer
118
+// ------------------------
119
+
120
+#if ENABLED(USE_WATCHDOG)
121
+
122
+  #include <libmaple/iwdg.h>
123
+
124
+  void watchdogSetup() {
125
+    // do whatever. don't remove this function.
126
+  }
127
+
128
+  /**
129
+   *  The watchdog clock is 40Khz. So for a 4s or 8s interval use a /256 preescaler and 625 or 1250 reload value (counts down to 0).
130
+   */
131
+  #define STM32F1_WD_RELOAD TERN(WATCHDOG_DURATION_8S, 1250, 625) // 4 or 8 second timeout
132
+
133
+  /**
134
+   * @brief  Initialize the independent hardware watchdog.
135
+   *
136
+   * @return No return
137
+   *
138
+   * @details The watchdog clock is 40Khz. So for a 4s or 8s interval use a /256 preescaler and 625 or 1250 reload value (counts down to 0).
139
+   */
140
+  void MarlinHAL::watchdog_init() {
141
+    #if DISABLED(DISABLE_WATCHDOG_INIT)
142
+      iwdg_init(IWDG_PRE_256, STM32F1_WD_RELOAD);
143
+    #endif
144
+  }
145
+
146
+  // Reset watchdog. MUST be called every 4 or 8 seconds after the
147
+  // first watchdog_init or the STM32F1 will reset.
148
+  void MarlinHAL::watchdog_refresh() {
149
+    #if DISABLED(PINS_DEBUGGING) && PIN_EXISTS(LED)
150
+      TOGGLE(LED_PIN);  // heartbeat indicator
151
+    #endif
152
+    iwdg_feed();
153
+  }
154
+
155
+#endif // USE_WATCHDOG
156
+
157
+// ------------------------
117 158
 // ADC
118 159
 // ------------------------
119 160
 

+ 4
- 1
Marlin/src/HAL/STM32F1/HAL.h View File

@@ -34,7 +34,6 @@
34 34
 #include "../shared/HAL_SPI.h"
35 35
 
36 36
 #include "fastio.h"
37
-#include "watchdog.h"
38 37
 
39 38
 #include <stdint.h>
40 39
 #include <util/atomic.h>
@@ -247,6 +246,10 @@ public:
247 246
   // Earliest possible init, before setup()
248 247
   MarlinHAL() {}
249 248
 
249
+  // Watchdog
250
+  static void watchdog_init()    IF_DISABLED(USE_WATCHDOG, {});
251
+  static void watchdog_refresh() IF_DISABLED(USE_WATCHDOG, {});
252
+
250 253
   static void init();          // Called early in setup()
251 254
   static void init_board() {}  // Called less early in setup()
252 255
   static void reboot();        // Restart the firmware from 0x0

+ 1
- 2
Marlin/src/HAL/STM32F1/MinSerial.cpp View File

@@ -27,7 +27,6 @@
27 27
 #if ENABLED(POSTMORTEM_DEBUGGING)
28 28
 
29 29
 #include "../shared/MinSerial.h"
30
-#include "watchdog.h"
31 30
 
32 31
 #include <libmaple/usart.h>
33 32
 #include <libmaple/rcc.h>
@@ -82,7 +81,7 @@ static void TX(char c) {
82 81
   #if WITHIN(SERIAL_PORT, 1, 6)
83 82
     struct usart_dev* dev = MYSERIAL1.c_dev();
84 83
     while (!(dev->regs->SR & USART_SR_TXE)) {
85
-      TERN_(USE_WATCHDOG, HAL_watchdog_refresh());
84
+      hal.watchdog_refresh();
86 85
       sw_barrier();
87 86
     }
88 87
     dev->regs->DR = c;

+ 0
- 66
Marlin/src/HAL/STM32F1/watchdog.cpp View File

@@ -1,66 +0,0 @@
1
-/**
2
- * Marlin 3D Printer Firmware
3
- * Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
4
- *
5
- * Based on Sprinter and grbl.
6
- * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm
7
- *
8
- * This program is free software: you can redistribute it and/or modify
9
- * it under the terms of the GNU General Public License as published by
10
- * the Free Software Foundation, either version 3 of the License, or
11
- * (at your option) any later version.
12
- *
13
- * This program is distributed in the hope that it will be useful,
14
- * but WITHOUT ANY WARRANTY; without even the implied warranty of
15
- * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the
16
- * GNU General Public License for more details.
17
- *
18
- * You should have received a copy of the GNU General Public License
19
- * along with this program.  If not, see <https://www.gnu.org/licenses/>.
20
- *
21
- */
22
-
23
-/**
24
- * HAL for stm32duino.com based on Libmaple and compatible (STM32F1)
25
- */
26
-
27
-#ifdef __STM32F1__
28
-
29
-#include "../../inc/MarlinConfig.h"
30
-
31
-#if ENABLED(USE_WATCHDOG)
32
-
33
-#include <libmaple/iwdg.h>
34
-#include "watchdog.h"
35
-
36
-/**
37
- *  The watchdog clock is 40Khz. So for a 4s or 8s interval use a /256 preescaler and 625 or 1250 reload value (counts down to 0).
38
- */
39
-#define STM32F1_WD_RELOAD TERN(WATCHDOG_DURATION_8S, 1250, 625) // 4 or 8 second timeout
40
-
41
-void HAL_watchdog_refresh() {
42
-  #if DISABLED(PINS_DEBUGGING) && PIN_EXISTS(LED)
43
-    TOGGLE(LED_PIN);  // heartbeat indicator
44
-  #endif
45
-  iwdg_feed();
46
-}
47
-
48
-void watchdogSetup() {
49
-  // do whatever. don't remove this function.
50
-}
51
-
52
-/**
53
- * @brief  Initialized the independent hardware watchdog.
54
- *
55
- * @return No return
56
- *
57
- * @details The watchdog clock is 40Khz. So for a 4s or 8s interval use a /256 preescaler and 625 or 1250 reload value (counts down to 0).
58
- */
59
-void watchdog_init() {
60
-  #if DISABLED(DISABLE_WATCHDOG_INIT)
61
-    iwdg_init(IWDG_PRE_256, STM32F1_WD_RELOAD);
62
-  #endif
63
-}
64
-
65
-#endif // USE_WATCHDOG
66
-#endif // __STM32F1__

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

@@ -1,35 +0,0 @@
1
-/**
2
- * Marlin 3D Printer Firmware
3
- * Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
4
- *
5
- * Based on Sprinter and grbl.
6
- * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm
7
- *
8
- * This program is free software: you can redistribute it and/or modify
9
- * it under the terms of the GNU General Public License as published by
10
- * the Free Software Foundation, either version 3 of the License, or
11
- * (at your option) any later version.
12
- *
13
- * This program is distributed in the hope that it will be useful,
14
- * but WITHOUT ANY WARRANTY; without even the implied warranty of
15
- * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the
16
- * GNU General Public License for more details.
17
- *
18
- * You should have received a copy of the GNU General Public License
19
- * along with this program.  If not, see <https://www.gnu.org/licenses/>.
20
- *
21
- */
22
-#pragma once
23
-
24
-/**
25
- * HAL for stm32duino.com based on Libmaple and compatible (STM32F1)
26
- */
27
-
28
-#include <libmaple/iwdg.h>
29
-
30
-// Initialize watchdog with a 4 or 8 second countdown time
31
-void watchdog_init();
32
-
33
-// Reset watchdog. MUST be called every 4 or 8 seconds after the
34
-// first watchdog_init or the STM32F1 will reset.
35
-void HAL_watchdog_refresh();

+ 22
- 0
Marlin/src/HAL/TEENSY31_32/HAL.cpp View File

@@ -63,6 +63,28 @@ uint8_t MarlinHAL::get_reset_source() {
63 63
 }
64 64
 
65 65
 // ------------------------
66
+// Watchdog Timer
67
+// ------------------------
68
+
69
+#if ENABLED(USE_WATCHDOG)
70
+
71
+  #define WDT_TIMEOUT_MS TERN(WATCHDOG_DURATION_8S, 8000, 4000) // 4 or 8 second timeout
72
+
73
+  void MarlinHAL::watchdog_init() {
74
+    WDOG_TOVALH = 0;
75
+    WDOG_TOVALL = WDT_TIMEOUT_MS;
76
+    WDOG_STCTRLH = WDOG_STCTRLH_WDOGEN;
77
+  }
78
+
79
+  void MarlinHAL::watchdog_refresh() {
80
+    // Watchdog refresh sequence
81
+    WDOG_REFRESH = 0xA602;
82
+    WDOG_REFRESH = 0xB480;
83
+  }
84
+
85
+#endif
86
+
87
+// ------------------------
66 88
 // ADC
67 89
 // ------------------------
68 90
 

+ 4
- 1
Marlin/src/HAL/TEENSY31_32/HAL.h View File

@@ -32,7 +32,6 @@
32 32
 #include "../shared/HAL_SPI.h"
33 33
 
34 34
 #include "fastio.h"
35
-#include "watchdog.h"
36 35
 
37 36
 #include <stdint.h>
38 37
 
@@ -135,6 +134,10 @@ public:
135 134
   // Earliest possible init, before setup()
136 135
   MarlinHAL() {}
137 136
 
137
+  // Watchdog
138
+  static void watchdog_init()    IF_DISABLED(USE_WATCHDOG, {});
139
+  static void watchdog_refresh() IF_DISABLED(USE_WATCHDOG, {});
140
+
138 141
   static void init() {}        // Called early in setup()
139 142
   static void init_board() {}  // Called less early in setup()
140 143
   static void reboot();        // Restart the firmware from 0x0

+ 0
- 40
Marlin/src/HAL/TEENSY31_32/watchdog.cpp View File

@@ -1,40 +0,0 @@
1
-/**
2
- * Marlin 3D Printer Firmware
3
- * Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
4
- *
5
- * Based on Sprinter and grbl.
6
- * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm
7
- *
8
- * This program is free software: you can redistribute it and/or modify
9
- * it under the terms of the GNU General Public License as published by
10
- * the Free Software Foundation, either version 3 of the License, or
11
- * (at your option) any later version.
12
- *
13
- * This program is distributed in the hope that it will be useful,
14
- * but WITHOUT ANY WARRANTY; without even the implied warranty of
15
- * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the
16
- * GNU General Public License for more details.
17
- *
18
- * You should have received a copy of the GNU General Public License
19
- * along with this program.  If not, see <https://www.gnu.org/licenses/>.
20
- *
21
- */
22
-#ifdef __MK20DX256__
23
-
24
-#include "../../inc/MarlinConfig.h"
25
-
26
-#if ENABLED(USE_WATCHDOG)
27
-
28
-#include "watchdog.h"
29
-
30
-#define WDT_TIMEOUT_MS TERN(WATCHDOG_DURATION_8S, 8000, 4000) // 4 or 8 second timeout
31
-
32
-void watchdog_init() {
33
-  WDOG_TOVALH = 0;
34
-  WDOG_TOVALL = WDT_TIMEOUT_MS;
35
-  WDOG_STCTRLH = WDOG_STCTRLH_WDOGEN;
36
-}
37
-
38
-#endif // USE_WATCHDOG
39
-
40
-#endif // __MK20DX256__

+ 0
- 34
Marlin/src/HAL/TEENSY31_32/watchdog.h View File

@@ -1,34 +0,0 @@
1
-/**
2
- * Marlin 3D Printer Firmware
3
- * Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
4
- *
5
- * Based on Sprinter and grbl.
6
- * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm
7
- *
8
- * This program is free software: you can redistribute it and/or modify
9
- * it under the terms of the GNU General Public License as published by
10
- * the Free Software Foundation, either version 3 of the License, or
11
- * (at your option) any later version.
12
- *
13
- * This program is distributed in the hope that it will be useful,
14
- * but WITHOUT ANY WARRANTY; without even the implied warranty of
15
- * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the
16
- * GNU General Public License for more details.
17
- *
18
- * You should have received a copy of the GNU General Public License
19
- * along with this program.  If not, see <https://www.gnu.org/licenses/>.
20
- *
21
- */
22
-#pragma once
23
-
24
-#include "HAL.h"
25
-
26
-// Arduino Due core now has watchdog support
27
-
28
-void watchdog_init();
29
-
30
-inline void HAL_watchdog_refresh() {
31
-  // Watchdog refresh sequence
32
-  WDOG_REFRESH = 0xA602;
33
-  WDOG_REFRESH = 0xB480;
34
-}

+ 22
- 0
Marlin/src/HAL/TEENSY35_36/HAL.cpp View File

@@ -62,6 +62,28 @@ uint8_t MarlinHAL::get_reset_source() {
62 62
 }
63 63
 
64 64
 // ------------------------
65
+// Watchdog Timer
66
+// ------------------------
67
+
68
+#if ENABLED(USE_WATCHDOG)
69
+
70
+  #define WDT_TIMEOUT_MS TERN(WATCHDOG_DURATION_8S, 8000, 4000) // 4 or 8 second timeout
71
+
72
+  void MarlinHAL::watchdog_init() {
73
+    WDOG_TOVALH = 0;
74
+    WDOG_TOVALL = WDT_TIMEOUT_MS;
75
+    WDOG_STCTRLH = WDOG_STCTRLH_WDOGEN;
76
+  }
77
+
78
+  void MarlinHAL::watchdog_refresh() {
79
+    // Watchdog refresh sequence
80
+    WDOG_REFRESH = 0xA602;
81
+    WDOG_REFRESH = 0xB480;
82
+  }
83
+
84
+#endif
85
+
86
+// ------------------------
65 87
 // ADC
66 88
 // ------------------------
67 89
 

+ 4
- 1
Marlin/src/HAL/TEENSY35_36/HAL.h View File

@@ -32,7 +32,6 @@
32 32
 #include "../shared/HAL_SPI.h"
33 33
 
34 34
 #include "fastio.h"
35
-#include "watchdog.h"
36 35
 
37 36
 #include <stdint.h>
38 37
 #include <util/atomic.h>
@@ -140,6 +139,10 @@ public:
140 139
   // Earliest possible init, before setup()
141 140
   MarlinHAL() {}
142 141
 
142
+  // Watchdog
143
+  static void watchdog_init()    IF_DISABLED(USE_WATCHDOG, {});
144
+  static void watchdog_refresh() IF_DISABLED(USE_WATCHDOG, {});
145
+
143 146
   static void init() {}        // Called early in setup()
144 147
   static void init_board() {}  // Called less early in setup()
145 148
   static void reboot();        // Restart the firmware from 0x0

+ 0
- 40
Marlin/src/HAL/TEENSY35_36/watchdog.cpp View File

@@ -1,40 +0,0 @@
1
-/**
2
- * Marlin 3D Printer Firmware
3
- * Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
4
- *
5
- * Based on Sprinter and grbl.
6
- * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm
7
- *
8
- * This program is free software: you can redistribute it and/or modify
9
- * it under the terms of the GNU General Public License as published by
10
- * the Free Software Foundation, either version 3 of the License, or
11
- * (at your option) any later version.
12
- *
13
- * This program is distributed in the hope that it will be useful,
14
- * but WITHOUT ANY WARRANTY; without even the implied warranty of
15
- * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the
16
- * GNU General Public License for more details.
17
- *
18
- * You should have received a copy of the GNU General Public License
19
- * along with this program.  If not, see <https://www.gnu.org/licenses/>.
20
- *
21
- */
22
-#if defined(__MK64FX512__) || defined(__MK66FX1M0__)
23
-
24
-#include "../../inc/MarlinConfig.h"
25
-
26
-#if ENABLED(USE_WATCHDOG)
27
-
28
-#include "watchdog.h"
29
-
30
-#define WDT_TIMEOUT_MS TERN(WATCHDOG_DURATION_8S, 8000, 4000) // 4 or 8 second timeout
31
-
32
-void watchdog_init() {
33
-  WDOG_TOVALH = 0;
34
-  WDOG_TOVALL = WDT_TIMEOUT_MS;
35
-  WDOG_STCTRLH = WDOG_STCTRLH_WDOGEN;
36
-}
37
-
38
-#endif // USE_WATCHDOG
39
-
40
-#endif // __MK64FX512__ || __MK66FX1M0__

+ 0
- 30
Marlin/src/HAL/TEENSY35_36/watchdog.h View File

@@ -1,30 +0,0 @@
1
-/**
2
- * Marlin 3D Printer Firmware
3
- * Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
4
- *
5
- * Based on Sprinter and grbl.
6
- * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm
7
- *
8
- * This program is free software: you can redistribute it and/or modify
9
- * it under the terms of the GNU General Public License as published by
10
- * the Free Software Foundation, either version 3 of the License, or
11
- * (at your option) any later version.
12
- *
13
- * This program is distributed in the hope that it will be useful,
14
- * but WITHOUT ANY WARRANTY; without even the implied warranty of
15
- * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the
16
- * GNU General Public License for more details.
17
- *
18
- * You should have received a copy of the GNU General Public License
19
- * along with this program.  If not, see <https://www.gnu.org/licenses/>.
20
- *
21
- */
22
-#pragma once
23
-
24
-void watchdog_init();
25
-
26
-inline void HAL_watchdog_refresh() {
27
-  // Watchdog refresh sequence
28
-  WDOG_REFRESH = 0xA602;
29
-  WDOG_REFRESH = 0xB480;
30
-}

+ 25
- 0
Marlin/src/HAL/TEENSY40_41/HAL.cpp View File

@@ -79,6 +79,31 @@ void MarlinHAL::clear_reset_source() {
79 79
 }
80 80
 
81 81
 // ------------------------
82
+// Watchdog Timer
83
+// ------------------------
84
+
85
+#if ENABLED(USE_WATCHDOG)
86
+
87
+  #define WDT_TIMEOUT TERN(WATCHDOG_DURATION_8S, 8, 4) // 4 or 8 second timeout
88
+
89
+  constexpr uint8_t timeoutval = (WDT_TIMEOUT - 0.5f) / 0.5f;
90
+
91
+  void MarlinHAL::watchdog_init() {
92
+    CCM_CCGR3 |= CCM_CCGR3_WDOG1(3);  // enable WDOG1 clocks
93
+    WDOG1_WMCR = 0;                   // disable power down PDE
94
+    WDOG1_WCR |= WDOG_WCR_SRS | WDOG_WCR_WT(timeoutval);
95
+    WDOG1_WCR |= WDOG_WCR_WDE | WDOG_WCR_WDT | WDOG_WCR_SRE;
96
+  }
97
+
98
+  void MarlinHAL::watchdog_refresh() {
99
+    // Watchdog refresh sequence
100
+    WDOG1_WSR = 0x5555;
101
+    WDOG1_WSR = 0xAAAA;
102
+  }
103
+
104
+#endif
105
+
106
+// ------------------------
82 107
 // ADC
83 108
 // ------------------------
84 109
 

+ 4
- 1
Marlin/src/HAL/TEENSY40_41/HAL.h View File

@@ -32,7 +32,6 @@
32 32
 #include "../shared/HAL_SPI.h"
33 33
 
34 34
 #include "fastio.h"
35
-#include "watchdog.h"
36 35
 
37 36
 #include <stdint.h>
38 37
 #include <util/atomic.h>
@@ -162,6 +161,10 @@ public:
162 161
   // Earliest possible init, before setup()
163 162
   MarlinHAL() {}
164 163
 
164
+  // Watchdog
165
+  static void watchdog_init()    IF_DISABLED(USE_WATCHDOG, {});
166
+  static void watchdog_refresh() IF_DISABLED(USE_WATCHDOG, {});
167
+
165 168
   static void init() {}        // Called early in setup()
166 169
   static void init_board() {}  // Called less early in setup()
167 170
   static void reboot();        // Restart the firmware from 0x0

+ 0
- 52
Marlin/src/HAL/TEENSY40_41/watchdog.cpp View File

@@ -1,52 +0,0 @@
1
-/**
2
- * Marlin 3D Printer Firmware
3
- * Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
4
- *
5
- * Based on Sprinter and grbl.
6
- * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm
7
- *
8
- * This program is free software: you can redistribute it and/or modify
9
- * it under the terms of the GNU General Public License as published by
10
- * the Free Software Foundation, either version 3 of the License, or
11
- * (at your option) any later version.
12
- *
13
- * This program is distributed in the hope that it will be useful,
14
- * but WITHOUT ANY WARRANTY; without even the implied warranty of
15
- * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the
16
- * GNU General Public License for more details.
17
- *
18
- * You should have received a copy of the GNU General Public License
19
- * along with this program.  If not, see <https://www.gnu.org/licenses/>.
20
- *
21
- */
22
-#ifdef __IMXRT1062__
23
-
24
-/**
25
- * HAL Watchdog for Teensy 4.0 (IMXRT1062DVL6A) / 4.1 (IMXRT1062DVJ6A)
26
- */
27
-
28
-#include "../../inc/MarlinConfig.h"
29
-
30
-#if ENABLED(USE_WATCHDOG)
31
-
32
-#include "watchdog.h"
33
-
34
-#define WDT_TIMEOUT TERN(WATCHDOG_DURATION_8S, 8, 4) // 4 or 8 second timeout
35
-
36
-constexpr uint8_t timeoutval = (WDT_TIMEOUT - 0.5f) / 0.5f;
37
-
38
-void watchdog_init() {
39
-  CCM_CCGR3 |= CCM_CCGR3_WDOG1(3);  // enable WDOG1 clocks
40
-  WDOG1_WMCR = 0;                   // disable power down PDE
41
-  WDOG1_WCR |= WDOG_WCR_SRS | WDOG_WCR_WT(timeoutval);
42
-  WDOG1_WCR |= WDOG_WCR_WDE | WDOG_WCR_WDT | WDOG_WCR_SRE;
43
-}
44
-
45
-void HAL_watchdog_refresh() {
46
-  // Watchdog refresh sequence
47
-  WDOG1_WSR = 0x5555;
48
-  WDOG1_WSR = 0xAAAA;
49
-}
50
-
51
-#endif // USE_WATCHDOG
52
-#endif // __IMXRT1062__

+ 0
- 30
Marlin/src/HAL/TEENSY40_41/watchdog.h View File

@@ -1,30 +0,0 @@
1
-/**
2
- * Marlin 3D Printer Firmware
3
- * Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
4
- *
5
- * Based on Sprinter and grbl.
6
- * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm
7
- *
8
- * This program is free software: you can redistribute it and/or modify
9
- * it under the terms of the GNU General Public License as published by
10
- * the Free Software Foundation, either version 3 of the License, or
11
- * (at your option) any later version.
12
- *
13
- * This program is distributed in the hope that it will be useful,
14
- * but WITHOUT ANY WARRANTY; without even the implied warranty of
15
- * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the
16
- * GNU General Public License for more details.
17
- *
18
- * You should have received a copy of the GNU General Public License
19
- * along with this program.  If not, see <https://www.gnu.org/licenses/>.
20
- *
21
- */
22
-#pragma once
23
-
24
-/**
25
- * HAL Watchdog for Teensy 4.0 (IMXRT1062DVL6A) / 4.1 (IMXRT1062DVJ6A)
26
- */
27
-
28
-void watchdog_init();
29
-
30
-void HAL_watchdog_refresh();

+ 4
- 4
Marlin/src/MarlinCore.cpp View File

@@ -934,18 +934,18 @@ void minkill(const bool steppers_off/*=false*/) {
934 934
 
935 935
     // Wait for both KILL and ENC to be released
936 936
     while (TERN0(HAS_KILL, kill_state()) || TERN0(SOFT_RESET_ON_KILL, ui.button_pressed()))
937
-      watchdog_refresh();
937
+      hal.watchdog_refresh();
938 938
 
939 939
     // Wait for either KILL or ENC to be pressed again
940 940
     while (TERN1(HAS_KILL, !kill_state()) && TERN1(SOFT_RESET_ON_KILL, !ui.button_pressed()))
941
-      watchdog_refresh();
941
+      hal.watchdog_refresh();
942 942
 
943 943
     // Reboot the board
944 944
     hal.reboot();
945 945
 
946 946
   #else
947 947
 
948
-    for (;;) watchdog_refresh();  // Wait for RESET button or power-cycle
948
+    for (;;) hal.watchdog_refresh();  // Wait for RESET button or power-cycle
949 949
 
950 950
   #endif
951 951
 }
@@ -1561,7 +1561,7 @@ void setup() {
1561 1561
   #endif
1562 1562
 
1563 1563
   #if ENABLED(USE_WATCHDOG)
1564
-    SETUP_RUN(watchdog_init());       // Reinit watchdog after hal.get_reset_source call
1564
+    SETUP_RUN(hal.watchdog_init());   // Reinit watchdog after hal.get_reset_source call
1565 1565
   #endif
1566 1566
 
1567 1567
   #if ENABLED(EXTERNAL_CLOSED_LOOP_CONTROLLER)

+ 5
- 5
Marlin/src/gcode/config/M43.cpp View File

@@ -69,7 +69,7 @@ inline void toggle_pins() {
69 69
       SERIAL_EOL();
70 70
     }
71 71
     else {
72
-      watchdog_refresh();
72
+      hal.watchdog_refresh();
73 73
       report_pin_state_extended(pin, ignore_protection, true, F("Pulsing   "));
74 74
       #ifdef __STM32F1__
75 75
         const auto prior_mode = _GET_MODE(i);
@@ -98,10 +98,10 @@ inline void toggle_pins() {
98 98
       {
99 99
         pinMode(pin, OUTPUT);
100 100
         for (int16_t j = 0; j < repeat; j++) {
101
-          watchdog_refresh(); extDigitalWrite(pin, 0); safe_delay(wait);
102
-          watchdog_refresh(); extDigitalWrite(pin, 1); safe_delay(wait);
103
-          watchdog_refresh(); extDigitalWrite(pin, 0); safe_delay(wait);
104
-          watchdog_refresh();
101
+          hal.watchdog_refresh(); extDigitalWrite(pin, 0); safe_delay(wait);
102
+          hal.watchdog_refresh(); extDigitalWrite(pin, 1); safe_delay(wait);
103
+          hal.watchdog_refresh(); extDigitalWrite(pin, 0); safe_delay(wait);
104
+          hal.watchdog_refresh();
105 105
         }
106 106
       }
107 107
       #ifdef __STM32F1__

+ 0
- 1
Marlin/src/gcode/feature/L6470/M916-M918.cpp View File

@@ -309,7 +309,6 @@ void GcodeSuite::M917() {
309 309
         }
310 310
         DEBUG_ECHOLNPGM(".");
311 311
         reset_stepper_timeout(); // keep steppers powered
312
-        watchdog_refresh();
313 312
         safe_delay(5000);
314 313
         status_composite_temp = 0;
315 314
         for (j = 0; j < driver_count; j++) {

+ 2
- 2
Marlin/src/gcode/gcode_d.cpp View File

@@ -214,7 +214,7 @@ void GcodeSuite::D(const int16_t dcode) {
214 214
 
215 215
         c = 1024 * 4;
216 216
         while (c--) {
217
-          TERN_(USE_WATCHDOG, watchdog_refresh());
217
+          hal.watchdog_refresh();
218 218
           card.write(buf, COUNT(buf));
219 219
         }
220 220
         SERIAL_ECHOLNPGM(" done");
@@ -231,7 +231,7 @@ void GcodeSuite::D(const int16_t dcode) {
231 231
         __attribute__((aligned(sizeof(size_t)))) uint8_t buf[512];
232 232
         uint16_t c = 1024 * 4;
233 233
         while (c--) {
234
-          TERN_(USE_WATCHDOG, watchdog_refresh());
234
+          hal.watchdog_refresh();
235 235
           card.read(buf, COUNT(buf));
236 236
           bool error = false;
237 237
           for (uint16_t i = 0; i < COUNT(buf); i++) {

+ 1
- 1
Marlin/src/lcd/e3v2/proui/meshviewer.cpp View File

@@ -74,7 +74,7 @@ void MeshViewerClass::DrawMesh(bed_mesh_t zval, const uint8_t sizex, const uint8
74 74
   LOOP_S_L_N(x, 1, sizex - 1) DrawMeshVLine(x);
75 75
   LOOP_S_L_N(y, 1, sizey - 1) DrawMeshHLine(y);
76 76
   LOOP_L_N(y, sizey) {
77
-    watchdog_refresh();
77
+    hal.watchdog_refresh();
78 78
     LOOP_L_N(x, sizex) {
79 79
       uint16_t color = DWINUI::RainbowInt(zmesh[x][y], _MIN(-5, minz), _MAX(5, maxz));
80 80
       uint8_t radius = rm(zmesh[x][y]);

+ 1
- 1
Marlin/src/lcd/extui/mks_ui/draw_print_file.cpp View File

@@ -402,7 +402,7 @@ void lv_gcode_file_read(uint8_t *data_buf) {
402 402
     char temp_test[200];
403 403
     volatile uint16_t *p_index;
404 404
 
405
-    watchdog_refresh();
405
+    hal.watchdog_refresh();
406 406
     memset(public_buf, 0, 200);
407 407
 
408 408
     while (card.isFileOpen()) {

+ 2
- 2
Marlin/src/lcd/extui/mks_ui/draw_z_offset_wizard.cpp View File

@@ -104,7 +104,7 @@ static void event_handler(lv_obj_t *obj, lv_event_t event) {
104 104
       sync_plan_position();
105 105
       // Raise Z as if it was homed
106 106
       do_z_clearance(Z_POST_CLEARANCE);
107
-      watchdog_refresh();
107
+      hal.watchdog_refresh();
108 108
       draw_return_ui();
109 109
       return;
110 110
     case ID_M_RETURN:
@@ -117,7 +117,7 @@ static void event_handler(lv_obj_t *obj, lv_event_t event) {
117 117
       #else // Otherwise do a Z clearance move like after Homing
118 118
         do_z_clearance(Z_POST_CLEARANCE);
119 119
       #endif
120
-      watchdog_refresh();
120
+      hal.watchdog_refresh();
121 121
       draw_return_ui();
122 122
       return;
123 123
   }

+ 11
- 11
Marlin/src/lcd/extui/mks_ui/pic_manager.cpp View File

@@ -267,12 +267,12 @@ void spiFlashErase_PIC() {
267 267
   W25QXX.init(SPI_QUARTER_SPEED);
268 268
   // erase 0x001000 -64K
269 269
   for (pic_sectorcnt = 0; pic_sectorcnt < (64 - 4) / 4; pic_sectorcnt++) {
270
-    watchdog_refresh();
270
+    hal.watchdog_refresh();
271 271
     W25QXX.SPI_FLASH_SectorErase(PICINFOADDR + pic_sectorcnt * 4 * 1024);
272 272
   }
273 273
   // erase 64K -- 6M
274 274
   for (pic_sectorcnt = 0; pic_sectorcnt < (PIC_SIZE_xM * 1024 / 64 - 1); pic_sectorcnt++) {
275
-    watchdog_refresh();
275
+    hal.watchdog_refresh();
276 276
     W25QXX.SPI_FLASH_BlockErase((pic_sectorcnt + 1) * 64 * 1024);
277 277
   }
278 278
 }
@@ -282,7 +282,7 @@ void spiFlashErase_PIC() {
282 282
     volatile uint32_t Font_sectorcnt = 0;
283 283
     W25QXX.init(SPI_QUARTER_SPEED);
284 284
     for (Font_sectorcnt = 0; Font_sectorcnt < 32 - 1; Font_sectorcnt++) {
285
-      watchdog_refresh();
285
+      hal.watchdog_refresh();
286 286
       W25QXX.SPI_FLASH_BlockErase(FONTINFOADDR + Font_sectorcnt * 64 * 1024);
287 287
     }
288 288
   }
@@ -414,7 +414,7 @@ uint32_t Pic_Info_Write(uint8_t *P_name, uint32_t P_size) {
414 414
       return;
415 415
     }
416 416
 
417
-    watchdog_refresh();
417
+    hal.watchdog_refresh();
418 418
     disp_assets_update_progress(fn);
419 419
 
420 420
     W25QXX.init(SPI_QUARTER_SPEED);
@@ -427,21 +427,21 @@ uint32_t Pic_Info_Write(uint8_t *P_name, uint32_t P_size) {
427 427
     totalSizeLoaded += pfileSize;
428 428
     if (assetType == ASSET_TYPE_LOGO) {
429 429
       do {
430
-        watchdog_refresh();
430
+        hal.watchdog_refresh();
431 431
         pbr = file.read(public_buf, BMP_WRITE_BUF_LEN);
432 432
         Pic_Logo_Write((uint8_t*)fn, public_buf, pbr);
433 433
       } while (pbr >= BMP_WRITE_BUF_LEN);
434 434
     }
435 435
     else if (assetType == ASSET_TYPE_TITLE_LOGO) {
436 436
       do {
437
-        watchdog_refresh();
437
+        hal.watchdog_refresh();
438 438
         pbr = file.read(public_buf, BMP_WRITE_BUF_LEN);
439 439
         Pic_TitleLogo_Write((uint8_t*)fn, public_buf, pbr);
440 440
       } while (pbr >= BMP_WRITE_BUF_LEN);
441 441
     }
442 442
     else if (assetType == ASSET_TYPE_G_PREVIEW) {
443 443
       do {
444
-        watchdog_refresh();
444
+        hal.watchdog_refresh();
445 445
         pbr = file.read(public_buf, BMP_WRITE_BUF_LEN);
446 446
         default_view_Write(public_buf, pbr);
447 447
       } while (pbr >= BMP_WRITE_BUF_LEN);
@@ -451,7 +451,7 @@ uint32_t Pic_Info_Write(uint8_t *P_name, uint32_t P_size) {
451 451
       SPIFlash.beginWrite(Pic_Write_Addr);
452 452
       #if HAS_SPI_FLASH_COMPRESSION
453 453
         do {
454
-          watchdog_refresh();
454
+          hal.watchdog_refresh();
455 455
           pbr = file.read(public_buf, SPI_FLASH_PageSize);
456 456
           TERN_(MARLIN_DEV_MODE, totalSizes += pbr);
457 457
           SPIFlash.writeData(public_buf, SPI_FLASH_PageSize);
@@ -472,7 +472,7 @@ uint32_t Pic_Info_Write(uint8_t *P_name, uint32_t P_size) {
472 472
     else if (assetType == ASSET_TYPE_FONT) {
473 473
       Pic_Write_Addr = UNIGBK_FLASH_ADDR;
474 474
       do {
475
-        watchdog_refresh();
475
+        hal.watchdog_refresh();
476 476
         pbr = file.read(public_buf, BMP_WRITE_BUF_LEN);
477 477
         W25QXX.SPI_FLASH_BufferWrite(public_buf, Pic_Write_Addr, pbr);
478 478
         Pic_Write_Addr += pbr;
@@ -493,11 +493,11 @@ uint32_t Pic_Info_Write(uint8_t *P_name, uint32_t P_size) {
493 493
 
494 494
       disp_assets_update();
495 495
       disp_assets_update_progress(F("Erasing pics..."));
496
-      watchdog_refresh();
496
+      hal.watchdog_refresh();
497 497
       spiFlashErase_PIC();
498 498
       #if HAS_SPI_FLASH_FONT
499 499
         disp_assets_update_progress(F("Erasing fonts..."));
500
-        watchdog_refresh();
500
+        hal.watchdog_refresh();
501 501
         spiFlashErase_FONT();
502 502
       #endif
503 503
 

+ 6
- 6
Marlin/src/lcd/extui/mks_ui/tft_lvgl_configuration.cpp View File

@@ -125,13 +125,13 @@ void tft_lvgl_init() {
125 125
   ui_cfg_init();
126 126
   disp_language_init();
127 127
 
128
-  watchdog_refresh();     // LVGL init takes time
128
+  hal.watchdog_refresh();     // LVGL init takes time
129 129
 
130 130
   // Init TFT first!
131 131
   SPI_TFT.spi_init(SPI_FULL_SPEED);
132 132
   SPI_TFT.LCD_init();
133 133
 
134
-  watchdog_refresh();     // LVGL init takes time
134
+  hal.watchdog_refresh();     // LVGL init takes time
135 135
 
136 136
   #if ENABLED(USB_FLASH_DRIVE_SUPPORT)
137 137
     uint16_t usb_flash_loop = 1000;
@@ -142,21 +142,21 @@ void tft_lvgl_init() {
142 142
     #endif
143 143
     do {
144 144
       card.media_driver_usbFlash.idle();
145
-      watchdog_refresh();
145
+      hal.watchdog_refresh();
146 146
       delay(2);
147 147
     } while (!card.media_driver_usbFlash.isInserted() && usb_flash_loop--);
148 148
     card.mount();
149 149
   #elif HAS_LOGO_IN_FLASH
150 150
     delay(1000);
151
-    watchdog_refresh();
151
+    hal.watchdog_refresh();
152 152
     delay(1000);
153 153
   #endif
154 154
 
155
-  watchdog_refresh();     // LVGL init takes time
155
+  hal.watchdog_refresh();     // LVGL init takes time
156 156
 
157 157
   #if ENABLED(SDSUPPORT)
158 158
     UpdateAssets();
159
-    watchdog_refresh();   // LVGL init takes time
159
+    hal.watchdog_refresh();   // LVGL init takes time
160 160
     TERN_(MKS_TEST, mks_test_get());
161 161
   #endif
162 162
 

+ 6
- 6
Marlin/src/lcd/extui/mks_ui/wifi_module.cpp View File

@@ -123,7 +123,7 @@ uint32_t getWifiTickDiff(int32_t lastTick, int32_t curTick) {
123 123
 void wifi_delay(int n) {
124 124
   const uint32_t start = getWifiTick();
125 125
   while (getWifiTickDiff(start, getWifiTick()) < (uint32_t)n)
126
-    watchdog_refresh();
126
+    hal.watchdog_refresh();
127 127
 }
128 128
 
129 129
 void wifi_reset() {
@@ -1882,7 +1882,7 @@ void wifi_rcv_handle() {
1882 1882
 void wifi_looping() {
1883 1883
   do {
1884 1884
     wifi_rcv_handle();
1885
-    watchdog_refresh();
1885
+    hal.watchdog_refresh();
1886 1886
   } while (wifi_link_state == WIFI_TRANS_FILE);
1887 1887
 }
1888 1888
 
@@ -1897,7 +1897,7 @@ void mks_esp_wifi_init() {
1897 1897
 
1898 1898
   esp_state = TRANSFER_IDLE;
1899 1899
   esp_port_begin(1);
1900
-  watchdog_refresh();
1900
+  hal.watchdog_refresh();
1901 1901
   wifi_reset();
1902 1902
 
1903 1903
   #if 0
@@ -1950,14 +1950,14 @@ void mks_esp_wifi_init() {
1950 1950
 }
1951 1951
 
1952 1952
 void mks_wifi_firmware_update() {
1953
-  watchdog_refresh();
1953
+  hal.watchdog_refresh();
1954 1954
   card.openFileRead((char *)ESP_FIRMWARE_FILE);
1955 1955
 
1956 1956
   if (card.isFileOpen()) {
1957 1957
     card.closefile();
1958 1958
 
1959 1959
     wifi_delay(2000);
1960
-    watchdog_refresh();
1960
+    hal.watchdog_refresh();
1961 1961
     if (usartFifoAvailable((SZ_USART_FIFO *)&WifiRxFifo) < 20) return;
1962 1962
 
1963 1963
     clear_cur_ui();
@@ -1965,7 +1965,7 @@ void mks_wifi_firmware_update() {
1965 1965
     lv_draw_dialog(DIALOG_TYPE_UPDATE_ESP_FIRMWARE);
1966 1966
 
1967 1967
     lv_task_handler();
1968
-    watchdog_refresh();
1968
+    hal.watchdog_refresh();
1969 1969
 
1970 1970
     if (wifi_upload(0) >= 0) {
1971 1971
       card.removeFile((char *)ESP_FIRMWARE_FILE_RENAME);

+ 3
- 3
Marlin/src/lcd/extui/mks_ui/wifi_upload.cpp View File

@@ -265,7 +265,7 @@ EspUploadResult readPacket(uint8_t op, uint32_t *valp, size_t *bodyLen, uint32_t
265 265
     EspUploadResult stat;
266 266
 
267 267
     //IWDG_ReloadCounter();
268
-    watchdog_refresh();
268
+    hal.watchdog_refresh();
269 269
 
270 270
     if (getWifiTickDiff(startTime, getWifiTick()) > msTimeout)
271 271
       return timeout;
@@ -445,7 +445,7 @@ EspUploadResult Sync(uint16_t timeout) {
445 445
     for (;;) {
446 446
       size_t bodyLen;
447 447
       EspUploadResult rc = readPacket(ESP_SYNC, 0, &bodyLen, defaultTimeout);
448
-      watchdog_refresh();
448
+      hal.watchdog_refresh();
449 449
       if (rc != success || bodyLen != 2) break;
450 450
     }
451 451
   }
@@ -673,7 +673,7 @@ int32_t wifi_upload(int type) {
673 673
 
674 674
   while (esp_upload.state != upload_idle) {
675 675
     upload_spin();
676
-    watchdog_refresh();
676
+    hal.watchdog_refresh();
677 677
   }
678 678
 
679 679
   ResetWiFiForUpload(1);

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

@@ -1226,10 +1226,10 @@ inline void loud_kill(FSTR_P const lcd_msg, const heater_id_t heater_id) {
1226 1226
   thermalManager.disable_all_heaters();
1227 1227
   #if HAS_BEEPER
1228 1228
     for (uint8_t i = 20; i--;) {
1229
-      watchdog_refresh();
1229
+      hal.watchdog_refresh();
1230 1230
       buzzer.click(25);
1231 1231
       delay(80);
1232
-      watchdog_refresh();
1232
+      hal.watchdog_refresh();
1233 1233
     }
1234 1234
     buzzer.on();
1235 1235
   #endif
@@ -1274,7 +1274,7 @@ void Temperature::_temp_error(const heater_id_t heater_id, FSTR_P const serial_m
1274 1274
   }
1275 1275
 
1276 1276
   disable_all_heaters(); // always disable (even for bogus temp)
1277
-  watchdog_refresh();
1277
+  hal.watchdog_refresh();
1278 1278
 
1279 1279
   #if BOGUS_TEMPERATURE_GRACE_PERIOD
1280 1280
     const millis_t ms = millis();
@@ -1638,7 +1638,7 @@ void Temperature::min_temp_error(const heater_id_t heater_id) {
1638 1638
  *  - Update the heated bed PID output value
1639 1639
  */
1640 1640
 void Temperature::manage_heater() {
1641
-  if (marlin_state == MF_INITIALIZING) return watchdog_refresh(); // If Marlin isn't started, at least reset the watchdog!
1641
+  if (marlin_state == MF_INITIALIZING) return hal.watchdog_refresh(); // If Marlin isn't started, at least reset the watchdog!
1642 1642
 
1643 1643
   static bool no_reentry = false;  // Prevent recursion
1644 1644
   if (no_reentry) return;
@@ -2387,7 +2387,7 @@ void Temperature::manage_heater() {
2387 2387
  */
2388 2388
 void Temperature::updateTemperaturesFromRawValues() {
2389 2389
 
2390
-  watchdog_refresh(); // Reset because raw_temps_ready was set by the interrupt
2390
+  hal.watchdog_refresh(); // Reset because raw_temps_ready was set by the interrupt
2391 2391
 
2392 2392
   TERN_(TEMP_SENSOR_0_IS_MAX_TC, temp_hotend[0].setraw(READ_MAX_TC(0)));
2393 2393
   TERN_(TEMP_SENSOR_1_IS_MAX_TC, temp_hotend[1].setraw(READ_MAX_TC(1)));

+ 4
- 4
Marlin/src/sd/Sd2Card.cpp View File

@@ -249,7 +249,7 @@ bool DiskIODriver_SPI_SD::init(const uint8_t sckRateID, const pin_t chipSelectPi
249 249
   const millis_t init_timeout = millis() + SD_INIT_TIMEOUT;
250 250
   uint32_t arg;
251 251
 
252
-  watchdog_refresh(); // In case init takes too long
252
+  hal.watchdog_refresh(); // In case init takes too long
253 253
 
254 254
   // Set pin modes
255 255
   #if ENABLED(ZONESTAR_12864OLED)
@@ -270,7 +270,7 @@ bool DiskIODriver_SPI_SD::init(const uint8_t sckRateID, const pin_t chipSelectPi
270 270
   // Must supply min of 74 clock cycles with CS high.
271 271
   LOOP_L_N(i, 10) spiSend(0xFF);
272 272
 
273
-  watchdog_refresh(); // In case init takes too long
273
+  hal.watchdog_refresh(); // In case init takes too long
274 274
 
275 275
   // Command to go idle in SPI mode
276 276
   while ((status_ = cardCommand(CMD0, 0)) != R1_IDLE_STATE) {
@@ -284,7 +284,7 @@ bool DiskIODriver_SPI_SD::init(const uint8_t sckRateID, const pin_t chipSelectPi
284 284
     crcSupported = (cardCommand(CMD59, 1) == R1_IDLE_STATE);
285 285
   #endif
286 286
 
287
-  watchdog_refresh(); // In case init takes too long
287
+  hal.watchdog_refresh(); // In case init takes too long
288 288
 
289 289
   // check SD version
290 290
   for (;;) {
@@ -306,7 +306,7 @@ bool DiskIODriver_SPI_SD::init(const uint8_t sckRateID, const pin_t chipSelectPi
306 306
     }
307 307
   }
308 308
 
309
-  watchdog_refresh(); // In case init takes too long
309
+  hal.watchdog_refresh(); // In case init takes too long
310 310
 
311 311
   // Initialize card and send host supports SDHC if SD2
312 312
   arg = type() == SD_CARD_TYPE_SD2 ? 0x40000000 : 0;

Loading…
Cancel
Save