Browse Source

⏪️ Refactor still needs work

Reverting #23295
Scott Lahteine 3 years ago
parent
commit
6a8b9274a3
69 changed files with 1279 additions and 1749 deletions
  1. 7
    7
      Marlin/src/HAL/AVR/HAL.cpp
  2. 67
    105
      Marlin/src/HAL/AVR/HAL.h
  3. 2
    2
      Marlin/src/HAL/AVR/MarlinSerial.cpp
  4. 6
    5
      Marlin/src/HAL/AVR/fast_pwm.cpp
  5. 2
    2
      Marlin/src/HAL/AVR/timers.h
  6. 34
    11
      Marlin/src/HAL/DUE/HAL.cpp
  7. 47
    87
      Marlin/src/HAL/DUE/HAL.h
  8. 2
    2
      Marlin/src/HAL/DUE/MarlinSerial.cpp
  9. 1
    1
      Marlin/src/HAL/DUE/timers.h
  10. 18
    17
      Marlin/src/HAL/ESP32/HAL.cpp
  11. 57
    88
      Marlin/src/HAL/ESP32/HAL.h
  12. 2
    2
      Marlin/src/HAL/ESP32/timers.h
  13. 27
    12
      Marlin/src/HAL/LINUX/HAL.cpp
  14. 49
    95
      Marlin/src/HAL/LINUX/HAL.h
  15. 3
    1
      Marlin/src/HAL/LINUX/arduino.cpp
  16. 3
    2
      Marlin/src/HAL/LINUX/include/Arduino.h
  17. 2
    2
      Marlin/src/HAL/LINUX/timers.h
  18. 22
    20
      Marlin/src/HAL/LPC1768/HAL.cpp
  19. 59
    101
      Marlin/src/HAL/LPC1768/HAL.h
  20. 1
    2
      Marlin/src/HAL/LPC1768/Servo.h
  21. 9
    5
      Marlin/src/HAL/LPC1768/fast_pwm.cpp
  22. 3
    3
      Marlin/src/HAL/LPC1768/main.cpp
  23. 1
    1
      Marlin/src/HAL/LPC1768/timers.h
  24. 65
    107
      Marlin/src/HAL/NATIVE_SIM/HAL.h
  25. 2
    2
      Marlin/src/HAL/NATIVE_SIM/timers.h
  26. 17
    9
      Marlin/src/HAL/SAMD51/HAL.cpp
  27. 46
    81
      Marlin/src/HAL/SAMD51/HAL.h
  28. 18
    10
      Marlin/src/HAL/STM32/HAL.cpp
  29. 76
    101
      Marlin/src/HAL/STM32/HAL.h
  30. 4
    4
      Marlin/src/HAL/STM32/HAL_SPI.cpp
  31. 4
    4
      Marlin/src/HAL/STM32/eeprom_flash.cpp
  32. 2
    2
      Marlin/src/HAL/STM32/fast_pwm.cpp
  33. 1
    5
      Marlin/src/HAL/STM32/pinsDebug.h
  34. 2
    2
      Marlin/src/HAL/STM32/timers.h
  35. 99
    91
      Marlin/src/HAL/STM32F1/HAL.cpp
  36. 80
    104
      Marlin/src/HAL/STM32F1/HAL.h
  37. 1
    2
      Marlin/src/HAL/STM32F1/Servo.h
  38. 5
    3
      Marlin/src/HAL/STM32F1/fast_pwm.cpp
  39. 1
    1
      Marlin/src/HAL/STM32F1/timers.h
  40. 38
    41
      Marlin/src/HAL/TEENSY31_32/HAL.cpp
  41. 38
    93
      Marlin/src/HAL/TEENSY31_32/HAL.h
  42. 1
    1
      Marlin/src/HAL/TEENSY31_32/timers.h
  43. 53
    57
      Marlin/src/HAL/TEENSY35_36/HAL.cpp
  44. 39
    94
      Marlin/src/HAL/TEENSY35_36/HAL.h
  45. 1
    1
      Marlin/src/HAL/TEENSY35_36/timers.h
  46. 94
    100
      Marlin/src/HAL/TEENSY40_41/HAL.cpp
  47. 47
    101
      Marlin/src/HAL/TEENSY40_41/HAL.h
  48. 1
    1
      Marlin/src/HAL/TEENSY40_41/timers.h
  49. 0
    36
      Marlin/src/HAL/shared/HAL.cpp
  50. 4
    4
      Marlin/src/HAL/shared/HAL_spi_L6470.cpp
  51. 27
    21
      Marlin/src/MarlinCore.cpp
  52. 1
    1
      Marlin/src/feature/caselight.cpp
  53. 1
    1
      Marlin/src/feature/controllerfan.cpp
  54. 1
    3
      Marlin/src/feature/e_parser.h
  55. 1
    1
      Marlin/src/feature/leds/leds.cpp
  56. 5
    5
      Marlin/src/feature/spindle_laser.cpp
  57. 1
    1
      Marlin/src/feature/spindle_laser.h
  58. 2
    2
      Marlin/src/gcode/control/M42.cpp
  59. 5
    5
      Marlin/src/gcode/gcode_d.cpp
  60. 0
    7
      Marlin/src/inc/SanityCheck.h
  61. 2
    2
      Marlin/src/lcd/dogm/marlinui_DOGM.cpp
  62. 1
    1
      Marlin/src/lcd/e3v2/enhanced/dwin.cpp
  63. 1
    1
      Marlin/src/module/endstops.cpp
  64. 3
    3
      Marlin/src/module/planner.cpp
  65. 1
    1
      Marlin/src/module/servo.cpp
  66. 1
    1
      Marlin/src/module/servo.h
  67. 5
    5
      Marlin/src/module/stepper.cpp
  68. 56
    56
      Marlin/src/module/temperature.cpp
  69. 2
    2
      ini/native.ini

+ 7
- 7
Marlin/src/HAL/AVR/HAL.cpp View File

36
 // ------------------------
36
 // ------------------------
37
 
37
 
38
 // Don't initialize/override variable (which would happen in .init4)
38
 // Don't initialize/override variable (which would happen in .init4)
39
-uint8_t MarlinHAL::reset_reason __attribute__((section(".noinit")));
39
+uint8_t reset_reason __attribute__((section(".noinit")));
40
 
40
 
41
 // ------------------------
41
 // ------------------------
42
 // Public functions
42
 // Public functions
45
 __attribute__((naked))             // Don't output function pro- and epilogue
45
 __attribute__((naked))             // Don't output function pro- and epilogue
46
 __attribute__((used))              // Output the function, even if "not used"
46
 __attribute__((used))              // Output the function, even if "not used"
47
 __attribute__((section(".init3"))) // Put in an early user definable section
47
 __attribute__((section(".init3"))) // Put in an early user definable section
48
-void save_reset_reason() {
48
+void HAL_save_reset_reason() {
49
   #if ENABLED(OPTIBOOT_RESET_REASON)
49
   #if ENABLED(OPTIBOOT_RESET_REASON)
50
     __asm__ __volatile__(
50
     __asm__ __volatile__(
51
       A("STS %0, r2")
51
       A("STS %0, r2")
52
-      : "=m"(hal.reset_reason)
52
+      : "=m"(reset_reason)
53
     );
53
     );
54
   #else
54
   #else
55
-    hal.reset_reason = MCUSR;
55
+    reset_reason = MCUSR;
56
   #endif
56
   #endif
57
 
57
 
58
   // Clear within 16ms since WDRF bit enables a 16ms watchdog timer -> Boot loop
58
   // Clear within 16ms since WDRF bit enables a 16ms watchdog timer -> Boot loop
59
-  hal.clear_reset_source();
59
+  MCUSR = 0;
60
   wdt_disable();
60
   wdt_disable();
61
 }
61
 }
62
 
62
 
63
-void MarlinHAL::init() {
63
+void HAL_init() {
64
   // Init Servo Pins
64
   // Init Servo Pins
65
   #define INIT_SERVO(N) OUT_WRITE(SERVO##N##_PIN, LOW)
65
   #define INIT_SERVO(N) OUT_WRITE(SERVO##N##_PIN, LOW)
66
   #if HAS_SERVO_0
66
   #if HAS_SERVO_0
77
   #endif
77
   #endif
78
 }
78
 }
79
 
79
 
80
-void MarlinHAL::reboot() {
80
+void HAL_reboot() {
81
   #if ENABLED(USE_WATCHDOG)
81
   #if ENABLED(USE_WATCHDOG)
82
     while (1) { /* run out the watchdog */ }
82
     while (1) { /* run out the watchdog */ }
83
   #else
83
   #else

+ 67
- 105
Marlin/src/HAL/AVR/HAL.h View File

74
   #define CRITICAL_SECTION_START()  unsigned char _sreg = SREG; cli()
74
   #define CRITICAL_SECTION_START()  unsigned char _sreg = SREG; cli()
75
   #define CRITICAL_SECTION_END()    SREG = _sreg
75
   #define CRITICAL_SECTION_END()    SREG = _sreg
76
 #endif
76
 #endif
77
-
78
-#define HAL_CAN_SET_PWM_FREQ   // This HAL supports PWM Frequency adjustment
77
+#define ISRS_ENABLED() TEST(SREG, SREG_I)
78
+#define ENABLE_ISRS()  sei()
79
+#define DISABLE_ISRS() cli()
79
 
80
 
80
 // ------------------------
81
 // ------------------------
81
 // Types
82
 // Types
83
 
84
 
84
 typedef int8_t pin_t;
85
 typedef int8_t pin_t;
85
 
86
 
86
-// Use shared/servos.cpp
87
 #define SHARED_SERVOS HAS_SERVOS
87
 #define SHARED_SERVOS HAS_SERVOS
88
-
89
-class Servo;
90
-typedef Servo hal_servo_t;
88
+#define HAL_SERVO_LIB Servo
91
 
89
 
92
 // ------------------------
90
 // ------------------------
93
-// Serial ports
91
+// Public Variables
94
 // ------------------------
92
 // ------------------------
95
 
93
 
94
+extern uint8_t reset_reason;
95
+
96
+// Serial ports
96
 #ifdef USBCON
97
 #ifdef USBCON
97
   #include "../../core/serial_hook.h"
98
   #include "../../core/serial_hook.h"
98
   typedef ForwardSerial1Class< decltype(Serial) > DefaultSerial1;
99
   typedef ForwardSerial1Class< decltype(Serial) > DefaultSerial1;
141
   #endif
142
   #endif
142
 #endif
143
 #endif
143
 
144
 
144
-//
145
-// ADC
146
-//
147
-#define HAL_ADC_VREF        5.0
148
-#define HAL_ADC_RESOLUTION 10
145
+// ------------------------
146
+// Public functions
147
+// ------------------------
149
 
148
 
150
-//
151
-// Pin Mapping for M42, M43, M226
152
-//
153
-#define GET_PIN_MAP_PIN(index) index
154
-#define GET_PIN_MAP_INDEX(pin) pin
155
-#define PARSED_PIN_INDEX(code, dval) parser.intval(code, dval)
149
+void HAL_init();
156
 
150
 
157
-#define HAL_SENSITIVE_PINS 0, 1,
151
+//void cli();
158
 
152
 
159
-#ifdef __AVR_AT90USB1286__
160
-  #define JTAG_DISABLE() do{ MCUCR = 0x80; MCUCR = 0x80; }while(0)
161
-#endif
153
+//void _delay_ms(const int delay);
162
 
154
 
163
-// AVR compatibility
164
-#define strtof strtod
155
+inline void HAL_clear_reset_source() { }
156
+inline uint8_t HAL_get_reset_source() { return reset_reason; }
165
 
157
 
166
-// ------------------------
167
-// Class Utilities
168
-// ------------------------
158
+void HAL_reboot();
169
 
159
 
170
 #pragma GCC diagnostic push
160
 #pragma GCC diagnostic push
171
 #if GCC_VERSION <= 50000
161
 #if GCC_VERSION <= 50000
176
 
166
 
177
 #pragma GCC diagnostic pop
167
 #pragma GCC diagnostic pop
178
 
168
 
179
-// ------------------------
180
-// MarlinHAL Class
181
-// ------------------------
182
-
183
-class MarlinHAL {
184
-public:
169
+// ADC
170
+#ifdef DIDR2
171
+  #define HAL_ANALOG_SELECT(ind) do{ if (ind < 8) SBI(DIDR0, ind); else SBI(DIDR2, ind & 0x07); }while(0)
172
+#else
173
+  #define HAL_ANALOG_SELECT(ind) SBI(DIDR0, ind);
174
+#endif
185
 
175
 
186
-  // Earliest possible init, before setup()
187
-  MarlinHAL() {}
176
+inline void HAL_adc_init() {
177
+  ADCSRA = _BV(ADEN) | _BV(ADSC) | _BV(ADIF) | 0x07;
178
+  DIDR0 = 0;
179
+  #ifdef DIDR2
180
+    DIDR2 = 0;
181
+  #endif
182
+}
188
 
183
 
189
-  static void init();                 // Called early in setup()
190
-  static inline void init_board() {}  // Called less early in setup()
191
-  static void reboot();               // Restart the firmware from 0x0
184
+#define SET_ADMUX_ADCSRA(ch) ADMUX = _BV(REFS0) | (ch & 0x07); SBI(ADCSRA, ADSC)
185
+#ifdef MUX5
186
+  #define HAL_START_ADC(ch) if (ch > 7) ADCSRB = _BV(MUX5); else ADCSRB = 0; SET_ADMUX_ADCSRA(ch)
187
+#else
188
+  #define HAL_START_ADC(ch) ADCSRB = 0; SET_ADMUX_ADCSRA(ch)
189
+#endif
192
 
190
 
193
-  static inline bool isr_state() { return TEST(SREG, SREG_I); }
194
-  static inline void isr_on()  { sei(); }
195
-  static inline void isr_off() { cli(); }
191
+#define HAL_ADC_VREF        5.0
192
+#define HAL_ADC_RESOLUTION 10
193
+#define HAL_READ_ADC()  ADC
194
+#define HAL_ADC_READY() !TEST(ADCSRA, ADSC)
196
 
195
 
197
-  static inline void delay_ms(const int ms) { _delay_ms(ms); }
196
+#define GET_PIN_MAP_PIN(index) index
197
+#define GET_PIN_MAP_INDEX(pin) pin
198
+#define PARSED_PIN_INDEX(code, dval) parser.intval(code, dval)
198
 
199
 
199
-  // Tasks, called from idle()
200
-  static inline void idletask() {}
200
+#define HAL_SENSITIVE_PINS 0, 1,
201
 
201
 
202
-  // Reset
203
-  static uint8_t reset_reason;
204
-  static inline uint8_t get_reset_source() { return reset_reason; }
205
-  static inline void clear_reset_source() { MCUSR = 0; }
202
+#ifdef __AVR_AT90USB1286__
203
+  #define JTAG_DISABLE() do{ MCUCR = 0x80; MCUCR = 0x80; }while(0)
204
+#endif
206
 
205
 
207
-  // Free SRAM
208
-  static inline int freeMemory() { return ::freeMemory(); }
206
+// AVR compatibility
207
+#define strtof strtod
209
 
208
 
210
-  //
211
-  // ADC Methods
212
-  //
209
+#define HAL_CAN_SET_PWM_FREQ   // This HAL supports PWM Frequency adjustment
213
 
210
 
214
-  // Called by Temperature::init once at startup
215
-  static inline void adc_init() {
216
-    ADCSRA = _BV(ADEN) | _BV(ADSC) | _BV(ADIF) | 0x07;
217
-    DIDR0 = 0;
218
-    #ifdef DIDR2
219
-      DIDR2 = 0;
220
-    #endif
221
-  }
211
+/**
212
+ *  set_pwm_frequency
213
+ *  Sets the frequency of the timer corresponding to the provided pin
214
+ *  as close as possible to the provided desired frequency. Internally
215
+ *  calculates the required waveform generation mode, prescaler and
216
+ *  resolution values required and sets the timer registers accordingly.
217
+ *  NOTE that the frequency is applied to all pins on the timer (Ex OC3A, OC3B and OC3B)
218
+ *  NOTE that there are limitations, particularly if using TIMER2. (see Configuration_adv.h -> FAST FAN PWM Settings)
219
+ */
220
+void set_pwm_frequency(const pin_t pin, int f_desired);
222
 
221
 
223
-  // Called by Temperature::init for each sensor at startup
224
-  static inline void adc_enable(const uint8_t ch) {
225
-    #ifdef DIDR2
226
-      if (ch > 7) { SBI(DIDR2, ch & 0x07); return; }
227
-    #endif
228
-    SBI(DIDR0, ch);
229
-  }
230
-
231
-  // Begin ADC sampling on the given channel
232
-  static inline void adc_start(const uint8_t ch) {
233
-    #ifdef MUX5
234
-      ADCSRB = ch > 7 ? _BV(MUX5) : 0;
235
-    #else
236
-      ADCSRB = 0;
237
-    #endif
238
-    ADMUX = _BV(REFS0) | (ch & 0x07);
239
-    SBI(ADCSRA, ADSC);
240
-  }
241
-
242
-  // Is the ADC ready for reading?
243
-  static inline bool adc_ready() { return !TEST(ADCSRA, ADSC); }
244
-
245
-  // The current value of the ADC register
246
-  static inline __typeof__(ADC) adc_value() { return ADC; }
247
-
248
-  /**
249
-   * Set the PWM duty cycle for the pin to the given value.
250
-   * Optionally invert the duty cycle [default = false]
251
-   * Optionally change the scale of the provided value to enable finer PWM duty control [default = 255]
252
-   */
253
-  static void set_pwm_duty(const pin_t pin, const uint16_t v, const uint16_t v_size=255, const bool invert=false);
254
-
255
-  /**
256
-   * Set the frequency of the timer for the given pin as close as
257
-   * possible to the provided desired frequency. Internally calculate
258
-   * the required waveform generation mode, prescaler, and resolution
259
-   * values and set timer registers accordingly.
260
-   * NOTE that the frequency is applied to all pins on the timer (Ex OC3A, OC3B and OC3B)
261
-   * NOTE that there are limitations, particularly if using TIMER2. (see Configuration_adv.h -> FAST FAN PWM Settings)
262
-   */
263
-  static void set_pwm_frequency(const pin_t pin, int f_desired);
264
-};
265
-
266
-extern MarlinHAL hal;
222
+/**
223
+ * set_pwm_duty
224
+ *  Set the PWM duty cycle of the provided pin to the provided value
225
+ *  Optionally allows inverting the duty cycle [default = false]
226
+ *  Optionally allows changing the maximum size of the provided value to enable finer PWM duty control [default = 255]
227
+ */
228
+void set_pwm_duty(const pin_t pin, const uint16_t v, const uint16_t v_size=255, const bool invert=false);

+ 2
- 2
Marlin/src/HAL/AVR/MarlinSerial.cpp View File

486
     const uint8_t i = (tx_buffer.head + 1) & (Cfg::TX_SIZE - 1);
486
     const uint8_t i = (tx_buffer.head + 1) & (Cfg::TX_SIZE - 1);
487
 
487
 
488
     // If global interrupts are disabled (as the result of being called from an ISR)...
488
     // If global interrupts are disabled (as the result of being called from an ISR)...
489
-    if (!hal.isr_state()) {
489
+    if (!ISRS_ENABLED()) {
490
 
490
 
491
       // Make room by polling if it is possible to transmit, and do so!
491
       // Make room by polling if it is possible to transmit, and do so!
492
       while (i == tx_buffer.tail) {
492
       while (i == tx_buffer.tail) {
534
     if (!_written) return;
534
     if (!_written) return;
535
 
535
 
536
     // If global interrupts are disabled (as the result of being called from an ISR)...
536
     // If global interrupts are disabled (as the result of being called from an ISR)...
537
-    if (!hal.isr_state()) {
537
+    if (!ISRS_ENABLED()) {
538
 
538
 
539
       // Wait until everything was transmitted - We must do polling, as interrupts are disabled
539
       // Wait until everything was transmitted - We must do polling, as interrupts are disabled
540
       while (tx_buffer.head != tx_buffer.tail || !B_TXC) {
540
       while (tx_buffer.head != tx_buffer.tail || !B_TXC) {

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

35
 };
35
 };
36
 
36
 
37
 /**
37
 /**
38
- * Get the timer information and register for a pin.
39
- * Return a Timer struct containing this information.
40
- * Used by set_pwm_frequency, set_pwm_duty
38
+ * get_pwm_timer
39
+ *  Get the timer information and register of the provided pin.
40
+ *  Return a Timer struct containing this information.
41
+ *  Used by set_pwm_frequency, set_pwm_duty
41
  */
42
  */
42
 Timer get_pwm_timer(const pin_t pin) {
43
 Timer get_pwm_timer(const pin_t pin) {
43
   uint8_t q = 0;
44
   uint8_t q = 0;
149
   return timer;
150
   return timer;
150
 }
151
 }
151
 
152
 
152
-void MarlinHAL::set_pwm_frequency(const pin_t pin, int f_desired) {
153
+void set_pwm_frequency(const pin_t pin, int f_desired) {
153
   Timer timer = get_pwm_timer(pin);
154
   Timer timer = get_pwm_timer(pin);
154
   if (timer.n == 0) return; // Don't proceed if protected timer or not recognized
155
   if (timer.n == 0) return; // Don't proceed if protected timer or not recognized
155
   uint16_t size;
156
   uint16_t size;
229
 
230
 
230
 #endif // NEEDS_HARDWARE_PWM
231
 #endif // NEEDS_HARDWARE_PWM
231
 
232
 
232
-void MarlinHAL::set_pwm_duty(const pin_t pin, const uint16_t v, const uint16_t v_size/*=255*/, const bool invert/*=false*/) {
233
+void set_pwm_duty(const pin_t pin, const uint16_t v, const uint16_t v_size/*=255*/, const bool invert/*=false*/) {
233
   #if NEEDS_HARDWARE_PWM
234
   #if NEEDS_HARDWARE_PWM
234
 
235
 
235
     // If v is 0 or v_size (max), digitalWrite to LOW or HIGH.
236
     // If v is 0 or v_size (max), digitalWrite to LOW or HIGH.

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

109
  * (otherwise, characters will be lost due to UART overflow).
109
  * (otherwise, characters will be lost due to UART overflow).
110
  * Then: Stepper, Endstops, Temperature, and -finally- all others.
110
  * Then: Stepper, Endstops, Temperature, and -finally- all others.
111
  */
111
  */
112
-#define HAL_timer_isr_prologue(T) NOOP
113
-#define HAL_timer_isr_epilogue(T) NOOP
112
+#define HAL_timer_isr_prologue(T)
113
+#define HAL_timer_isr_epilogue(T)
114
 
114
 
115
 /* 18 cycles maximum latency */
115
 /* 18 cycles maximum latency */
116
 #ifndef HAL_STEP_TIMER_ISR
116
 #ifndef HAL_STEP_TIMER_ISR

+ 34
- 11
Marlin/src/HAL/DUE/HAL.cpp View File

34
 // Public Variables
34
 // Public Variables
35
 // ------------------------
35
 // ------------------------
36
 
36
 
37
-uint16_t MarlinHAL::adc_result;
37
+uint16_t HAL_adc_result;
38
 
38
 
39
 // ------------------------
39
 // ------------------------
40
 // Public functions
40
 // Public functions
42
 
42
 
43
 TERN_(POSTMORTEM_DEBUGGING, extern void install_min_serial());
43
 TERN_(POSTMORTEM_DEBUGGING, extern void install_min_serial());
44
 
44
 
45
-void MarlinHAL::init() {
45
+// HAL initialization task
46
+void HAL_init() {
46
   // Initialize the USB stack
47
   // Initialize the USB stack
47
   #if ENABLED(SDSUPPORT)
48
   #if ENABLED(SDSUPPORT)
48
     OUT_WRITE(SDSS, HIGH);  // Try to set SDSS inactive before any other SPI users start up
49
     OUT_WRITE(SDSS, HIGH);  // Try to set SDSS inactive before any other SPI users start up
51
   TERN_(POSTMORTEM_DEBUGGING, install_min_serial()); // Install the min serial handler
52
   TERN_(POSTMORTEM_DEBUGGING, install_min_serial()); // Install the min serial handler
52
 }
53
 }
53
 
54
 
54
-void MarlinHAL::init_board() {
55
-  #ifdef BOARD_INIT
56
-    BOARD_INIT();
57
-  #endif
55
+// HAL idle task
56
+void HAL_idletask() {
57
+  // Perform USB stack housekeeping
58
+  usb_task_idle();
58
 }
59
 }
59
 
60
 
60
-void MarlinHAL::idletask() {
61
-  usb_task_idle();    // Perform USB stack housekeeping
62
-}
61
+// Disable interrupts
62
+void cli() { noInterrupts(); }
63
+
64
+// Enable interrupts
65
+void sei() { interrupts(); }
66
+
67
+void HAL_clear_reset_source() { }
63
 
68
 
64
-uint8_t MarlinHAL::get_reset_source() {
69
+uint8_t HAL_get_reset_source() {
65
   switch ((RSTC->RSTC_SR >> 8) & 0x07) {
70
   switch ((RSTC->RSTC_SR >> 8) & 0x07) {
66
     case 0: return RST_POWER_ON;
71
     case 0: return RST_POWER_ON;
67
     case 1: return RST_BACKUP;
72
     case 1: return RST_BACKUP;
72
   }
77
   }
73
 }
78
 }
74
 
79
 
75
-void MarlinHAL::reboot() { rstc_start_software_reset(RSTC); }
80
+void HAL_reboot() { rstc_start_software_reset(RSTC); }
81
+
82
+void _delay_ms(const int delay_ms) {
83
+  // Todo: port for Due?
84
+  delay(delay_ms);
85
+}
76
 
86
 
77
 extern "C" {
87
 extern "C" {
78
   extern unsigned int _ebss; // end of bss section
88
   extern unsigned int _ebss; // end of bss section
84
   return (int)&free_memory - (heap_end ?: (int)&_ebss);
94
   return (int)&free_memory - (heap_end ?: (int)&_ebss);
85
 }
95
 }
86
 
96
 
97
+// ------------------------
98
+// ADC
99
+// ------------------------
100
+
101
+void HAL_adc_start_conversion(const uint8_t ch) {
102
+  HAL_adc_result = analogRead(ch);
103
+}
104
+
105
+uint16_t HAL_adc_get_result() {
106
+  // nop
107
+  return HAL_adc_result;
108
+}
109
+
87
 // Forward the default serial ports
110
 // Forward the default serial ports
88
 #if USING_HW_SERIAL0
111
 #if USING_HW_SERIAL0
89
   DefaultSerial1 MSerial0(false, Serial);
112
   DefaultSerial1 MSerial0(false, Serial);

+ 47
- 87
Marlin/src/HAL/DUE/HAL.h View File

38
 
38
 
39
 #include "../../core/serial_hook.h"
39
 #include "../../core/serial_hook.h"
40
 
40
 
41
-// ------------------------
42
-// Serial ports
43
-// ------------------------
44
-
45
 typedef ForwardSerial1Class< decltype(Serial) > DefaultSerial1;
41
 typedef ForwardSerial1Class< decltype(Serial) > DefaultSerial1;
46
 typedef ForwardSerial1Class< decltype(Serial1) > DefaultSerial2;
42
 typedef ForwardSerial1Class< decltype(Serial1) > DefaultSerial2;
47
 typedef ForwardSerial1Class< decltype(Serial2) > DefaultSerial3;
43
 typedef ForwardSerial1Class< decltype(Serial2) > DefaultSerial3;
101
 #include "MarlinSerial.h"
97
 #include "MarlinSerial.h"
102
 #include "MarlinSerialUSB.h"
98
 #include "MarlinSerialUSB.h"
103
 
99
 
104
-// ------------------------
105
-// Types
106
-// ------------------------
100
+// On AVR this is in math.h?
101
+#define square(x) ((x)*(x))
107
 
102
 
108
 typedef int8_t pin_t;
103
 typedef int8_t pin_t;
109
 
104
 
110
-// Use shared/servos.cpp
111
 #define SHARED_SERVOS HAS_SERVOS
105
 #define SHARED_SERVOS HAS_SERVOS
112
-class Servo;
113
-typedef Servo hal_servo_t;
106
+#define HAL_SERVO_LIB Servo
114
 
107
 
115
 //
108
 //
116
 // Interrupts
109
 // Interrupts
117
 //
110
 //
118
-#define sei() noInterrupts()
119
-#define cli() interrupts()
111
+#define CRITICAL_SECTION_START()  uint32_t primask = __get_PRIMASK(); __disable_irq()
112
+#define CRITICAL_SECTION_END()    if (!primask) __enable_irq()
113
+#define ISRS_ENABLED() (!__get_PRIMASK())
114
+#define ENABLE_ISRS()  __enable_irq()
115
+#define DISABLE_ISRS() __disable_irq()
116
+
117
+void cli();                     // Disable interrupts
118
+void sei();                     // Enable interrupts
119
+
120
+void HAL_clear_reset_source();  // clear reset reason
121
+uint8_t HAL_get_reset_source(); // get reset reason
120
 
122
 
121
-#define CRITICAL_SECTION_START()  const bool _irqon = hal.isr_state(); hal.isr_off()
122
-#define CRITICAL_SECTION_END()    if (_irqon) hal.isr_on()
123
+void HAL_reboot();
123
 
124
 
124
 //
125
 //
125
 // ADC
126
 // ADC
126
 //
127
 //
127
-#define HAL_ADC_VREF         3.3
128
-#define HAL_ADC_RESOLUTION  10
128
+extern uint16_t HAL_adc_result;     // result of last ADC conversion
129
 
129
 
130
 #ifndef analogInputToDigitalPin
130
 #ifndef analogInputToDigitalPin
131
   #define analogInputToDigitalPin(p) ((p < 12U) ? (p) + 54U : -1)
131
   #define analogInputToDigitalPin(p) ((p < 12U) ? (p) + 54U : -1)
132
 #endif
132
 #endif
133
 
133
 
134
+#define HAL_ANALOG_SELECT(ch)
135
+
136
+inline void HAL_adc_init() {}//todo
137
+
138
+#define HAL_ADC_VREF         3.3
139
+#define HAL_ADC_RESOLUTION  10
140
+#define HAL_START_ADC(ch)   HAL_adc_start_conversion(ch)
141
+#define HAL_READ_ADC()      HAL_adc_result
142
+#define HAL_ADC_READY()     true
143
+
144
+void HAL_adc_start_conversion(const uint8_t ch);
145
+uint16_t HAL_adc_get_result();
146
+
134
 //
147
 //
135
-// Pin Mapping for M42, M43, M226
148
+// PWM
149
+//
150
+inline void set_pwm_duty(const pin_t pin, const uint16_t v, const uint16_t=255, const bool=false) { analogWrite(pin, v); }
151
+
152
+//
153
+// Pin Map
136
 //
154
 //
137
 #define GET_PIN_MAP_PIN(index) index
155
 #define GET_PIN_MAP_PIN(index) index
138
 #define GET_PIN_MAP_INDEX(pin) pin
156
 #define GET_PIN_MAP_INDEX(pin) pin
141
 //
159
 //
142
 // Tone
160
 // Tone
143
 //
161
 //
162
+void toneInit();
144
 void tone(const pin_t _pin, const unsigned int frequency, const unsigned long duration=0);
163
 void tone(const pin_t _pin, const unsigned int frequency, const unsigned long duration=0);
145
 void noTone(const pin_t _pin);
164
 void noTone(const pin_t _pin);
146
 
165
 
147
-// ------------------------
148
-// Class Utilities
149
-// ------------------------
166
+// Enable hooks into idle and setup for HAL
167
+#define HAL_IDLETASK 1
168
+void HAL_idletask();
169
+void HAL_init();
170
+
171
+//
172
+// Utility functions
173
+//
174
+void _delay_ms(const int delay);
150
 
175
 
151
 #pragma GCC diagnostic push
176
 #pragma GCC diagnostic push
152
 #if GCC_VERSION <= 50000
177
 #if GCC_VERSION <= 50000
153
   #pragma GCC diagnostic ignored "-Wunused-function"
178
   #pragma GCC diagnostic ignored "-Wunused-function"
154
 #endif
179
 #endif
155
 
180
 
181
+int freeMemory();
182
+
156
 #pragma GCC diagnostic pop
183
 #pragma GCC diagnostic pop
157
 
184
 
158
 #ifdef __cplusplus
185
 #ifdef __cplusplus
162
 #ifdef __cplusplus
189
 #ifdef __cplusplus
163
   }
190
   }
164
 #endif
191
 #endif
165
-
166
-// Return free RAM between end of heap (or end bss) and whatever is current
167
-int freeMemory();
168
-
169
-// ------------------------
170
-// MarlinHAL Class
171
-// ------------------------
172
-
173
-class MarlinHAL {
174
-public:
175
-
176
-  // Earliest possible init, before setup()
177
-  MarlinHAL() {}
178
-
179
-  static void init();       // Called early in setup()
180
-  static void init_board(); // Called less early in setup()
181
-  static void reboot();     // Software reset
182
-
183
-  static inline bool isr_state() { return !__get_PRIMASK(); }
184
-  static inline void isr_on()  { __enable_irq(); }
185
-  static inline void isr_off() { __disable_irq(); }
186
-
187
-  static inline void delay_ms(const int ms) { delay(ms); }
188
-
189
-  // Tasks, called from idle()
190
-  static void idletask();
191
-
192
-  // Reset
193
-  static uint8_t get_reset_source();
194
-  static inline void clear_reset_source() {}
195
-
196
-  // Free SRAM
197
-  static inline int freeMemory() { return ::freeMemory(); }
198
-
199
-  //
200
-  // ADC Methods
201
-  //
202
-
203
-  static uint16_t adc_result;
204
-
205
-  // Called by Temperature::init once at startup
206
-  static inline void adc_init() {}
207
-
208
-  // Called by Temperature::init for each sensor at startup
209
-  static inline void adc_enable(const int ch) {}
210
-
211
-  // Begin ADC sampling on the given channel
212
-  static inline void adc_start(const uint8_t ch) { adc_result = analogRead(ch); }
213
-
214
-  // Is the ADC ready for reading?
215
-  static inline bool adc_ready() { return true; }
216
-
217
-  // The current value of the ADC register
218
-  static inline uint16_t adc_value() { return adc_result; }
219
-
220
-  /**
221
-   * Set the PWM duty cycle for the pin to the given value.
222
-   * No inverting the duty cycle in this HAL.
223
-   * No changing the maximum size of the provided value to enable finer PWM duty control in this HAL.
224
-   */
225
-  static inline void set_pwm_duty(const pin_t pin, const uint16_t v, const uint16_t=255, const bool=false) {
226
-    analogWrite(pin, v);
227
-  }
228
-
229
-};
230
-
231
-extern MarlinHAL hal;

+ 2
- 2
Marlin/src/HAL/DUE/MarlinSerial.cpp View File

406
     const uint8_t i = (tx_buffer.head + 1) & (Cfg::TX_SIZE - 1);
406
     const uint8_t i = (tx_buffer.head + 1) & (Cfg::TX_SIZE - 1);
407
 
407
 
408
     // If global interrupts are disabled (as the result of being called from an ISR)...
408
     // If global interrupts are disabled (as the result of being called from an ISR)...
409
-    if (!hal.isr_state()) {
409
+    if (!ISRS_ENABLED()) {
410
 
410
 
411
       // Make room by polling if it is possible to transmit, and do so!
411
       // Make room by polling if it is possible to transmit, and do so!
412
       while (i == tx_buffer.tail) {
412
       while (i == tx_buffer.tail) {
454
     if (!_written) return;
454
     if (!_written) return;
455
 
455
 
456
     // If global interrupts are disabled (as the result of being called from an ISR)...
456
     // If global interrupts are disabled (as the result of being called from an ISR)...
457
-    if (!hal.isr_state()) {
457
+    if (!ISRS_ENABLED()) {
458
 
458
 
459
       // Wait until everything was transmitted - We must do polling, as interrupts are disabled
459
       // Wait until everything was transmitted - We must do polling, as interrupts are disabled
460
       while (tx_buffer.head != tx_buffer.tail || !(HWUART->UART_SR & UART_SR_TXEMPTY)) {
460
       while (tx_buffer.head != tx_buffer.tail || !(HWUART->UART_SR & UART_SR_TXEMPTY)) {

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

125
   pConfig->pTimerRegs->TC_CHANNEL[pConfig->channel].TC_SR;
125
   pConfig->pTimerRegs->TC_CHANNEL[pConfig->channel].TC_SR;
126
 }
126
 }
127
 
127
 
128
-#define HAL_timer_isr_epilogue(T) NOOP
128
+#define HAL_timer_isr_epilogue(T)

+ 18
- 17
Marlin/src/HAL/ESP32/HAL.cpp View File

52
 // Externs
52
 // Externs
53
 // ------------------------
53
 // ------------------------
54
 
54
 
55
-portMUX_TYPE MarlinHAL::spinlock = portMUX_INITIALIZER_UNLOCKED;
55
+portMUX_TYPE spinlock = portMUX_INITIALIZER_UNLOCKED;
56
 
56
 
57
 // ------------------------
57
 // ------------------------
58
 // Local defines
58
 // Local defines
64
 // Public Variables
64
 // Public Variables
65
 // ------------------------
65
 // ------------------------
66
 
66
 
67
-uint16_t MarlinHAL::adc_result;
67
+uint16_t HAL_adc_result;
68
 
68
 
69
 // ------------------------
69
 // ------------------------
70
 // Private Variables
70
 // Private Variables
95
 #endif
95
 #endif
96
 
96
 
97
 #if ENABLED(USE_ESP32_EXIO)
97
 #if ENABLED(USE_ESP32_EXIO)
98
-
99
   HardwareSerial YSerial2(2);
98
   HardwareSerial YSerial2(2);
100
 
99
 
101
   void Write_EXIO(uint8_t IO, uint8_t v) {
100
   void Write_EXIO(uint8_t IO, uint8_t v) {
102
-    if (hal.isr_state()) {
103
-      hal.isr_off();
101
+    if (ISRS_ENABLED()) {
102
+      DISABLE_ISRS();
104
       YSerial2.write(0x80 | (((char)v) << 5) | (IO - 100));
103
       YSerial2.write(0x80 | (((char)v) << 5) | (IO - 100));
105
-      hal.isr_on();
104
+      ENABLE_ISRS();
106
     }
105
     }
107
     else
106
     else
108
       YSerial2.write(0x80 | (((char)v) << 5) | (IO - 100));
107
       YSerial2.write(0x80 | (((char)v) << 5) | (IO - 100));
109
   }
108
   }
110
-
111
 #endif
109
 #endif
112
 
110
 
113
-void MarlinHAL::init_board() {
111
+void HAL_init_board() {
114
   #if ENABLED(USE_ESP32_TASK_WDT)
112
   #if ENABLED(USE_ESP32_TASK_WDT)
115
     esp_task_wdt_init(10, true);
113
     esp_task_wdt_init(10, true);
116
   #endif
114
   #endif
156
   #endif
154
   #endif
157
 }
155
 }
158
 
156
 
159
-void MarlinHAL::idletask() {
157
+void HAL_idletask() {
160
   #if BOTH(WIFISUPPORT, OTASUPPORT)
158
   #if BOTH(WIFISUPPORT, OTASUPPORT)
161
     OTA_handle();
159
     OTA_handle();
162
   #endif
160
   #endif
163
   TERN_(ESP3D_WIFISUPPORT, esp3dlib.idletask());
161
   TERN_(ESP3D_WIFISUPPORT, esp3dlib.idletask());
164
 }
162
 }
165
 
163
 
166
-uint8_t MarlinHAL::get_reset_source() { return rtc_get_reset_reason(1); }
164
+void HAL_clear_reset_source() { }
165
+
166
+uint8_t HAL_get_reset_source() { return rtc_get_reset_reason(1); }
167
 
167
 
168
-void MarlinHAL::reboot() { ESP.restart(); }
168
+void HAL_reboot() { ESP.restart(); }
169
+
170
+void _delay_ms(int delay_ms) { delay(delay_ms); }
169
 
171
 
170
 // return free memory between end of heap (or end bss) and whatever is current
172
 // return free memory between end of heap (or end bss) and whatever is current
171
-int MarlinHAL::freeMemory() { return ESP.getFreeHeap(); }
173
+int freeMemory() { return ESP.getFreeHeap(); }
172
 
174
 
173
 // ------------------------
175
 // ------------------------
174
 // ADC
176
 // ADC
175
 // ------------------------
177
 // ------------------------
176
-
177
 #define ADC1_CHANNEL(pin) ADC1_GPIO ## pin ## _CHANNEL
178
 #define ADC1_CHANNEL(pin) ADC1_GPIO ## pin ## _CHANNEL
178
 
179
 
179
 adc1_channel_t get_channel(int pin) {
180
 adc1_channel_t get_channel(int pin) {
195
   }
196
   }
196
 }
197
 }
197
 
198
 
198
-void MarlinHAL::adc_init() {
199
+void HAL_adc_init() {
199
   // Configure ADC
200
   // Configure ADC
200
   adc1_config_width(ADC_WIDTH_12Bit);
201
   adc1_config_width(ADC_WIDTH_12Bit);
201
 
202
 
225
   }
226
   }
226
 }
227
 }
227
 
228
 
228
-void MarlinHAL::adc_start(const pin_t pin) {
229
-  const adc1_channel_t chan = get_channel(pin);
229
+void HAL_adc_start_conversion(const uint8_t adc_pin) {
230
+  const adc1_channel_t chan = get_channel(adc_pin);
230
   uint32_t mv;
231
   uint32_t mv;
231
   esp_adc_cal_get_voltage((adc_channel_t)chan, &characteristics[attenuations[chan]], &mv);
232
   esp_adc_cal_get_voltage((adc_channel_t)chan, &characteristics[attenuations[chan]], &mv);
232
-  adc_result = mv * 1023.0 / 3300.0;
233
+  HAL_adc_result = mv * 1023.0 / 3300.0;
233
 
234
 
234
   // Change the attenuation level based on the new reading
235
   // Change the attenuation level based on the new reading
235
   adc_atten_t atten;
236
   adc_atten_t atten;

+ 57
- 88
Marlin/src/HAL/ESP32/HAL.h View File

49
 // Defines
49
 // Defines
50
 // ------------------------
50
 // ------------------------
51
 
51
 
52
+extern portMUX_TYPE spinlock;
53
+
52
 #define MYSERIAL1 flushableSerial
54
 #define MYSERIAL1 flushableSerial
53
 
55
 
54
 #if EITHER(WIFISUPPORT, ESP3D_WIFISUPPORT)
56
 #if EITHER(WIFISUPPORT, ESP3D_WIFISUPPORT)
63
 
65
 
64
 #define CRITICAL_SECTION_START() portENTER_CRITICAL(&spinlock)
66
 #define CRITICAL_SECTION_START() portENTER_CRITICAL(&spinlock)
65
 #define CRITICAL_SECTION_END()   portEXIT_CRITICAL(&spinlock)
67
 #define CRITICAL_SECTION_END()   portEXIT_CRITICAL(&spinlock)
68
+#define ISRS_ENABLED() (spinlock.owner == portMUX_FREE_VAL)
69
+#define ENABLE_ISRS()  if (spinlock.owner != portMUX_FREE_VAL) portEXIT_CRITICAL(&spinlock)
70
+#define DISABLE_ISRS() portENTER_CRITICAL(&spinlock)
66
 
71
 
67
 // ------------------------
72
 // ------------------------
68
 // Types
73
 // Types
70
 
75
 
71
 typedef int16_t pin_t;
76
 typedef int16_t pin_t;
72
 
77
 
73
-class Servo;
74
-typedef Servo hal_servo_t;
78
+#define HAL_SERVO_LIB Servo
79
+
80
+// ------------------------
81
+// Public Variables
82
+// ------------------------
83
+
84
+/** result of last ADC conversion */
85
+extern uint16_t HAL_adc_result;
75
 
86
 
76
 // ------------------------
87
 // ------------------------
77
 // Public functions
88
 // Public functions
80
 //
91
 //
81
 // Tone
92
 // Tone
82
 //
93
 //
94
+void toneInit();
83
 void tone(const pin_t _pin, const unsigned int frequency, const unsigned long duration=0);
95
 void tone(const pin_t _pin, const unsigned int frequency, const unsigned long duration=0);
84
 void noTone(const pin_t _pin);
96
 void noTone(const pin_t _pin);
85
 
97
 
98
+// clear reset reason
99
+void HAL_clear_reset_source();
100
+
101
+// reset reason
102
+uint8_t HAL_get_reset_source();
103
+
104
+void HAL_reboot();
105
+
106
+void _delay_ms(int delay);
107
+
108
+#pragma GCC diagnostic push
109
+#if GCC_VERSION <= 50000
110
+  #pragma GCC diagnostic ignored "-Wunused-function"
111
+#endif
112
+
113
+int freeMemory();
114
+
115
+#pragma GCC diagnostic pop
116
+
86
 void analogWrite(pin_t pin, int value);
117
 void analogWrite(pin_t pin, int value);
87
 
118
 
88
-//
89
-// Pin Mapping for M42, M43, M226
90
-//
119
+// ADC
120
+#define HAL_ANALOG_SELECT(pin)
121
+
122
+void HAL_adc_init();
123
+
124
+#define HAL_ADC_VREF         3.3
125
+#define HAL_ADC_RESOLUTION  10
126
+#define HAL_START_ADC(pin)  HAL_adc_start_conversion(pin)
127
+#define HAL_READ_ADC()      HAL_adc_result
128
+#define HAL_ADC_READY()     true
129
+
130
+void HAL_adc_start_conversion(const uint8_t adc_pin);
131
+
132
+// PWM
133
+inline void set_pwm_duty(const pin_t pin, const uint16_t v, const uint16_t=255, const bool=false) { analogWrite(pin, v); }
134
+
135
+// Pin Map
91
 #define GET_PIN_MAP_PIN(index) index
136
 #define GET_PIN_MAP_PIN(index) index
92
 #define GET_PIN_MAP_INDEX(pin) pin
137
 #define GET_PIN_MAP_INDEX(pin) pin
93
 #define PARSED_PIN_INDEX(code, dval) parser.intval(code, dval)
138
 #define PARSED_PIN_INDEX(code, dval) parser.intval(code, dval)
94
 
139
 
140
+// Enable hooks into idle and setup for HAL
141
+#define HAL_IDLETASK 1
142
+#define BOARD_INIT() HAL_init_board();
143
+void HAL_idletask();
144
+inline void HAL_init() {}
145
+void HAL_init_board();
146
+
95
 #if ENABLED(USE_ESP32_EXIO)
147
 #if ENABLED(USE_ESP32_EXIO)
96
   void Write_EXIO(uint8_t IO, uint8_t v);
148
   void Write_EXIO(uint8_t IO, uint8_t v);
97
 #endif
149
 #endif
136
   }
188
   }
137
 
189
 
138
 }
190
 }
139
-
140
-// ------------------------
141
-// Class Utilities
142
-// ------------------------
143
-
144
-#pragma GCC diagnostic push
145
-#if GCC_VERSION <= 50000
146
-  #pragma GCC diagnostic ignored "-Wunused-function"
147
-#endif
148
-
149
-int freeMemory();
150
-
151
-#pragma GCC diagnostic pop
152
-
153
-void _delay_ms(const int ms);
154
-
155
-// ------------------------
156
-// MarlinHAL Class
157
-// ------------------------
158
-
159
-#define HAL_ADC_VREF         3.3
160
-#define HAL_ADC_RESOLUTION  10
161
-
162
-class MarlinHAL {
163
-public:
164
-
165
-  // Earliest possible init, before setup()
166
-  MarlinHAL() {}
167
-
168
-  static inline void init() {}  // Called early in setup()
169
-  static void init_board();     // Called less early in setup()
170
-  static void reboot();         // Restart the firmware
171
-
172
-  static portMUX_TYPE spinlock;
173
-  static inline bool isr_state() { return spinlock.owner == portMUX_FREE_VAL; }
174
-  static inline void isr_on()  { if (spinlock.owner != portMUX_FREE_VAL) portEXIT_CRITICAL(&spinlock); }
175
-  static inline void isr_off() { portENTER_CRITICAL(&spinlock); }
176
-
177
-  static inline void delay_ms(const int ms) { _delay_ms(ms); }
178
-
179
-  // Tasks, called from idle()
180
-  static void idletask();
181
-
182
-  // Reset
183
-  static uint8_t get_reset_source();
184
-  static inline void clear_reset_source() {}
185
-
186
-  // Free SRAM
187
-  static int freeMemory();
188
-
189
-  //
190
-  // ADC Methods
191
-  //
192
-
193
-  static uint16_t adc_result;
194
-
195
-  // Called by Temperature::init once at startup
196
-  static void adc_init();
197
-
198
-  // Called by Temperature::init for each sensor at startup
199
-  static inline void adc_enable(const pin_t pin) {}
200
-
201
-  // Begin ADC sampling on the given channel
202
-  static void adc_start(const pin_t pin);
203
-
204
-  // Is the ADC ready for reading?
205
-  static inline bool adc_ready() { return true; }
206
-
207
-  // The current value of the ADC register
208
-  static inline uint16_t adc_value() { return adc_result; }
209
-
210
-  /**
211
-   * Set the PWM duty cycle for the pin to the given value.
212
-   * No inverting the duty cycle in this HAL.
213
-   * No changing the maximum size of the provided value to enable finer PWM duty control in this HAL.
214
-   */
215
-  static inline void set_pwm_duty(const pin_t pin, const uint16_t v, const uint16_t=255, const bool=false) {
216
-    analogWrite(pin, v);
217
-  }
218
-
219
-};
220
-
221
-extern MarlinHAL hal;

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

136
 void HAL_timer_disable_interrupt(const uint8_t timer_num);
136
 void HAL_timer_disable_interrupt(const uint8_t timer_num);
137
 bool HAL_timer_interrupt_enabled(const uint8_t timer_num);
137
 bool HAL_timer_interrupt_enabled(const uint8_t timer_num);
138
 
138
 
139
-#define HAL_timer_isr_prologue(T) NOOP
140
-#define HAL_timer_isr_epilogue(T) NOOP
139
+#define HAL_timer_isr_prologue(T)
140
+#define HAL_timer_isr_epilogue(T)

+ 27
- 12
Marlin/src/HAL/LINUX/HAL.cpp View File

24
 #include "../../inc/MarlinConfig.h"
24
 #include "../../inc/MarlinConfig.h"
25
 #include "../shared/Delay.h"
25
 #include "../shared/Delay.h"
26
 
26
 
27
-extern MarlinHAL hal;
28
-
29
-// ------------------------
30
-// Serial ports
31
-// ------------------------
32
-
33
 MSerialT usb_serial(TERN0(EMERGENCY_PARSER, true));
27
 MSerialT usb_serial(TERN0(EMERGENCY_PARSER, true));
34
 
28
 
35
 // U8glib required functions
29
 // U8glib required functions
43
 //************************//
37
 //************************//
44
 
38
 
45
 // return free heap space
39
 // return free heap space
46
-int freeMemory() { return 0; }
40
+int freeMemory() {
41
+  return 0;
42
+}
47
 
43
 
48
 // ------------------------
44
 // ------------------------
49
 // ADC
45
 // ADC
50
 // ------------------------
46
 // ------------------------
51
 
47
 
52
-uint8_t MarlinHAL::active_ch = 0;
48
+void HAL_adc_init() {
53
 
49
 
54
-uint16_t MarlinHAL::adc_value() {
55
-  const pin_t pin = analogInputToDigitalPin(active_ch);
50
+}
51
+
52
+void HAL_adc_enable_channel(const uint8_t ch) {
53
+
54
+}
55
+
56
+uint8_t active_ch = 0;
57
+void HAL_adc_start_conversion(const uint8_t ch) {
58
+  active_ch = ch;
59
+}
60
+
61
+bool HAL_adc_finished() {
62
+  return true;
63
+}
64
+
65
+uint16_t HAL_adc_get_result() {
66
+  pin_t pin = analogInputToDigitalPin(active_ch);
56
   if (!VALID_PIN(pin)) return 0;
67
   if (!VALID_PIN(pin)) return 0;
57
-  const uint16_t data = ((Gpio::get(pin) >> 2) & 0x3FF);
68
+  uint16_t data = ((Gpio::get(pin) >> 2) & 0x3FF);
58
   return data;    // return 10bit value as Marlin expects
69
   return data;    // return 10bit value as Marlin expects
59
 }
70
 }
60
 
71
 
61
-void MarlinHAL::reboot() { /* Reset the application state and GPIO */ }
72
+void HAL_pwm_init() {
73
+
74
+}
75
+
76
+void HAL_reboot() { /* Reset the application state and GPIO */ }
62
 
77
 
63
 #endif // __PLAT_LINUX__
78
 #endif // __PLAT_LINUX__

+ 49
- 95
Marlin/src/HAL/LINUX/HAL.h View File

21
  */
21
  */
22
 #pragma once
22
 #pragma once
23
 
23
 
24
-#include <iostream>
25
-#include <stdint.h>
26
-#include <stdarg.h>
27
-#undef min
28
-#undef max
29
-#include <algorithm>
30
-
31
-#include "hardware/Clock.h"
32
-
33
-#include "../shared/Marduino.h"
34
-#include "../shared/math_32bit.h"
35
-#include "../shared/HAL_SPI.h"
36
-#include "fastio.h"
37
-#include "watchdog.h"
38
-#include "serial.h"
39
-
40
-// ------------------------
41
-// Defines
42
-// ------------------------
43
-
44
 #define CPU_32_BIT
24
 #define CPU_32_BIT
45
-#define SHARED_SERVOS HAS_SERVOS  // Use shared/servos.cpp
46
 
25
 
47
 #define F_CPU 100000000UL
26
 #define F_CPU 100000000UL
48
 #define SystemCoreClock F_CPU
27
 #define SystemCoreClock F_CPU
28
+#include <iostream>
29
+#include <stdint.h>
30
+#include <stdarg.h>
49
 
31
 
50
-#define DELAY_CYCLES(x) Clock::delayCycles(x)
32
+#undef min
33
+#undef max
51
 
34
 
52
-#define CPU_ST7920_DELAY_1 600
53
-#define CPU_ST7920_DELAY_2 750
54
-#define CPU_ST7920_DELAY_3 750
35
+#include <algorithm>
55
 
36
 
56
-void _printf(const  char *format, ...);
37
+void _printf (const  char *format, ...);
57
 void _putc(uint8_t c);
38
 void _putc(uint8_t c);
58
 uint8_t _getc();
39
 uint8_t _getc();
59
 
40
 
41
+//extern "C" volatile uint32_t _millis;
42
+
60
 //arduino: Print.h
43
 //arduino: Print.h
61
 #define DEC 10
44
 #define DEC 10
62
 #define HEX 16
45
 #define HEX 16
66
 #define B01 1
49
 #define B01 1
67
 #define B10 2
50
 #define B10 2
68
 
51
 
69
-// ------------------------
70
-// Serial ports
71
-// ------------------------
52
+#include "hardware/Clock.h"
53
+
54
+#include "../shared/Marduino.h"
55
+#include "../shared/math_32bit.h"
56
+#include "../shared/HAL_SPI.h"
57
+#include "fastio.h"
58
+#include "watchdog.h"
59
+#include "serial.h"
60
+
61
+#define SHARED_SERVOS HAS_SERVOS
72
 
62
 
73
 extern MSerialT usb_serial;
63
 extern MSerialT usb_serial;
74
 #define MYSERIAL1 usb_serial
64
 #define MYSERIAL1 usb_serial
75
 
65
 
66
+#define CPU_ST7920_DELAY_1 600
67
+#define CPU_ST7920_DELAY_2 750
68
+#define CPU_ST7920_DELAY_3 750
69
+
76
 //
70
 //
77
 // Interrupts
71
 // Interrupts
78
 //
72
 //
79
 #define CRITICAL_SECTION_START()
73
 #define CRITICAL_SECTION_START()
80
 #define CRITICAL_SECTION_END()
74
 #define CRITICAL_SECTION_END()
75
+#define ISRS_ENABLED()
76
+#define ENABLE_ISRS()
77
+#define DISABLE_ISRS()
81
 
78
 
82
-// ADC
83
-#define HAL_ADC_VREF           5.0
84
-#define HAL_ADC_RESOLUTION    10
85
-
86
-// ------------------------
87
-// Class Utilities
88
-// ------------------------
79
+inline void HAL_init() {}
89
 
80
 
81
+// Utility functions
90
 #pragma GCC diagnostic push
82
 #pragma GCC diagnostic push
91
 #if GCC_VERSION <= 50000
83
 #if GCC_VERSION <= 50000
92
   #pragma GCC diagnostic ignored "-Wunused-function"
84
   #pragma GCC diagnostic ignored "-Wunused-function"
96
 
88
 
97
 #pragma GCC diagnostic pop
89
 #pragma GCC diagnostic pop
98
 
90
 
99
-// ------------------------
100
-// MarlinHAL Class
101
-// ------------------------
102
-
103
-class MarlinHAL {
104
-public:
105
-
106
-  // Earliest possible init, before setup()
107
-  MarlinHAL() {}
108
-
109
-  static inline void init() {}        // Called early in setup()
110
-  static inline void init_board() {}  // Called less early in setup()
111
-  static void reboot();               // Reset the application state and GPIO
112
-
113
-  static inline bool isr_state() { return true; }
114
-  static inline void isr_on()  {}
115
-  static inline void isr_off() {}
116
-
117
-  static inline void delay_ms(const int ms) { _delay_ms(ms); }
118
-
119
-  // Tasks, called from idle()
120
-  static inline void idletask() {}
121
-
122
-  // Reset
123
-  static constexpr uint8_t reset_reason = RST_POWER_ON;
124
-  static inline uint8_t get_reset_source() { return reset_reason; }
125
-  static inline void clear_reset_source() {}
126
-
127
-  // Free SRAM
128
-  static inline int freeMemory() { return ::freeMemory(); }
129
-
130
-  //
131
-  // ADC Methods
132
-  //
133
-
134
-  static uint8_t active_ch;
135
-
136
-  // Called by Temperature::init once at startup
137
-  static inline void adc_init() {}
138
-
139
-  // Called by Temperature::init for each sensor at startup
140
-  static inline void adc_enable(const uint8_t) {}
141
-
142
-  // Begin ADC sampling on the given channel
143
-  static inline void adc_start(const uint8_t ch) { active_ch = ch; }
91
+// ADC
92
+#define HAL_ADC_VREF           5.0
93
+#define HAL_ADC_RESOLUTION    10
94
+#define HAL_ANALOG_SELECT(ch) HAL_adc_enable_channel(ch)
95
+#define HAL_START_ADC(ch)     HAL_adc_start_conversion(ch)
96
+#define HAL_READ_ADC()        HAL_adc_get_result()
97
+#define HAL_ADC_READY()       true
144
 
98
 
145
-  // Is the ADC ready for reading?
146
-  static inline bool adc_ready() { return true; }
99
+void HAL_adc_init();
100
+void HAL_adc_enable_channel(const uint8_t ch);
101
+void HAL_adc_start_conversion(const uint8_t ch);
102
+uint16_t HAL_adc_get_result();
147
 
103
 
148
-  // The current value of the ADC register
149
-  static uint16_t adc_value();
104
+// PWM
105
+inline void set_pwm_duty(const pin_t pin, const uint16_t v, const uint16_t=255, const bool=false) { analogWrite(pin, v); }
150
 
106
 
151
-  /**
152
-   * Set the PWM duty cycle for the pin to the given value.
153
-   * No option to change the resolution or invert the duty cycle.
154
-   */
155
-  static inline void set_pwm_duty(const pin_t pin, const uint16_t v, const uint16_t=255, const bool=false) {
156
-    analogWrite(pin, v);
157
-  }
107
+// Reset source
108
+inline void HAL_clear_reset_source(void) {}
109
+inline uint8_t HAL_get_reset_source(void) { return RST_POWER_ON; }
158
 
110
 
159
-  static inline void set_pwm_frequency(const pin_t, int) {}
160
-};
111
+void HAL_reboot(); // Reset the application state and GPIO
161
 
112
 
162
-extern MarlinHAL hal;
113
+/* ---------------- Delay in cycles */
114
+FORCE_INLINE static void DELAY_CYCLES(uint64_t x) {
115
+  Clock::delayCycles(x);
116
+}

+ 3
- 1
Marlin/src/HAL/LINUX/arduino.cpp View File

31
 void sei() { } // Enable
31
 void sei() { } // Enable
32
 
32
 
33
 // Time functions
33
 // Time functions
34
-void _delay_ms(const int ms) { delay(ms); }
34
+void _delay_ms(const int delay_ms) {
35
+  delay(delay_ms);
36
+}
35
 
37
 
36
 uint32_t millis() {
38
 uint32_t millis() {
37
   return (uint32_t)Clock::millis();
39
   return (uint32_t)Clock::millis();

+ 3
- 2
Marlin/src/HAL/LINUX/include/Arduino.h View File

59
 #endif
59
 #endif
60
 
60
 
61
 #define sq(v) ((v) * (v))
61
 #define sq(v) ((v) * (v))
62
+#define square(v) sq(v)
62
 #define constrain(value, arg_min, arg_max) ((value) < (arg_min) ? (arg_min) :((value) > (arg_max) ? (arg_max) : (value)))
63
 #define constrain(value, arg_min, arg_max) ((value) < (arg_min) ? (arg_min) :((value) > (arg_max) ? (arg_max) : (value)))
63
 
64
 
64
 //Interrupts
65
 //Interrupts
73
 }
74
 }
74
 
75
 
75
 // Time functions
76
 // Time functions
76
-extern "C" void delay(const int ms);
77
-void _delay_ms(const int ms);
77
+extern "C" void delay(const int milis);
78
+void _delay_ms(const int delay);
78
 void delayMicroseconds(unsigned long);
79
 void delayMicroseconds(unsigned long);
79
 uint32_t millis();
80
 uint32_t millis();
80
 
81
 

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

92
 void HAL_timer_disable_interrupt(const uint8_t timer_num);
92
 void HAL_timer_disable_interrupt(const uint8_t timer_num);
93
 bool HAL_timer_interrupt_enabled(const uint8_t timer_num);
93
 bool HAL_timer_interrupt_enabled(const uint8_t timer_num);
94
 
94
 
95
-#define HAL_timer_isr_prologue(T) NOOP
96
-#define HAL_timer_isr_epilogue(T) NOOP
95
+#define HAL_timer_isr_prologue(T)
96
+#define HAL_timer_isr_epilogue(T)

+ 22
- 20
Marlin/src/HAL/LPC1768/HAL.cpp View File

31
 
31
 
32
 DefaultSerial1 USBSerial(false, UsbSerial);
32
 DefaultSerial1 USBSerial(false, UsbSerial);
33
 
33
 
34
-uint32_t MarlinHAL::adc_result = 0;
34
+uint32_t HAL_adc_reading = 0;
35
 
35
 
36
 // U8glib required functions
36
 // U8glib required functions
37
 extern "C" {
37
 extern "C" {
41
   void u8g_Delay(uint16_t val)       { delay(val); }
41
   void u8g_Delay(uint16_t val)       { delay(val); }
42
 }
42
 }
43
 
43
 
44
+//************************//
45
+
44
 // return free heap space
46
 // return free heap space
45
 int freeMemory() {
47
 int freeMemory() {
46
   char stack_end;
48
   char stack_end;
52
   return result;
54
   return result;
53
 }
55
 }
54
 
56
 
55
-void MarlinHAL::reboot() { NVIC_SystemReset(); }
56
-
57
-uint8_t MarlinHAL::get_reset_source() {
58
-  #if ENABLED(USE_WATCHDOG)
59
-    if (watchdog_timed_out()) return RST_WATCHDOG;
60
-  #endif
61
-  return RST_POWER_ON;
62
-}
63
-
64
-void MarlinHAL::clear_reset_source() {
65
-  TERN_(USE_WATCHDOG, watchdog_clear_timeout_flag());
57
+// scan command line for code
58
+//   return index into pin map array if found and the pin is valid.
59
+//   return dval if not found or not a valid pin.
60
+int16_t PARSED_PIN_INDEX(const char code, const int16_t dval) {
61
+  const uint16_t val = (uint16_t)parser.intval(code, -1), port = val / 100, pin = val % 100;
62
+  const  int16_t ind = (port < ((NUM_DIGITAL_PINS) >> 5) && pin < 32) ? ((port << 5) | pin) : -2;
63
+  return ind > -1 ? ind : dval;
66
 }
64
 }
67
 
65
 
68
 void flashFirmware(const int16_t) {
66
 void flashFirmware(const int16_t) {
69
   delay(500);          // Give OS time to disconnect
67
   delay(500);          // Give OS time to disconnect
70
   USB_Connect(false);  // USB clear connection
68
   USB_Connect(false);  // USB clear connection
71
   delay(1000);         // Give OS time to notice
69
   delay(1000);         // Give OS time to notice
72
-  hal.reboot();
70
+  HAL_reboot();
73
 }
71
 }
74
 
72
 
75
-// For M42/M43, scan command line for pin code
76
-//   return index into pin map array if found and the pin is valid.
77
-//   return dval if not found or not a valid pin.
78
-int16_t PARSED_PIN_INDEX(const char code, const int16_t dval) {
79
-  const uint16_t val = (uint16_t)parser.intval(code, -1), port = val / 100, pin = val % 100;
80
-  const  int16_t ind = (port < ((NUM_DIGITAL_PINS) >> 5) && pin < 32) ? ((port << 5) | pin) : -2;
81
-  return ind > -1 ? ind : dval;
73
+void HAL_clear_reset_source(void) {
74
+  TERN_(USE_WATCHDOG, watchdog_clear_timeout_flag());
82
 }
75
 }
83
 
76
 
77
+uint8_t HAL_get_reset_source(void) {
78
+  #if ENABLED(USE_WATCHDOG)
79
+    if (watchdog_timed_out()) return RST_WATCHDOG;
80
+  #endif
81
+  return RST_POWER_ON;
82
+}
83
+
84
+void HAL_reboot() { NVIC_SystemReset(); }
85
+
84
 #endif // TARGET_LPC1768
86
 #endif // TARGET_LPC1768

+ 59
- 101
Marlin/src/HAL/LPC1768/HAL.h View File

28
 
28
 
29
 #define CPU_32_BIT
29
 #define CPU_32_BIT
30
 
30
 
31
+void HAL_init();
32
+
31
 #include <stdint.h>
33
 #include <stdint.h>
32
 #include <stdarg.h>
34
 #include <stdarg.h>
33
 #include <algorithm>
35
 #include <algorithm>
45
 #include <pinmapping.h>
47
 #include <pinmapping.h>
46
 #include <CDCSerial.h>
48
 #include <CDCSerial.h>
47
 
49
 
48
-// ------------------------
49
-// Serial ports
50
-// ------------------------
50
+//
51
+// Default graphical display delays
52
+//
53
+#define CPU_ST7920_DELAY_1 600
54
+#define CPU_ST7920_DELAY_2 750
55
+#define CPU_ST7920_DELAY_3 750
51
 
56
 
52
 typedef ForwardSerial1Class< decltype(UsbSerial) > DefaultSerial1;
57
 typedef ForwardSerial1Class< decltype(UsbSerial) > DefaultSerial1;
53
 extern DefaultSerial1 USBSerial;
58
 extern DefaultSerial1 USBSerial;
109
 //
114
 //
110
 // Interrupts
115
 // Interrupts
111
 //
116
 //
117
+#define CRITICAL_SECTION_START()  uint32_t primask = __get_PRIMASK(); __disable_irq()
118
+#define CRITICAL_SECTION_END()    if (!primask) __enable_irq()
119
+#define ISRS_ENABLED() (!__get_PRIMASK())
120
+#define ENABLE_ISRS()  __enable_irq()
121
+#define DISABLE_ISRS() __disable_irq()
122
+
123
+//
124
+// Utility functions
125
+//
126
+#pragma GCC diagnostic push
127
+#if GCC_VERSION <= 50000
128
+  #pragma GCC diagnostic ignored "-Wunused-function"
129
+#endif
112
 
130
 
113
-#define CRITICAL_SECTION_START()  const bool irqon = !__get_PRIMASK(); __disable_irq()
114
-#define CRITICAL_SECTION_END()    if (irqon) __enable_irq()
131
+int freeMemory();
132
+
133
+#pragma GCC diagnostic pop
115
 
134
 
116
 //
135
 //
117
-// ADC
136
+// ADC API
118
 //
137
 //
119
 
138
 
120
 #define ADC_MEDIAN_FILTER_SIZE (23) // Higher values increase step delay (phase shift),
139
 #define ADC_MEDIAN_FILTER_SIZE (23) // Higher values increase step delay (phase shift),
133
 #define HAL_ADC_RESOLUTION     12   // 15 bit maximum, raw temperature is stored as int16_t
152
 #define HAL_ADC_RESOLUTION     12   // 15 bit maximum, raw temperature is stored as int16_t
134
 #define HAL_ADC_FILTERED            // Disable oversampling done in Marlin as ADC values already filtered in HAL
153
 #define HAL_ADC_FILTERED            // Disable oversampling done in Marlin as ADC values already filtered in HAL
135
 
154
 
136
-//
137
-// Pin Mapping for M42, M43, M226
138
-//
155
+using FilteredADC = LPC176x::ADC<ADC_LOWPASS_K_VALUE, ADC_MEDIAN_FILTER_SIZE>;
156
+extern uint32_t HAL_adc_reading;
157
+[[gnu::always_inline]] inline void HAL_adc_start_conversion(const pin_t pin) {
158
+  HAL_adc_reading = FilteredADC::read(pin) >> (16 - HAL_ADC_RESOLUTION); // returns 16bit value, reduce to required bits
159
+}
160
+[[gnu::always_inline]] inline uint16_t HAL_adc_get_result() {
161
+  return HAL_adc_reading;
162
+}
163
+
164
+#define HAL_adc_init()
165
+#define HAL_ANALOG_SELECT(pin) FilteredADC::enable_channel(pin)
166
+#define HAL_START_ADC(pin)     HAL_adc_start_conversion(pin)
167
+#define HAL_READ_ADC()         HAL_adc_get_result()
168
+#define HAL_ADC_READY()        (true)
139
 
169
 
140
 // Test whether the pin is valid
170
 // Test whether the pin is valid
141
 constexpr bool VALID_PIN(const pin_t pin) {
171
 constexpr bool VALID_PIN(const pin_t pin) {
162
 // P0.6 thru P0.9 are for the onboard SD card
192
 // P0.6 thru P0.9 are for the onboard SD card
163
 #define HAL_SENSITIVE_PINS P0_06, P0_07, P0_08, P0_09,
193
 #define HAL_SENSITIVE_PINS P0_06, P0_07, P0_08, P0_09,
164
 
194
 
165
-// ------------------------
166
-// Defines
167
-// ------------------------
195
+#define HAL_IDLETASK 1
196
+void HAL_idletask();
168
 
197
 
169
 #define PLATFORM_M997_SUPPORT
198
 #define PLATFORM_M997_SUPPORT
170
 void flashFirmware(const int16_t);
199
 void flashFirmware(const int16_t);
171
 
200
 
172
 #define HAL_CAN_SET_PWM_FREQ   // This HAL supports PWM Frequency adjustment
201
 #define HAL_CAN_SET_PWM_FREQ   // This HAL supports PWM Frequency adjustment
173
 
202
 
174
-// Default graphical display delays
175
-#define CPU_ST7920_DELAY_1 600
176
-#define CPU_ST7920_DELAY_2 750
177
-#define CPU_ST7920_DELAY_3 750
178
-
179
-// ------------------------
180
-// Class Utilities
181
-// ------------------------
182
-
183
-#pragma GCC diagnostic push
184
-#if GCC_VERSION <= 50000
185
-  #pragma GCC diagnostic ignored "-Wunused-function"
186
-#endif
187
-
188
-int freeMemory();
189
-
190
-#pragma GCC diagnostic pop
191
-
192
-// ------------------------
193
-// MarlinHAL Class
194
-// ------------------------
195
-
196
-class MarlinHAL {
197
-public:
198
-
199
-  // Earliest possible init, before setup()
200
-  MarlinHAL() {}
201
-
202
-  static void init();                 // Called early in setup()
203
-  static inline void init_board() {}  // Called less early in setup()
204
-  static void reboot();               // Restart the firmware from 0x0
205
-
206
-  static inline bool isr_state() { return !__get_PRIMASK(); }
207
-  static inline void isr_on()  { __enable_irq(); }
208
-  static inline void isr_off() { __disable_irq(); }
209
-
210
-  static inline void delay_ms(const int ms) { _delay_ms(ms); }
211
-
212
-  // Tasks, called from idle()
213
-  static void idletask();
214
-
215
-  // Reset
216
-  static uint8_t get_reset_source();
217
-  static void clear_reset_source();
218
-
219
-  // Free SRAM
220
-  static inline int freeMemory() { return ::freeMemory(); }
221
-
222
-  //
223
-  // ADC Methods
224
-  //
225
-
226
-  using FilteredADC = LPC176x::ADC<ADC_LOWPASS_K_VALUE, ADC_MEDIAN_FILTER_SIZE>;
227
-
228
-  // Called by Temperature::init once at startup
229
-  static inline void adc_init() {}
230
-
231
-  // Called by Temperature::init for each sensor at startup
232
-  static inline void adc_enable(const pin_t pin) {
233
-    FilteredADC::enable_channel(pin);
234
-  }
235
-
236
-  // Begin ADC sampling on the given pin
237
-  static uint32_t adc_result;
238
-  FORCE_INLINE static void adc_start(const pin_t pin) {
239
-    adc_result = FilteredADC::read(pin) >> (16 - HAL_ADC_RESOLUTION); // returns 16bit value, reduce to required bits
240
-  }
241
-
242
-  // Is the ADC ready for reading?
243
-  static inline bool adc_ready() { return true; }
244
-
245
-  // The current value of the ADC register
246
-  FORCE_INLINE static uint16_t adc_value() {
247
-    return (uint16_t)adc_result;
248
-  }
203
+/**
204
+ * set_pwm_frequency
205
+ *  Set the frequency of the timer corresponding to the provided pin
206
+ *  All Hardware PWM pins run at the same frequency and all
207
+ *  Software PWM pins run at the same frequency
208
+ */
209
+void set_pwm_frequency(const pin_t pin, int f_desired);
249
 
210
 
250
-  /**
251
-   * Set the PWM duty cycle for the pin to the given value.
252
-   * Optionally invert the duty cycle [default = false]
253
-   * Optionally change the scale of the provided value to enable finer PWM duty control [default = 255]
254
-   */
255
-  static void set_pwm_duty(const pin_t pin, const uint16_t v, const uint16_t v_size=255, const bool invert=false);
211
+/**
212
+ * set_pwm_duty
213
+ *  Set the PWM duty cycle of the provided pin to the provided value
214
+ *  Optionally allows inverting the duty cycle [default = false]
215
+ *  Optionally allows changing the maximum size of the provided value to enable finer PWM duty control [default = 255]
216
+ */
217
+void set_pwm_duty(const pin_t pin, const uint16_t v, const uint16_t v_size=255, const bool invert=false);
256
 
218
 
257
-  /**
258
-   * Set the frequency of the timer corresponding to the provided pin
259
-   * All Hardware PWM pins will run at the same frequency and
260
-   * All Software PWM pins will run at the same frequency
261
-   */
262
-  static void set_pwm_frequency(const pin_t pin, int f_desired);
263
-};
219
+// Reset source
220
+void HAL_clear_reset_source(void);
221
+uint8_t HAL_get_reset_source(void);
264
 
222
 
265
-extern MarlinHAL hal;
223
+void HAL_reboot();

+ 1
- 2
Marlin/src/HAL/LPC1768/Servo.h View File

65
   }
65
   }
66
 };
66
 };
67
 
67
 
68
-class libServo;
69
-typedef libServo hal_servo_t;
68
+#define HAL_SERVO_LIB libServo

+ 9
- 5
Marlin/src/HAL/LPC1768/fast_pwm.cpp View File

21
  */
21
  */
22
 #ifdef TARGET_LPC1768
22
 #ifdef TARGET_LPC1768
23
 
23
 
24
-#include "../../inc/MarlinConfig.h"
24
+#include "../../inc/MarlinConfigPre.h"
25
 #include <pwm.h>
25
 #include <pwm.h>
26
 
26
 
27
-void MarlinHAL::set_pwm_duty(const pin_t pin, const uint16_t v, const uint16_t v_size/*=255*/, const bool invert/*=false*/) {
27
+void set_pwm_duty(const pin_t pin, const uint16_t v, const uint16_t v_size/*=255*/, const bool invert/*=false*/) {
28
   if (!LPC176x::pin_is_valid(pin)) return;
28
   if (!LPC176x::pin_is_valid(pin)) return;
29
   if (LPC176x::pwm_attach_pin(pin))
29
   if (LPC176x::pwm_attach_pin(pin))
30
     LPC176x::pwm_write_ratio(pin, invert ? 1.0f - (float)v / v_size : (float)v / v_size);  // map 1-254 onto PWM range
30
     LPC176x::pwm_write_ratio(pin, invert ? 1.0f - (float)v / v_size : (float)v / v_size);  // map 1-254 onto PWM range
31
 }
31
 }
32
 
32
 
33
-void MarlinHAL::set_pwm_frequency(const pin_t pin, int f_desired) {
34
-  LPC176x::pwm_set_frequency(pin, f_desired);
35
-}
33
+#if NEEDS_HARDWARE_PWM // Specific meta-flag for features that mandate PWM
34
+
35
+  void set_pwm_frequency(const pin_t pin, int f_desired) {
36
+    LPC176x::pwm_set_frequency(pin, f_desired);
37
+  }
38
+
39
+#endif
36
 
40
 
37
 #endif // TARGET_LPC1768
41
 #endif // TARGET_LPC1768

+ 3
- 3
Marlin/src/HAL/LPC1768/main.cpp View File

48
 
48
 
49
 TERN_(POSTMORTEM_DEBUGGING, extern void install_min_serial());
49
 TERN_(POSTMORTEM_DEBUGGING, extern void install_min_serial());
50
 
50
 
51
-void MarlinHAL::init() {
51
+void HAL_init() {
52
 
52
 
53
   // Init LEDs
53
   // Init LEDs
54
   #if PIN_EXISTS(LED)
54
   #if PIN_EXISTS(LED)
130
   const millis_t usb_timeout = millis() + 2000;
130
   const millis_t usb_timeout = millis() + 2000;
131
   while (!USB_Configuration && PENDING(millis(), usb_timeout)) {
131
   while (!USB_Configuration && PENDING(millis(), usb_timeout)) {
132
     delay(50);
132
     delay(50);
133
-    idletask();
133
+    HAL_idletask();
134
     #if PIN_EXISTS(LED)
134
     #if PIN_EXISTS(LED)
135
       TOGGLE(LED_PIN);     // Flash quickly during USB initialization
135
       TOGGLE(LED_PIN);     // Flash quickly during USB initialization
136
     #endif
136
     #endif
142
 }
142
 }
143
 
143
 
144
 // HAL idle task
144
 // HAL idle task
145
-void MarlinHAL::idletask() {
145
+void HAL_idletask() {
146
   #if HAS_SHARED_MEDIA
146
   #if HAS_SHARED_MEDIA
147
     // If Marlin is using the SD card we need to lock it to prevent access from
147
     // If Marlin is using the SD card we need to lock it to prevent access from
148
     // a PC via USB.
148
     // a PC via USB.

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

170
   }
170
   }
171
 }
171
 }
172
 
172
 
173
-#define HAL_timer_isr_epilogue(T) NOOP
173
+#define HAL_timer_isr_epilogue(T)

+ 65
- 107
Marlin/src/HAL/NATIVE_SIM/HAL.h View File

21
  */
21
  */
22
 #pragma once
22
 #pragma once
23
 
23
 
24
+#define CPU_32_BIT
25
+#define HAL_IDLETASK
26
+void HAL_idletask();
27
+
28
+#define F_CPU 100000000
29
+#define SystemCoreClock F_CPU
24
 #include <stdint.h>
30
 #include <stdint.h>
25
 #include <stdarg.h>
31
 #include <stdarg.h>
32
+
26
 #undef min
33
 #undef min
27
 #undef max
34
 #undef max
35
+
28
 #include <algorithm>
36
 #include <algorithm>
29
 #include "pinmapping.h"
37
 #include "pinmapping.h"
30
 
38
 
32
 void _putc(uint8_t c);
40
 void _putc(uint8_t c);
33
 uint8_t _getc();
41
 uint8_t _getc();
34
 
42
 
43
+//extern "C" volatile uint32_t _millis;
44
+
35
 //arduino: Print.h
45
 //arduino: Print.h
36
 #define DEC 10
46
 #define DEC 10
37
 #define HEX 16
47
 #define HEX 16
48
 #include "watchdog.h"
58
 #include "watchdog.h"
49
 #include "serial.h"
59
 #include "serial.h"
50
 
60
 
51
-// ------------------------
52
-// Defines
53
-// ------------------------
54
-
55
-#define CPU_32_BIT
56
-#define SHARED_SERVOS HAS_SERVOS  // Use shared/servos.cpp
57
-
58
-#define F_CPU 100000000
59
-#define SystemCoreClock F_CPU
60
-
61
-#define CPU_ST7920_DELAY_1 600
62
-#define CPU_ST7920_DELAY_2 750
63
-#define CPU_ST7920_DELAY_3 750
64
-
65
-// ------------------------
66
-// Serial ports
67
-// ------------------------
61
+#define SHARED_SERVOS HAS_SERVOS
68
 
62
 
69
 extern MSerialT serial_stream_0;
63
 extern MSerialT serial_stream_0;
70
 extern MSerialT serial_stream_1;
64
 extern MSerialT serial_stream_1;
104
   #endif
98
   #endif
105
 #endif
99
 #endif
106
 
100
 
107
-// ------------------------
108
-// Interrupts
109
-// ------------------------
110
 
101
 
102
+#define CPU_ST7920_DELAY_1 600
103
+#define CPU_ST7920_DELAY_2 750
104
+#define CPU_ST7920_DELAY_3 750
105
+
106
+//
107
+// Interrupts
108
+//
111
 #define CRITICAL_SECTION_START()
109
 #define CRITICAL_SECTION_START()
112
 #define CRITICAL_SECTION_END()
110
 #define CRITICAL_SECTION_END()
111
+#define ISRS_ENABLED()
112
+#define ENABLE_ISRS()
113
+#define DISABLE_ISRS()
113
 
114
 
114
-// ------------------------
115
-// ADC
116
-// ------------------------
115
+inline void HAL_init() {}
116
+
117
+// Utility functions
118
+#pragma GCC diagnostic push
119
+#pragma GCC diagnostic ignored "-Wunused-function"
120
+int freeMemory();
121
+#pragma GCC diagnostic pop
117
 
122
 
123
+// ADC
118
 #define HAL_ADC_VREF           5.0
124
 #define HAL_ADC_VREF           5.0
119
 #define HAL_ADC_RESOLUTION    10
125
 #define HAL_ADC_RESOLUTION    10
126
+#define HAL_ANALOG_SELECT(ch) HAL_adc_enable_channel(ch)
127
+#define HAL_START_ADC(ch)     HAL_adc_start_conversion(ch)
128
+#define HAL_READ_ADC()        HAL_adc_get_result()
129
+#define HAL_ADC_READY()       true
130
+
131
+void HAL_adc_init();
132
+void HAL_adc_enable_channel(const uint8_t ch);
133
+void HAL_adc_start_conversion(const uint8_t ch);
134
+uint16_t HAL_adc_get_result();
135
+
136
+// PWM
137
+inline void set_pwm_duty(const pin_t pin, const uint16_t v, const uint16_t=255, const bool=false) { analogWrite(pin, v); }
138
+
139
+// Reset source
140
+inline void HAL_clear_reset_source(void) {}
141
+inline uint8_t HAL_get_reset_source(void) { return RST_POWER_ON; }
142
+
143
+void HAL_reboot();
120
 
144
 
121
 /* ---------------- Delay in cycles */
145
 /* ---------------- Delay in cycles */
122
 
146
 
135
   // https://github.com/gcc-mirror/gcc/blob/5c7634a0e5f202935aa6c11b6ea953b8bf80a00a/libstdc%2B%2B-v3/include/bits/char_traits.h#L329
159
   // https://github.com/gcc-mirror/gcc/blob/5c7634a0e5f202935aa6c11b6ea953b8bf80a00a/libstdc%2B%2B-v3/include/bits/char_traits.h#L329
136
   if (str != nullptr) {
160
   if (str != nullptr) {
137
     std::size_t i = 0;
161
     std::size_t i = 0;
138
-    while (str[i] != '\0') ++i;
162
+    while (str[i] != '\0') {
163
+      ++i;
164
+    }
165
+
139
     return i;
166
     return i;
140
   }
167
   }
168
+
141
   return 0;
169
   return 0;
142
 }
170
 }
143
 
171
 
144
 constexpr inline int strncmp_constexpr(const char* lhs, const char* rhs, std::size_t count) {
172
 constexpr inline int strncmp_constexpr(const char* lhs, const char* rhs, std::size_t count) {
145
   // https://github.com/gcc-mirror/gcc/blob/13b9cbfc32fe3ac4c81c4dd9c42d141c8fb95db4/libstdc%2B%2B-v3/include/bits/char_traits.h#L655
173
   // https://github.com/gcc-mirror/gcc/blob/13b9cbfc32fe3ac4c81c4dd9c42d141c8fb95db4/libstdc%2B%2B-v3/include/bits/char_traits.h#L655
146
-  if (lhs == nullptr || rhs == nullptr)
174
+  if (lhs == nullptr || rhs == nullptr) {
147
     return rhs != nullptr ? -1 : 1;
175
     return rhs != nullptr ? -1 : 1;
176
+  }
148
 
177
 
149
-  for (std::size_t i = 0; i < count; ++i)
178
+  for (std::size_t i = 0; i < count; ++i) {
150
     if (lhs[i] != rhs[i]) {
179
     if (lhs[i] != rhs[i]) {
151
       return lhs[i] < rhs[i] ? -1 : 1;
180
       return lhs[i] < rhs[i] ? -1 : 1;
152
-    else if (lhs[i] == '\0')
181
+    } else if (lhs[i] == '\0') {
153
       return 0;
182
       return 0;
183
+    }
184
+  }
154
 
185
 
155
   return 0;
186
   return 0;
156
 }
187
 }
162
     do {
193
     do {
163
       char sc = {};
194
       char sc = {};
164
       do {
195
       do {
165
-        if ((sc = *str++) == '\0') return nullptr;
196
+        if ((sc = *str++) == '\0') {
197
+          return nullptr;
198
+        }
166
       } while (sc != c);
199
       } while (sc != c);
167
     } while (strncmp_constexpr(str, target, len) != 0);
200
     } while (strncmp_constexpr(str, target, len) != 0);
168
     --str;
201
     --str;
169
   }
202
   }
203
+
170
   return str;
204
   return str;
171
 }
205
 }
172
 
206
 
177
     do {
211
     do {
178
       char sc = {};
212
       char sc = {};
179
       do {
213
       do {
180
-        if ((sc = *str++) == '\0') return nullptr;
214
+        if ((sc = *str++) == '\0') {
215
+          return nullptr;
216
+        }
181
       } while (sc != c);
217
       } while (sc != c);
182
     } while (strncmp_constexpr(str, target, len) != 0);
218
     } while (strncmp_constexpr(str, target, len) != 0);
183
     --str;
219
     --str;
184
   }
220
   }
185
   return str;
221
   return str;
186
 }
222
 }
187
-
188
-// ------------------------
189
-// Class Utilities
190
-// ------------------------
191
-
192
-#pragma GCC diagnostic push
193
-#if GCC_VERSION <= 50000
194
-  #pragma GCC diagnostic ignored "-Wunused-function"
195
-#endif
196
-
197
-int freeMemory();
198
-
199
-#pragma GCC diagnostic pop
200
-
201
-// ------------------------
202
-// MarlinHAL Class
203
-// ------------------------
204
-
205
-class MarlinHAL {
206
-public:
207
-
208
-  // Earliest possible init, before setup()
209
-  MarlinHAL() {}
210
-
211
-  static inline void init() {}        // Called early in setup()
212
-  static inline void init_board() {}  // Called less early in setup()
213
-  static void reboot();               // Restart the firmware from 0x0
214
-
215
-  static inline bool isr_state() { return true; }
216
-  static inline void isr_on()  {}
217
-  static inline void isr_off() {}
218
-
219
-  static inline void delay_ms(const int ms) { _delay_ms(ms); }
220
-
221
-  // Tasks, called from idle()
222
-  static void idletask();
223
-
224
-  // Reset
225
-  static constexpr uint8_t reset_reason = RST_POWER_ON;
226
-  static inline uint8_t get_reset_source() { return reset_reason; }
227
-  static inline void clear_reset_source() {}
228
-
229
-  // Free SRAM
230
-  static inline int freeMemory() { return ::freeMemory(); }
231
-
232
-  //
233
-  // ADC Methods
234
-  //
235
-
236
-  static uint8_t active_ch;
237
-
238
-  // Called by Temperature::init once at startup
239
-  static void adc_init();
240
-
241
-  // Called by Temperature::init for each sensor at startup
242
-  static void adc_enable(const uint8_t ch);
243
-
244
-  // Begin ADC sampling on the given channel
245
-  static void adc_start(const uint8_t ch);
246
-
247
-  // Is the ADC ready for reading?
248
-  static bool adc_ready();
249
-
250
-  // The current value of the ADC register
251
-  static uint16_t adc_value();
252
-
253
-  /**
254
-   * Set the PWM duty cycle for the pin to the given value.
255
-   * No option to invert the duty cycle [default = false]
256
-   * No option to change the scale of the provided value to enable finer PWM duty control [default = 255]
257
-   */
258
-  static inline void set_pwm_duty(const pin_t pin, const uint16_t v, const uint16_t=255, const bool=false) {
259
-    analogWrite(pin, v);
260
-  }
261
-
262
-};
263
-
264
-extern MarlinHAL hal;

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

87
 void HAL_timer_disable_interrupt(const uint8_t timer_num);
87
 void HAL_timer_disable_interrupt(const uint8_t timer_num);
88
 bool HAL_timer_interrupt_enabled(const uint8_t timer_num);
88
 bool HAL_timer_interrupt_enabled(const uint8_t timer_num);
89
 
89
 
90
-#define HAL_timer_isr_prologue(T) NOOP
91
-#define HAL_timer_isr_epilogue(T) NOOP
90
+#define HAL_timer_isr_prologue(T)
91
+#define HAL_timer_isr_epilogue(T)

+ 17
- 9
Marlin/src/HAL/SAMD51/HAL.cpp View File

106
 // Private Variables
106
 // Private Variables
107
 // ------------------------
107
 // ------------------------
108
 
108
 
109
-uint16_t MarlinHAL::adc_result;
109
+uint16_t HAL_adc_result;
110
 
110
 
111
 #if ADC_IS_REQUIRED
111
 #if ADC_IS_REQUIRED
112
 
112
 
402
 // ------------------------
402
 // ------------------------
403
 
403
 
404
 // HAL initialization task
404
 // HAL initialization task
405
-void MarlinHAL::init() {
405
+void HAL_init() {
406
   TERN_(DMA_IS_REQUIRED, dma_init());
406
   TERN_(DMA_IS_REQUIRED, dma_init());
407
   #if ENABLED(SDSUPPORT)
407
   #if ENABLED(SDSUPPORT)
408
     #if SD_CONNECTION_IS(ONBOARD) && PIN_EXISTS(SD_DETECT)
408
     #if SD_CONNECTION_IS(ONBOARD) && PIN_EXISTS(SD_DETECT)
412
   #endif
412
   #endif
413
 }
413
 }
414
 
414
 
415
+// HAL idle task
416
+/*
417
+void HAL_idletask() {
418
+}
419
+*/
420
+
421
+void HAL_clear_reset_source() { }
422
+
415
 #pragma push_macro("WDT")
423
 #pragma push_macro("WDT")
416
 #undef WDT    // Required to be able to use '.bit.WDT'. Compiler wrongly replace struct field with WDT define
424
 #undef WDT    // Required to be able to use '.bit.WDT'. Compiler wrongly replace struct field with WDT define
417
-uint8_t MarlinHAL::get_reset_source() {
425
+uint8_t HAL_get_reset_source() {
418
   RSTC_RCAUSE_Type resetCause;
426
   RSTC_RCAUSE_Type resetCause;
419
 
427
 
420
   resetCause.reg = REG_RSTC_RCAUSE;
428
   resetCause.reg = REG_RSTC_RCAUSE;
428
 }
436
 }
429
 #pragma pop_macro("WDT")
437
 #pragma pop_macro("WDT")
430
 
438
 
431
-void MarlinHAL::reboot() { NVIC_SystemReset(); }
439
+void HAL_reboot() { NVIC_SystemReset(); }
432
 
440
 
433
 extern "C" {
441
 extern "C" {
434
   void * _sbrk(int incr);
442
   void * _sbrk(int incr);
446
 // ADC
454
 // ADC
447
 // ------------------------
455
 // ------------------------
448
 
456
 
449
-void MarlinHAL::adc_init() {
457
+void HAL_adc_init() {
450
   #if ADC_IS_REQUIRED
458
   #if ADC_IS_REQUIRED
451
     memset(HAL_adc_results, 0xFF, sizeof(HAL_adc_results));                 // Fill result with invalid values
459
     memset(HAL_adc_results, 0xFF, sizeof(HAL_adc_results));                 // Fill result with invalid values
452
 
460
 
483
   #endif // ADC_IS_REQUIRED
491
   #endif // ADC_IS_REQUIRED
484
 }
492
 }
485
 
493
 
486
-void MarlinHAL::adc_start(const pin_t pin) {
494
+void HAL_adc_start_conversion(const uint8_t adc_pin) {
487
   #if ADC_IS_REQUIRED
495
   #if ADC_IS_REQUIRED
488
     LOOP_L_N(pi, COUNT(adc_pins)) {
496
     LOOP_L_N(pi, COUNT(adc_pins)) {
489
-      if (pin == adc_pins[pi]) {
490
-        adc_result = HAL_adc_results[pi];
497
+      if (adc_pin == adc_pins[pi]) {
498
+        HAL_adc_result = HAL_adc_results[pi];
491
         return;
499
         return;
492
       }
500
       }
493
     }
501
     }
494
   #endif
502
   #endif
495
 
503
 
496
-  adc_result = 0xFFFF;
504
+  HAL_adc_result = 0xFFFF;
497
 }
505
 }
498
 
506
 
499
 #endif // __SAMD51__
507
 #endif // __SAMD51__

+ 46
- 81
Marlin/src/HAL/SAMD51/HAL.h View File

89
 
89
 
90
 typedef int8_t pin_t;
90
 typedef int8_t pin_t;
91
 
91
 
92
-#define SHARED_SERVOS HAS_SERVOS  // Use shared/servos.cpp
93
-class Servo;
94
-typedef Servo hal_servo_t;
92
+#define SHARED_SERVOS HAS_SERVOS
93
+#define HAL_SERVO_LIB Servo
95
 
94
 
96
 //
95
 //
97
 // Interrupts
96
 // Interrupts
98
 //
97
 //
99
-#define CRITICAL_SECTION_START()  const bool irqon = !__get_PRIMASK(); __disable_irq()
100
-#define CRITICAL_SECTION_END()    if (irqon) __enable_irq()
98
+#define CRITICAL_SECTION_START()  uint32_t primask = __get_PRIMASK(); __disable_irq()
99
+#define CRITICAL_SECTION_END()    if (!primask) __enable_irq()
100
+#define ISRS_ENABLED() (!__get_PRIMASK())
101
+#define ENABLE_ISRS()  __enable_irq()
102
+#define DISABLE_ISRS() __disable_irq()
101
 
103
 
102
-#define cli() __disable_irq() // Disable interrupts
103
-#define sei() __enable_irq()  // Enable interrupts
104
+#define cli() __disable_irq()       // Disable interrupts
105
+#define sei() __enable_irq()        // Enable interrupts
106
+
107
+void HAL_clear_reset_source();  // clear reset reason
108
+uint8_t HAL_get_reset_source(); // get reset reason
109
+
110
+void HAL_reboot();
104
 
111
 
105
 //
112
 //
106
 // ADC
113
 // ADC
107
 //
114
 //
115
+extern uint16_t HAL_adc_result;     // Most recent ADC conversion
116
+
117
+#define HAL_ANALOG_SELECT(pin)
118
+
119
+void HAL_adc_init();
108
 
120
 
109
 //#define HAL_ADC_FILTERED          // Disable Marlin's oversampling. The HAL filters ADC values.
121
 //#define HAL_ADC_FILTERED          // Disable Marlin's oversampling. The HAL filters ADC values.
110
 #define HAL_ADC_VREF         3.3
122
 #define HAL_ADC_VREF         3.3
111
 #define HAL_ADC_RESOLUTION  10      // ... 12
123
 #define HAL_ADC_RESOLUTION  10      // ... 12
124
+#define HAL_START_ADC(pin)  HAL_adc_start_conversion(pin)
125
+#define HAL_READ_ADC()      HAL_adc_result
126
+#define HAL_ADC_READY()     true
127
+
128
+void HAL_adc_start_conversion(const uint8_t adc_pin);
112
 
129
 
113
 //
130
 //
114
-// Pin Mapping for M42, M43, M226
131
+// PWM
132
+//
133
+inline void set_pwm_duty(const pin_t pin, const uint16_t v, const uint16_t=255, const bool=false) { analogWrite(pin, v); }
134
+
135
+//
136
+// Pin Map
115
 //
137
 //
116
 #define GET_PIN_MAP_PIN(index) index
138
 #define GET_PIN_MAP_PIN(index) index
117
 #define GET_PIN_MAP_INDEX(pin) pin
139
 #define GET_PIN_MAP_INDEX(pin) pin
120
 //
142
 //
121
 // Tone
143
 // Tone
122
 //
144
 //
145
+void toneInit();
123
 void tone(const pin_t _pin, const unsigned int frequency, const unsigned long duration=0);
146
 void tone(const pin_t _pin, const unsigned int frequency, const unsigned long duration=0);
124
 void noTone(const pin_t _pin);
147
 void noTone(const pin_t _pin);
125
 
148
 
126
-// ------------------------
127
-// Class Utilities
128
-// ------------------------
149
+// Enable hooks into idle and setup for HAL
150
+void HAL_init();
151
+/*
152
+#define HAL_IDLETASK 1
153
+void HAL_idletask();
154
+*/
155
+
156
+//
157
+// Utility functions
158
+//
159
+FORCE_INLINE void _delay_ms(const int delay_ms) { delay(delay_ms); }
129
 
160
 
130
 #pragma GCC diagnostic push
161
 #pragma GCC diagnostic push
131
 #if GCC_VERSION <= 50000
162
 #if GCC_VERSION <= 50000
132
   #pragma GCC diagnostic ignored "-Wunused-function"
163
   #pragma GCC diagnostic ignored "-Wunused-function"
133
 #endif
164
 #endif
134
 
165
 
166
+int freeMemory();
167
+
168
+#pragma GCC diagnostic pop
169
+
135
 #ifdef __cplusplus
170
 #ifdef __cplusplus
136
   extern "C" {
171
   extern "C" {
137
 #endif
172
 #endif
138
-
139
 char *dtostrf(double __val, signed char __width, unsigned char __prec, char *__s);
173
 char *dtostrf(double __val, signed char __width, unsigned char __prec, char *__s);
140
-
141
-extern "C" int freeMemory();
142
-
143
 #ifdef __cplusplus
174
 #ifdef __cplusplus
144
   }
175
   }
145
 #endif
176
 #endif
146
-
147
-#pragma GCC diagnostic pop
148
-
149
-// ------------------------
150
-// MarlinHAL Class
151
-// ------------------------
152
-
153
-class MarlinHAL {
154
-public:
155
-
156
-  // Earliest possible init, before setup()
157
-  MarlinHAL() {}
158
-
159
-  static void init();                 // Called early in setup()
160
-  static inline void init_board() {}  // Called less early in setup()
161
-  static void reboot();               // Restart the firmware from 0x0
162
-
163
-  static inline bool isr_state() { return !__get_PRIMASK(); }
164
-  static inline void isr_on()  { sei(); }
165
-  static inline void isr_off() { cli(); }
166
-
167
-  static inline void delay_ms(const int ms) { delay(ms); }
168
-
169
-  // Tasks, called from idle()
170
-  static inline void idletask() {}
171
-
172
-  // Reset
173
-  static uint8_t get_reset_source();
174
-  static inline void clear_reset_source() {}
175
-
176
-  // Free SRAM
177
-  static inline int freeMemory() { return ::freeMemory(); }
178
-
179
-  //
180
-  // ADC Methods
181
-  //
182
-
183
-  static uint16_t adc_result;
184
-
185
-  // Called by Temperature::init once at startup
186
-  static void adc_init();
187
-
188
-  // Called by Temperature::init for each sensor at startup
189
-  static inline void adc_enable(const uint8_t ch) {}
190
-
191
-  // Begin ADC sampling on the given channel
192
-  static void adc_start(const pin_t pin);
193
-
194
-  // Is the ADC ready for reading?
195
-  static inline bool adc_ready() { return true; }
196
-
197
-  // The current value of the ADC register
198
-  static uint16_t adc_value() { return adc_result; }
199
-
200
-  /**
201
-   * Set the PWM duty cycle for the pin to the given value.
202
-   * No option to invert the duty cycle [default = false]
203
-   * No option to change the scale of the provided value to enable finer PWM duty control [default = 255]
204
-   */
205
-  static inline void set_pwm_duty(const pin_t pin, const uint16_t v, const uint16_t v_size=255, const bool invert=false) {
206
-    analogWrite(pin, v);
207
-  }
208
-
209
-};
210
-
211
-extern MarlinHAL hal;

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

53
 // Public Variables
53
 // Public Variables
54
 // ------------------------
54
 // ------------------------
55
 
55
 
56
-uint16_t MarlinHAL::adc_result;
56
+uint16_t HAL_adc_result;
57
 
57
 
58
 // ------------------------
58
 // ------------------------
59
 // Public functions
59
 // Public functions
60
 // ------------------------
60
 // ------------------------
61
 
61
 
62
-#if ENABLED(POSTMORTEM_DEBUGGING)
63
-  extern void install_min_serial();
64
-#endif
62
+TERN_(POSTMORTEM_DEBUGGING, extern void install_min_serial());
65
 
63
 
66
 // HAL initialization task
64
 // HAL initialization task
67
-void MarlinHAL::init() {
65
+void HAL_init() {
68
   // Ensure F_CPU is a constant expression.
66
   // Ensure F_CPU is a constant expression.
69
   // If the compiler breaks here, it means that delay code that should compute at compile time will not work.
67
   // If the compiler breaks here, it means that delay code that should compute at compile time will not work.
70
   // So better safe than sorry here.
68
   // So better safe than sorry here.
105
 }
103
 }
106
 
104
 
107
 // HAL idle task
105
 // HAL idle task
108
-void MarlinHAL::idletask() {
106
+void HAL_idletask() {
109
   #if HAS_SHARED_MEDIA
107
   #if HAS_SHARED_MEDIA
110
     // Stm32duino currently doesn't have a "loop/idle" method
108
     // Stm32duino currently doesn't have a "loop/idle" method
111
     CDC_resume_receive();
109
     CDC_resume_receive();
113
   #endif
111
   #endif
114
 }
112
 }
115
 
113
 
116
-void MarlinHAL::reboot() { NVIC_SystemReset(); }
114
+void HAL_clear_reset_source() { __HAL_RCC_CLEAR_RESET_FLAGS(); }
117
 
115
 
118
-uint8_t MarlinHAL::get_reset_source() {
116
+uint8_t HAL_get_reset_source() {
119
   return
117
   return
120
     #ifdef RCC_FLAG_IWDGRST // Some sources may not exist...
118
     #ifdef RCC_FLAG_IWDGRST // Some sources may not exist...
121
       RESET != __HAL_RCC_GET_FLAG(RCC_FLAG_IWDGRST)  ? RST_WATCHDOG :
119
       RESET != __HAL_RCC_GET_FLAG(RCC_FLAG_IWDGRST)  ? RST_WATCHDOG :
139
   ;
137
   ;
140
 }
138
 }
141
 
139
 
142
-void MarlinHAL::clear_reset_source() { __HAL_RCC_CLEAR_RESET_FLAGS(); }
140
+void HAL_reboot() { NVIC_SystemReset(); }
141
+
142
+void _delay_ms(const int delay_ms) { delay(delay_ms); }
143
 
143
 
144
 extern "C" {
144
 extern "C" {
145
   extern unsigned int _ebss; // end of bss section
145
   extern unsigned int _ebss; // end of bss section
146
 }
146
 }
147
 
147
 
148
+// ------------------------
149
+// ADC
150
+// ------------------------
151
+
152
+// TODO: Make sure this doesn't cause any delay
153
+void HAL_adc_start_conversion(const uint8_t adc_pin) { HAL_adc_result = analogRead(adc_pin); }
154
+uint16_t HAL_adc_get_result() { return HAL_adc_result; }
155
+
148
 // Reset the system to initiate a firmware flash
156
 // Reset the system to initiate a firmware flash
149
-WEAK void flashFirmware(const int16_t) { hal.reboot(); }
157
+WEAK void flashFirmware(const int16_t) { HAL_reboot(); }
150
 
158
 
151
 // Maple Compatibility
159
 // Maple Compatibility
152
 volatile uint32_t systick_uptime_millis = 0;
160
 volatile uint32_t systick_uptime_millis = 0;

+ 76
- 101
Marlin/src/HAL/STM32/HAL.h View File

44
 #define CPU_ST7920_DELAY_2  40
44
 #define CPU_ST7920_DELAY_2  40
45
 #define CPU_ST7920_DELAY_3 340
45
 #define CPU_ST7920_DELAY_3 340
46
 
46
 
47
-// ------------------------
48
-// Serial ports
49
-// ------------------------
47
+//
48
+// Serial Ports
49
+//
50
 #ifdef USBCON
50
 #ifdef USBCON
51
   #include <USBSerial.h>
51
   #include <USBSerial.h>
52
   #include "../../core/serial_hook.h"
52
   #include "../../core/serial_hook.h"
115
   #define analogInputToDigitalPin(p) (p)
115
   #define analogInputToDigitalPin(p) (p)
116
 #endif
116
 #endif
117
 
117
 
118
-//
119
-// Interrupts
120
-//
121
-#define CRITICAL_SECTION_START()  const bool irqon = !__get_PRIMASK(); __disable_irq()
122
-#define CRITICAL_SECTION_END()    if (irqon) __enable_irq()
118
+#define CRITICAL_SECTION_START()  uint32_t primask = __get_PRIMASK(); __disable_irq()
119
+#define CRITICAL_SECTION_END()    if (!primask) __enable_irq()
120
+#define ISRS_ENABLED() (!__get_PRIMASK())
121
+#define ENABLE_ISRS()  __enable_irq()
122
+#define DISABLE_ISRS() __disable_irq()
123
 #define cli() __disable_irq()
123
 #define cli() __disable_irq()
124
 #define sei() __enable_irq()
124
 #define sei() __enable_irq()
125
 
125
 
126
+// On AVR this is in math.h?
127
+#define square(x) ((x)*(x))
128
+
126
 // ------------------------
129
 // ------------------------
127
 // Types
130
 // Types
128
 // ------------------------
131
 // ------------------------
133
   typedef int16_t pin_t;
136
   typedef int16_t pin_t;
134
 #endif
137
 #endif
135
 
138
 
136
-class libServo;
137
-typedef libServo hal_servo_t;
139
+#define HAL_SERVO_LIB libServo
138
 #define PAUSE_SERVO_OUTPUT() libServo::pause_all_servos()
140
 #define PAUSE_SERVO_OUTPUT() libServo::pause_all_servos()
139
 #define RESUME_SERVO_OUTPUT() libServo::resume_all_servos()
141
 #define RESUME_SERVO_OUTPUT() libServo::resume_all_servos()
140
 
142
 
141
 // ------------------------
143
 // ------------------------
142
-// ADC
144
+// Public Variables
143
 // ------------------------
145
 // ------------------------
144
 
146
 
145
-#ifdef ADC_RESOLUTION
146
-  #define HAL_ADC_RESOLUTION ADC_RESOLUTION
147
-#else
148
-  #define HAL_ADC_RESOLUTION 12
149
-#endif
150
-
151
-#define HAL_ADC_VREF         3.3
147
+// result of last ADC conversion
148
+extern uint16_t HAL_adc_result;
152
 
149
 
153
-//
154
-// Pin Mapping for M42, M43, M226
155
-//
156
-#define GET_PIN_MAP_PIN(index) index
157
-#define GET_PIN_MAP_INDEX(pin) pin
158
-#define PARSED_PIN_INDEX(code, dval) parser.intval(code, dval)
150
+// ------------------------
151
+// Public functions
152
+// ------------------------
159
 
153
 
160
-#ifdef STM32F1xx
161
-  #define JTAG_DISABLE() AFIO_DBGAFR_CONFIG(AFIO_MAPR_SWJ_CFG_JTAGDISABLE)
162
-  #define JTAGSWD_DISABLE() AFIO_DBGAFR_CONFIG(AFIO_MAPR_SWJ_CFG_DISABLE)
163
-  #define JTAGSWD_RESET() AFIO_DBGAFR_CONFIG(AFIO_MAPR_SWJ_CFG_RESET); // Reset: FULL SWD+JTAG
164
-#endif
154
+// Memory related
155
+#define __bss_end __bss_end__
165
 
156
 
166
-#define PLATFORM_M997_SUPPORT
167
-void flashFirmware(const int16_t);
157
+// Enable hooks into  setup for HAL
158
+void HAL_init();
159
+#define HAL_IDLETASK 1
160
+void HAL_idletask();
168
 
161
 
169
-// Maple Compatibility
170
-typedef void (*systickCallback_t)(void);
171
-void systick_attach_callback(systickCallback_t cb);
172
-void HAL_SYSTICK_Callback();
162
+// Clear reset reason
163
+void HAL_clear_reset_source();
173
 
164
 
174
-extern volatile uint32_t systick_uptime_millis;
165
+// Reset reason
166
+uint8_t HAL_get_reset_source();
175
 
167
 
176
-#define HAL_CAN_SET_PWM_FREQ   // This HAL supports PWM Frequency adjustment
168
+void HAL_reboot();
177
 
169
 
178
-// ------------------------
179
-// Class Utilities
180
-// ------------------------
181
-
182
-// Memory related
183
-#define __bss_end __bss_end__
170
+void _delay_ms(const int delay);
184
 
171
 
185
 extern "C" char* _sbrk(int incr);
172
 extern "C" char* _sbrk(int incr);
186
 
173
 
187
 #pragma GCC diagnostic push
174
 #pragma GCC diagnostic push
188
-#if GCC_VERSION <= 50000
189
-  #pragma GCC diagnostic ignored "-Wunused-function"
190
-#endif
175
+#pragma GCC diagnostic ignored "-Wunused-function"
191
 
176
 
192
 static inline int freeMemory() {
177
 static inline int freeMemory() {
193
   volatile char top;
178
   volatile char top;
196
 
181
 
197
 #pragma GCC diagnostic pop
182
 #pragma GCC diagnostic pop
198
 
183
 
199
-// ------------------------
200
-// MarlinHAL Class
201
-// ------------------------
202
-
203
-class MarlinHAL {
204
-public:
205
-
206
-  // Earliest possible init, before setup()
207
-  MarlinHAL() {}
208
-
209
-  static void init();                 // Called early in setup()
210
-  static inline void init_board() {}  // Called less early in setup()
211
-  static void reboot();               // Restart the firmware from 0x0
212
-
213
-  static inline bool isr_state() { return !__get_PRIMASK(); }
214
-  static inline void isr_on()  { sei(); }
215
-  static inline void isr_off() { cli(); }
216
-
217
-  static inline void delay_ms(const int ms) { delay(ms); }
184
+//
185
+// ADC
186
+//
218
 
187
 
219
-  // Tasks, called from idle()
220
-  static void idletask();
188
+#define HAL_ANALOG_SELECT(pin) pinMode(pin, INPUT)
221
 
189
 
222
-  // Reset
223
-  static uint8_t get_reset_source();
224
-  static void clear_reset_source();
190
+#ifdef ADC_RESOLUTION
191
+  #define HAL_ADC_RESOLUTION ADC_RESOLUTION
192
+#else
193
+  #define HAL_ADC_RESOLUTION 12
194
+#endif
225
 
195
 
226
-  // Free SRAM
227
-  static inline int freeMemory() { return ::freeMemory(); }
196
+#define HAL_ADC_VREF         3.3
197
+#define HAL_START_ADC(pin)  HAL_adc_start_conversion(pin)
198
+#define HAL_READ_ADC()      HAL_adc_result
199
+#define HAL_ADC_READY()     true
228
 
200
 
229
-  //
230
-  // ADC Methods
231
-  //
201
+inline void HAL_adc_init() { analogReadResolution(HAL_ADC_RESOLUTION); }
232
 
202
 
233
-  static uint16_t adc_result;
203
+void HAL_adc_start_conversion(const uint8_t adc_pin);
234
 
204
 
235
-  // Called by Temperature::init once at startup
236
-  static inline void adc_init() {
237
-    analogReadResolution(HAL_ADC_RESOLUTION);
238
-  }
205
+uint16_t HAL_adc_get_result();
239
 
206
 
240
-  // Called by Temperature::init for each sensor at startup
241
-  static inline void adc_enable(const pin_t pin) { pinMode(pin, INPUT); }
207
+#define GET_PIN_MAP_PIN(index) index
208
+#define GET_PIN_MAP_INDEX(pin) pin
209
+#define PARSED_PIN_INDEX(code, dval) parser.intval(code, dval)
242
 
210
 
243
-  // Begin ADC sampling on the given channel
244
-  static void adc_start(const pin_t pin) { adc_result = analogRead(pin); }
211
+#ifdef STM32F1xx
212
+  #define JTAG_DISABLE() AFIO_DBGAFR_CONFIG(AFIO_MAPR_SWJ_CFG_JTAGDISABLE)
213
+  #define JTAGSWD_DISABLE() AFIO_DBGAFR_CONFIG(AFIO_MAPR_SWJ_CFG_DISABLE)
214
+  #define JTAGSWD_RESET() AFIO_DBGAFR_CONFIG(AFIO_MAPR_SWJ_CFG_RESET); // Reset: FULL SWD+JTAG
215
+#endif
245
 
216
 
246
-  // Is the ADC ready for reading?
247
-  static inline bool adc_ready() { return true; }
217
+#define PLATFORM_M997_SUPPORT
218
+void flashFirmware(const int16_t);
248
 
219
 
249
-  // The current value of the ADC register
250
-  static uint16_t adc_value() { return adc_result; }
220
+// Maple Compatibility
221
+typedef void (*systickCallback_t)(void);
222
+void systick_attach_callback(systickCallback_t cb);
223
+void HAL_SYSTICK_Callback();
251
 
224
 
252
-  /**
253
-   * Set the PWM duty cycle for the pin to the given value.
254
-   * Optionally invert the duty cycle [default = false]
255
-   * Optionally change the maximum size of the provided value to enable finer PWM duty control [default = 255]
256
-   */
257
-  static void set_pwm_duty(const pin_t pin, const uint16_t v, const uint16_t v_size=255, const bool invert=false);
225
+extern volatile uint32_t systick_uptime_millis;
258
 
226
 
259
-  /**
260
-   * Set the frequency of the timer for the given pin.
261
-   * All Timer PWM pins run at the same frequency.
262
-   */
263
-  static void set_pwm_frequency(const pin_t pin, int f_desired);
227
+#define HAL_CAN_SET_PWM_FREQ   // This HAL supports PWM Frequency adjustment
264
 
228
 
265
-};
229
+/**
230
+ * set_pwm_frequency
231
+ *  Set the frequency of the timer corresponding to the provided pin
232
+ *  All Timer PWM pins run at the same frequency
233
+ */
234
+void set_pwm_frequency(const pin_t pin, int f_desired);
266
 
235
 
267
-extern MarlinHAL hal;
236
+/**
237
+ * set_pwm_duty
238
+ *  Set the PWM duty cycle of the provided pin to the provided value
239
+ *  Optionally allows inverting the duty cycle [default = false]
240
+ *  Optionally allows changing the maximum size of the provided value to enable finer PWM duty control [default = 255]
241
+ */
242
+void set_pwm_duty(const pin_t pin, const uint16_t v, const uint16_t v_size=255, const bool invert=false);

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

102
 
102
 
103
   // Soft SPI receive byte
103
   // Soft SPI receive byte
104
   uint8_t spiRec() {
104
   uint8_t spiRec() {
105
-    hal.isr_off();                                                // No interrupts during byte receive
105
+    DISABLE_ISRS();                                               // No interrupts during byte receive
106
     const uint8_t data = HAL_SPI_STM32_SpiTransfer_Mode_3(0xFF);
106
     const uint8_t data = HAL_SPI_STM32_SpiTransfer_Mode_3(0xFF);
107
-    hal.isr_on();                                                 // Enable interrupts
107
+    ENABLE_ISRS();                                                // Enable interrupts
108
     return data;
108
     return data;
109
   }
109
   }
110
 
110
 
116
 
116
 
117
   // Soft SPI send byte
117
   // Soft SPI send byte
118
   void spiSend(uint8_t data) {
118
   void spiSend(uint8_t data) {
119
-    hal.isr_off();                          // No interrupts during byte send
119
+    DISABLE_ISRS();                         // No interrupts during byte send
120
     HAL_SPI_STM32_SpiTransfer_Mode_3(data); // Don't care what is received
120
     HAL_SPI_STM32_SpiTransfer_Mode_3(data); // Don't care what is received
121
-    hal.isr_on();                           // Enable interrupts
121
+    ENABLE_ISRS();                          // Enable interrupts
122
   }
122
   }
123
 
123
 
124
   // Soft SPI send block
124
   // Soft SPI send block

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

174
         UNLOCK_FLASH();
174
         UNLOCK_FLASH();
175
 
175
 
176
         TERN_(HAS_PAUSE_SERVO_OUTPUT, PAUSE_SERVO_OUTPUT());
176
         TERN_(HAS_PAUSE_SERVO_OUTPUT, PAUSE_SERVO_OUTPUT());
177
-        hal.isr_off();
177
+        DISABLE_ISRS();
178
         status = HAL_FLASHEx_Erase(&EraseInitStruct, &SectorError);
178
         status = HAL_FLASHEx_Erase(&EraseInitStruct, &SectorError);
179
-        hal.isr_on();
179
+        ENABLE_ISRS();
180
         TERN_(HAS_PAUSE_SERVO_OUTPUT, RESUME_SERVO_OUTPUT());
180
         TERN_(HAS_PAUSE_SERVO_OUTPUT, RESUME_SERVO_OUTPUT());
181
         if (status != HAL_OK) {
181
         if (status != HAL_OK) {
182
           DEBUG_ECHOLNPGM("HAL_FLASHEx_Erase=", status);
182
           DEBUG_ECHOLNPGM("HAL_FLASHEx_Erase=", status);
229
       // output. Servo output still glitches with interrupts disabled, but recovers after the
229
       // output. Servo output still glitches with interrupts disabled, but recovers after the
230
       // erase.
230
       // erase.
231
       TERN_(HAS_PAUSE_SERVO_OUTPUT, PAUSE_SERVO_OUTPUT());
231
       TERN_(HAS_PAUSE_SERVO_OUTPUT, PAUSE_SERVO_OUTPUT());
232
-      hal.isr_off();
232
+      DISABLE_ISRS();
233
       eeprom_buffer_flush();
233
       eeprom_buffer_flush();
234
-      hal.isr_on();
234
+      ENABLE_ISRS();
235
       TERN_(HAS_PAUSE_SERVO_OUTPUT, RESUME_SERVO_OUTPUT());
235
       TERN_(HAS_PAUSE_SERVO_OUTPUT, RESUME_SERVO_OUTPUT());
236
 
236
 
237
       eeprom_data_written = false;
237
       eeprom_data_written = false;

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

29
 // Array to support sticky frequency sets per timer
29
 // Array to support sticky frequency sets per timer
30
 static uint16_t timer_freq[TIMER_NUM];
30
 static uint16_t timer_freq[TIMER_NUM];
31
 
31
 
32
-void MarlinHAL::set_pwm_duty(const pin_t pin, const uint16_t v, const uint16_t v_size/*=255*/, const bool invert/*=false*/) {
32
+void set_pwm_duty(const pin_t pin, const uint16_t v, const uint16_t v_size/*=255*/, const bool invert/*=false*/) {
33
   if (!PWM_PIN(pin)) return; // Don't proceed if no hardware timer
33
   if (!PWM_PIN(pin)) return; // Don't proceed if no hardware timer
34
   const PinName pin_name = digitalPinToPinName(pin);
34
   const PinName pin_name = digitalPinToPinName(pin);
35
   TIM_TypeDef * const Instance = (TIM_TypeDef *)pinmap_peripheral(pin_name, PinMap_PWM);
35
   TIM_TypeDef * const Instance = (TIM_TypeDef *)pinmap_peripheral(pin_name, PinMap_PWM);
56
   if (previousMode != TIMER_OUTPUT_COMPARE_PWM1) HT->resume();
56
   if (previousMode != TIMER_OUTPUT_COMPARE_PWM1) HT->resume();
57
 }
57
 }
58
 
58
 
59
-void MarlinHAL::set_pwm_frequency(const pin_t pin, int f_desired) {
59
+void set_pwm_frequency(const pin_t pin, int f_desired) {
60
   if (!PWM_PIN(pin)) return; // Don't proceed if no hardware timer
60
   if (!PWM_PIN(pin)) return; // Don't proceed if no hardware timer
61
   const PinName pin_name = digitalPinToPinName(pin);
61
   const PinName pin_name = digitalPinToPinName(pin);
62
   TIM_TypeDef * const Instance = (TIM_TypeDef *)pinmap_peripheral(pin_name, PinMap_PWM); // Get HAL timer instance
62
   TIM_TypeDef * const Instance = (TIM_TypeDef *)pinmap_peripheral(pin_name, PinMap_PWM); // Get HAL timer instance

+ 1
- 5
Marlin/src/HAL/STM32/pinsDebug.h View File

115
 #define PRINT_PIN_ANALOG(p) do{ sprintf_P(buffer, PSTR(" (A%2d)  "), DIGITAL_PIN_TO_ANALOG_PIN(pin)); SERIAL_ECHO(buffer); }while(0)
115
 #define PRINT_PIN_ANALOG(p) do{ sprintf_P(buffer, PSTR(" (A%2d)  "), DIGITAL_PIN_TO_ANALOG_PIN(pin)); SERIAL_ECHO(buffer); }while(0)
116
 #define PRINT_PORT(ANUM) port_print(ANUM)
116
 #define PRINT_PORT(ANUM) port_print(ANUM)
117
 #define DIGITAL_PIN_TO_ANALOG_PIN(ANUM) -1  // will report analog pin number in the print port routine
117
 #define DIGITAL_PIN_TO_ANALOG_PIN(ANUM) -1  // will report analog pin number in the print port routine
118
+#define GET_PIN_MAP_PIN_M43(Index) pin_xref[Index].Ard_num
118
 
119
 
119
 // x is a variable used to search pin_array
120
 // x is a variable used to search pin_array
120
 #define GET_ARRAY_IS_DIGITAL(x) ((bool) pin_array[x].is_digital)
121
 #define GET_ARRAY_IS_DIGITAL(x) ((bool) pin_array[x].is_digital)
122
 #define PRINT_ARRAY_NAME(x) do{ sprintf_P(buffer, PSTR("%-" STRINGIFY(MAX_NAME_LENGTH) "s"), pin_array[x].name); SERIAL_ECHO(buffer); }while(0)
123
 #define PRINT_ARRAY_NAME(x) do{ sprintf_P(buffer, PSTR("%-" STRINGIFY(MAX_NAME_LENGTH) "s"), pin_array[x].name); SERIAL_ECHO(buffer); }while(0)
123
 #define MULTI_NAME_PAD 33 // space needed to be pretty if not first name assigned to a pin
124
 #define MULTI_NAME_PAD 33 // space needed to be pretty if not first name assigned to a pin
124
 
125
 
125
-//
126
-// Pin Mapping for M43
127
-//
128
-#define GET_PIN_MAP_PIN_M43(Index) pin_xref[Index].Ard_num
129
-
130
 #ifndef M43_NEVER_TOUCH
126
 #ifndef M43_NEVER_TOUCH
131
   #define _M43_NEVER_TOUCH(Index) (Index >= 9 && Index <= 12) // SERIAL/USB pins: PA9(TX) PA10(RX) PA11(USB_DM) PA12(USB_DP)
127
   #define _M43_NEVER_TOUCH(Index) (Index >= 9 && Index <= 12) // SERIAL/USB pins: PA9(TX) PA10(RX) PA11(USB_DM) PA12(USB_DP)
132
   #ifdef KILL_PIN
128
   #ifdef KILL_PIN

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

116
   }
116
   }
117
 }
117
 }
118
 
118
 
119
-#define HAL_timer_isr_prologue(T) NOOP
120
-#define HAL_timer_isr_epilogue(T) NOOP
119
+#define HAL_timer_isr_prologue(T)
120
+#define HAL_timer_isr_epilogue(T)

+ 99
- 91
Marlin/src/HAL/STM32F1/HAL.cpp View File

79
 #define SCB_AIRCR_PRIGROUP_Msk             (7UL << SCB_AIRCR_PRIGROUP_Pos)                /*!< SCB AIRCR: PRIGROUP Mask */
79
 #define SCB_AIRCR_PRIGROUP_Msk             (7UL << SCB_AIRCR_PRIGROUP_Pos)                /*!< SCB AIRCR: PRIGROUP Mask */
80
 
80
 
81
 // ------------------------
81
 // ------------------------
82
-// Serial ports
82
+// Public Variables
83
 // ------------------------
83
 // ------------------------
84
 
84
 
85
 #if defined(SERIAL_USB) && !HAS_SD_HOST_DRIVE
85
 #if defined(SERIAL_USB) && !HAS_SD_HOST_DRIVE
112
   #endif
112
   #endif
113
 #endif
113
 #endif
114
 
114
 
115
+uint16_t HAL_adc_result;
116
+
115
 // ------------------------
117
 // ------------------------
116
-// ADC
118
+// Private Variables
117
 // ------------------------
119
 // ------------------------
120
+STM32ADC adc(ADC1);
118
 
121
 
119
-uint16_t analogRead(pin_t pin) {
120
-  const bool is_analog = _GET_MODE(pin) == GPIO_INPUT_ANALOG;
121
-  return is_analog ? analogRead(uint8_t(pin)) : 0;
122
-}
123
-
124
-// Wrapper to maple unprotected analogWrite
125
-void analogWrite(pin_t pin, int pwm_val8) {
126
-  if (PWM_PIN(pin)) analogWrite(uint8_t(pin), pwm_val8);
127
-}
128
-
129
-uint16_t MarlinHAL::adc_result;
122
+const uint8_t adc_pins[] = {
123
+  #if HAS_TEMP_ADC_0
124
+    TEMP_0_PIN,
125
+  #endif
126
+  #if HAS_TEMP_ADC_PROBE
127
+    TEMP_PROBE_PIN,
128
+  #endif
129
+  #if HAS_HEATED_BED
130
+    TEMP_BED_PIN,
131
+  #endif
132
+  #if HAS_TEMP_CHAMBER
133
+    TEMP_CHAMBER_PIN,
134
+  #endif
135
+  #if HAS_TEMP_COOLER
136
+    TEMP_COOLER_PIN,
137
+  #endif
138
+  #if HAS_TEMP_ADC_1
139
+    TEMP_1_PIN,
140
+  #endif
141
+  #if HAS_TEMP_ADC_2
142
+    TEMP_2_PIN,
143
+  #endif
144
+  #if HAS_TEMP_ADC_3
145
+    TEMP_3_PIN,
146
+  #endif
147
+  #if HAS_TEMP_ADC_4
148
+    TEMP_4_PIN,
149
+  #endif
150
+  #if HAS_TEMP_ADC_5
151
+    TEMP_5_PIN,
152
+  #endif
153
+  #if HAS_TEMP_ADC_6
154
+    TEMP_6_PIN,
155
+  #endif
156
+  #if HAS_TEMP_ADC_7
157
+    TEMP_7_PIN,
158
+  #endif
159
+  #if ENABLED(FILAMENT_WIDTH_SENSOR)
160
+    FILWIDTH_PIN,
161
+  #endif
162
+  #if HAS_ADC_BUTTONS
163
+    ADC_KEYPAD_PIN,
164
+  #endif
165
+  #if HAS_JOY_ADC_X
166
+    JOY_X_PIN,
167
+  #endif
168
+  #if HAS_JOY_ADC_Y
169
+    JOY_Y_PIN,
170
+  #endif
171
+  #if HAS_JOY_ADC_Z
172
+    JOY_Z_PIN,
173
+  #endif
174
+  #if ENABLED(POWER_MONITOR_CURRENT)
175
+    POWER_MONITOR_CURRENT_PIN,
176
+  #endif
177
+  #if ENABLED(POWER_MONITOR_VOLTAGE)
178
+    POWER_MONITOR_VOLTAGE_PIN,
179
+  #endif
180
+};
130
 
181
 
131
 enum TempPinIndex : char {
182
 enum TempPinIndex : char {
132
   #if HAS_TEMP_ADC_0
183
   #if HAS_TEMP_ADC_0
194
 // ------------------------
245
 // ------------------------
195
 // Private functions
246
 // Private functions
196
 // ------------------------
247
 // ------------------------
197
-
198
 static void NVIC_SetPriorityGrouping(uint32_t PriorityGroup) {
248
 static void NVIC_SetPriorityGrouping(uint32_t PriorityGroup) {
199
   uint32_t reg_value;
249
   uint32_t reg_value;
200
-  uint32_t PriorityGroupTmp = (PriorityGroup & (uint32_t)0x07);               // only values 0..7 are used
250
+  uint32_t PriorityGroupTmp = (PriorityGroup & (uint32_t)0x07);               /* only values 0..7 are used          */
201
 
251
 
202
-  reg_value  =  SCB->AIRCR;                                                   // read old register configuration
203
-  reg_value &= ~(SCB_AIRCR_VECTKEY_Msk | SCB_AIRCR_PRIGROUP_Msk);             // clear bits to change
252
+  reg_value  =  SCB->AIRCR;                                                   /* read old register configuration    */
253
+  reg_value &= ~(SCB_AIRCR_VECTKEY_Msk | SCB_AIRCR_PRIGROUP_Msk);             /* clear bits to change               */
204
   reg_value  =  (reg_value                                 |
254
   reg_value  =  (reg_value                                 |
205
                 ((uint32_t)0x5FA << SCB_AIRCR_VECTKEY_Pos) |
255
                 ((uint32_t)0x5FA << SCB_AIRCR_VECTKEY_Pos) |
206
-                (PriorityGroupTmp << 8));                                     // Insert write key & priority group
256
+                (PriorityGroupTmp << 8));                                     /* Insert write key & priority group  */
207
   SCB->AIRCR =  reg_value;
257
   SCB->AIRCR =  reg_value;
208
 }
258
 }
209
 
259
 
211
 // Public functions
261
 // Public functions
212
 // ------------------------
262
 // ------------------------
213
 
263
 
214
-void flashFirmware(const int16_t) { hal.reboot(); }
215
-
216
 //
264
 //
217
 // Leave PA11/PA12 intact if USBSerial is not used
265
 // Leave PA11/PA12 intact if USBSerial is not used
218
 //
266
 //
232
 
280
 
233
 TERN_(POSTMORTEM_DEBUGGING, extern void install_min_serial());
281
 TERN_(POSTMORTEM_DEBUGGING, extern void install_min_serial());
234
 
282
 
235
-// ------------------------
236
-// MarlinHAL class
237
-// ------------------------
238
-
239
-void MarlinHAL::init() {
283
+void HAL_init() {
240
   NVIC_SetPriorityGrouping(0x3);
284
   NVIC_SetPriorityGrouping(0x3);
241
   #if PIN_EXISTS(LED)
285
   #if PIN_EXISTS(LED)
242
     OUT_WRITE(LED_PIN, LOW);
286
     OUT_WRITE(LED_PIN, LOW);
255
 }
299
 }
256
 
300
 
257
 // HAL idle task
301
 // HAL idle task
258
-void MarlinHAL::idletask() {
302
+void HAL_idletask() {
259
   #if HAS_SHARED_MEDIA
303
   #if HAS_SHARED_MEDIA
260
     // If Marlin is using the SD card we need to lock it to prevent access from
304
     // If Marlin is using the SD card we need to lock it to prevent access from
261
     // a PC via USB.
305
     // a PC via USB.
270
   #endif
314
   #endif
271
 }
315
 }
272
 
316
 
273
-void MarlinHAL::reboot() { nvic_sys_reset(); }
317
+void HAL_clear_reset_source() { }
318
+
319
+/**
320
+ * TODO: Check this and change or remove.
321
+ */
322
+uint8_t HAL_get_reset_source() { return RST_POWER_ON; }
323
+
324
+void _delay_ms(const int delay_ms) { delay(delay_ms); }
274
 
325
 
275
 extern "C" {
326
 extern "C" {
276
   extern unsigned int _ebss; // end of bss section
327
   extern unsigned int _ebss; // end of bss section
304
 }
355
 }
305
 */
356
 */
306
 
357
 
358
+// ------------------------
307
 // ADC
359
 // ADC
308
-
360
+// ------------------------
309
 // Init the AD in continuous capture mode
361
 // Init the AD in continuous capture mode
310
-void MarlinHAL::adc_init() {
311
-  static const uint8_t adc_pins[] = {
312
-    #if HAS_TEMP_ADC_0
313
-      TEMP_0_PIN,
314
-    #endif
315
-    #if HAS_TEMP_ADC_PROBE
316
-      TEMP_PROBE_PIN,
317
-    #endif
318
-    #if HAS_HEATED_BED
319
-      TEMP_BED_PIN,
320
-    #endif
321
-    #if HAS_TEMP_CHAMBER
322
-      TEMP_CHAMBER_PIN,
323
-    #endif
324
-    #if HAS_TEMP_COOLER
325
-      TEMP_COOLER_PIN,
326
-    #endif
327
-    #if HAS_TEMP_ADC_1
328
-      TEMP_1_PIN,
329
-    #endif
330
-    #if HAS_TEMP_ADC_2
331
-      TEMP_2_PIN,
332
-    #endif
333
-    #if HAS_TEMP_ADC_3
334
-      TEMP_3_PIN,
335
-    #endif
336
-    #if HAS_TEMP_ADC_4
337
-      TEMP_4_PIN,
338
-    #endif
339
-    #if HAS_TEMP_ADC_5
340
-      TEMP_5_PIN,
341
-    #endif
342
-    #if HAS_TEMP_ADC_6
343
-      TEMP_6_PIN,
344
-    #endif
345
-    #if HAS_TEMP_ADC_7
346
-      TEMP_7_PIN,
347
-    #endif
348
-    #if ENABLED(FILAMENT_WIDTH_SENSOR)
349
-      FILWIDTH_PIN,
350
-    #endif
351
-    #if HAS_ADC_BUTTONS
352
-      ADC_KEYPAD_PIN,
353
-    #endif
354
-    #if HAS_JOY_ADC_X
355
-      JOY_X_PIN,
356
-    #endif
357
-    #if HAS_JOY_ADC_Y
358
-      JOY_Y_PIN,
359
-    #endif
360
-    #if HAS_JOY_ADC_Z
361
-      JOY_Z_PIN,
362
-    #endif
363
-    #if ENABLED(POWER_MONITOR_CURRENT)
364
-      POWER_MONITOR_CURRENT_PIN,
365
-    #endif
366
-    #if ENABLED(POWER_MONITOR_VOLTAGE)
367
-      POWER_MONITOR_VOLTAGE_PIN,
368
-    #endif
369
-  };
370
-  static STM32ADC adc(ADC1);
362
+void HAL_adc_init() {
371
   // configure the ADC
363
   // configure the ADC
372
   adc.calibrate();
364
   adc.calibrate();
373
   #if F_CPU > 72000000
365
   #if F_CPU > 72000000
382
   adc.startConversion();
374
   adc.startConversion();
383
 }
375
 }
384
 
376
 
385
-void MarlinHAL::adc_start(const pin_t pin) {
377
+void HAL_adc_start_conversion(const uint8_t adc_pin) {
386
   //TEMP_PINS pin_index;
378
   //TEMP_PINS pin_index;
387
   TempPinIndex pin_index;
379
   TempPinIndex pin_index;
388
-  switch (pin) {
380
+  switch (adc_pin) {
389
     default: return;
381
     default: return;
390
     #if HAS_TEMP_ADC_0
382
     #if HAS_TEMP_ADC_0
391
       case TEMP_0_PIN: pin_index = TEMP_0; break;
383
       case TEMP_0_PIN: pin_index = TEMP_0; break;
448
   HAL_adc_result = HAL_adc_results[(int)pin_index] >> (12 - HAL_ADC_RESOLUTION); // shift out unused bits
440
   HAL_adc_result = HAL_adc_results[(int)pin_index] >> (12 - HAL_ADC_RESOLUTION); // shift out unused bits
449
 }
441
 }
450
 
442
 
443
+uint16_t HAL_adc_get_result() { return HAL_adc_result; }
444
+
445
+uint16_t analogRead(pin_t pin) {
446
+  const bool is_analog = _GET_MODE(pin) == GPIO_INPUT_ANALOG;
447
+  return is_analog ? analogRead(uint8_t(pin)) : 0;
448
+}
449
+
450
+// Wrapper to maple unprotected analogWrite
451
+void analogWrite(pin_t pin, int pwm_val8) {
452
+  if (PWM_PIN(pin)) analogWrite(uint8_t(pin), pwm_val8);
453
+}
454
+
455
+void HAL_reboot() { nvic_sys_reset(); }
456
+
457
+void flashFirmware(const int16_t) { HAL_reboot(); }
458
+
451
 #endif // __STM32F1__
459
 #endif // __STM32F1__

+ 80
- 104
Marlin/src/HAL/STM32F1/HAL.h View File

66
   #endif
66
   #endif
67
 #endif
67
 #endif
68
 
68
 
69
-// ------------------------
70
-// Serial ports
71
-// ------------------------
72
-
73
 #ifdef SERIAL_USB
69
 #ifdef SERIAL_USB
74
   typedef ForwardSerial1Class< USBSerial > DefaultSerial1;
70
   typedef ForwardSerial1Class< USBSerial > DefaultSerial1;
75
   extern DefaultSerial1 MSerial0;
71
   extern DefaultSerial1 MSerial0;
145
   #endif
141
   #endif
146
 #endif
142
 #endif
147
 
143
 
144
+// Set interrupt grouping for this MCU
145
+void HAL_init();
146
+#define HAL_IDLETASK 1
147
+void HAL_idletask();
148
+
148
 /**
149
 /**
149
  * TODO: review this to return 1 for pins that are not analog input
150
  * TODO: review this to return 1 for pins that are not analog input
150
  */
151
  */
157
   #define NO_COMPILE_TIME_PWM
158
   #define NO_COMPILE_TIME_PWM
158
 #endif
159
 #endif
159
 
160
 
160
-// Reset Reason
161
+#define CRITICAL_SECTION_START()  uint32_t primask = __get_primask(); (void)__iCliRetVal()
162
+#define CRITICAL_SECTION_END()    if (!primask) (void)__iSeiRetVal()
163
+#define ISRS_ENABLED() (!__get_primask())
164
+#define ENABLE_ISRS()  ((void)__iSeiRetVal())
165
+#define DISABLE_ISRS() ((void)__iCliRetVal())
166
+
167
+// On AVR this is in math.h?
168
+#define square(x) ((x)*(x))
169
+
161
 #define RST_POWER_ON   1
170
 #define RST_POWER_ON   1
162
 #define RST_EXTERNAL   2
171
 #define RST_EXTERNAL   2
163
 #define RST_BROWN_OUT  4
172
 #define RST_BROWN_OUT  4
172
 
181
 
173
 typedef int8_t pin_t;
182
 typedef int8_t pin_t;
174
 
183
 
175
-// Result of last ADC conversion
176
-extern uint16_t HAL_adc_result;
177
-
178
 // ------------------------
184
 // ------------------------
179
-// Interrupts
185
+// Public Variables
180
 // ------------------------
186
 // ------------------------
181
 
187
 
182
-#define CRITICAL_SECTION_START()  const bool irqon = !__get_primask(); (void)__iCliRetVal()
183
-#define CRITICAL_SECTION_END()    if (!primask) (void)__iSeiRetVal()
184
-#define cli() noInterrupts()
185
-#define sei() interrupts()
188
+// Result of last ADC conversion
189
+extern uint16_t HAL_adc_result;
186
 
190
 
187
 // ------------------------
191
 // ------------------------
188
-// ADC
192
+// Public functions
189
 // ------------------------
193
 // ------------------------
190
 
194
 
191
-#ifdef ADC_RESOLUTION
192
-  #define HAL_ADC_RESOLUTION ADC_RESOLUTION
193
-#else
194
-  #define HAL_ADC_RESOLUTION 12
195
-#endif
196
-
197
-#define HAL_ADC_VREF         3.3
195
+// Disable interrupts
196
+#define cli() noInterrupts()
198
 
197
 
199
-uint16_t analogRead(pin_t pin); // need HAL_ANALOG_SELECT() first
200
-void analogWrite(pin_t pin, int pwm_val8); // PWM only! mul by 257 in maple!?
198
+// Enable interrupts
199
+#define sei() interrupts()
201
 
200
 
202
-//
203
-// Pin Mapping for M42, M43, M226
204
-//
205
-#define GET_PIN_MAP_PIN(index) index
206
-#define GET_PIN_MAP_INDEX(pin) pin
207
-#define PARSED_PIN_INDEX(code, dval) parser.intval(code, dval)
201
+// Memory related
202
+#define __bss_end __bss_end__
208
 
203
 
209
-#define JTAG_DISABLE()    afio_cfg_debug_ports(AFIO_DEBUG_SW_ONLY)
210
-#define JTAGSWD_DISABLE() afio_cfg_debug_ports(AFIO_DEBUG_NONE)
204
+// Clear reset reason
205
+void HAL_clear_reset_source();
211
 
206
 
212
-#define PLATFORM_M997_SUPPORT
213
-void flashFirmware(const int16_t);
207
+// Reset reason
208
+uint8_t HAL_get_reset_source();
214
 
209
 
215
-#define HAL_CAN_SET_PWM_FREQ      // This HAL supports PWM Frequency adjustment
216
-#ifndef PWM_FREQUENCY
217
-  #define PWM_FREQUENCY      1000 // Default PWM Frequency
218
-#endif
210
+void HAL_reboot();
219
 
211
 
220
-// ------------------------
221
-// Class Utilities
222
-// ------------------------
212
+void _delay_ms(const int delay);
223
 
213
 
224
-// Memory related
225
-#define __bss_end __bss_end__
214
+#pragma GCC diagnostic push
215
+#pragma GCC diagnostic ignored "-Wunused-function"
226
 
216
 
227
-void _delay_ms(const int ms);
217
+/*
218
+extern "C" {
219
+  int freeMemory();
220
+}
221
+*/
228
 
222
 
229
 extern "C" char* _sbrk(int incr);
223
 extern "C" char* _sbrk(int incr);
230
 
224
 
231
-#pragma GCC diagnostic push
232
-#if GCC_VERSION <= 50000
233
-  #pragma GCC diagnostic ignored "-Wunused-function"
234
-#endif
235
-
236
 static inline int freeMemory() {
225
 static inline int freeMemory() {
237
   volatile char top;
226
   volatile char top;
238
   return &top - _sbrk(0);
227
   return &top - _sbrk(0);
240
 
229
 
241
 #pragma GCC diagnostic pop
230
 #pragma GCC diagnostic pop
242
 
231
 
243
-// ------------------------
244
-// MarlinHAL Class
245
-// ------------------------
246
-
247
-class MarlinHAL {
248
-public:
249
-
250
-  // Earliest possible init, before setup()
251
-  MarlinHAL() {}
252
-
253
-  static void init();                 // Called early in setup()
254
-  static inline void init_board() {}  // Called less early in setup()
255
-  static void reboot();               // Restart the firmware from 0x0
256
-
257
-  static inline bool isr_state() { return !__get_primask(); }
258
-  static inline void isr_on()  { ((void)__iSeiRetVal()); }
259
-  static inline void isr_off() { ((void)__iCliRetVal()); }
260
-
261
-  static inline void delay_ms(const int ms) { delay(ms); }
262
-
263
-  // Tasks, called from idle()
264
-  static void idletask();
265
-
266
-  // Reset
267
-  static inline uint8_t get_reset_source() { return RST_POWER_ON; }
268
-  static inline void clear_reset_source() {}
232
+//
233
+// ADC
234
+//
269
 
235
 
270
-  // Free SRAM
271
-  static inline int freeMemory() { return ::freeMemory(); }
236
+#define HAL_ANALOG_SELECT(pin) pinMode(pin, INPUT_ANALOG);
272
 
237
 
273
-  //
274
-  // ADC Methods
275
-  //
238
+void HAL_adc_init();
276
 
239
 
277
-  static uint16_t adc_result;
240
+#ifdef ADC_RESOLUTION
241
+  #define HAL_ADC_RESOLUTION ADC_RESOLUTION
242
+#else
243
+  #define HAL_ADC_RESOLUTION 12
244
+#endif
278
 
245
 
279
-  // Called by Temperature::init once at startup
280
-  static void adc_init();
246
+#define HAL_ADC_VREF         3.3
247
+#define HAL_START_ADC(pin)  HAL_adc_start_conversion(pin)
248
+#define HAL_READ_ADC()      HAL_adc_result
249
+#define HAL_ADC_READY()     true
281
 
250
 
282
-  // Called by Temperature::init for each sensor at startup
283
-  static inline void adc_enable(const pin_t pin) { pinMode(pin, INPUT_ANALOG); }
251
+void HAL_adc_start_conversion(const uint8_t adc_pin);
252
+uint16_t HAL_adc_get_result();
284
 
253
 
285
-  // Begin ADC sampling on the given channel
286
-  static void adc_start(const pin_t pin);
254
+uint16_t analogRead(pin_t pin); // need HAL_ANALOG_SELECT() first
255
+void analogWrite(pin_t pin, int pwm_val8); // PWM only! mul by 257 in maple!?
287
 
256
 
288
-  // Is the ADC ready for reading?
289
-  static inline bool adc_ready() { return true; }
257
+#define GET_PIN_MAP_PIN(index) index
258
+#define GET_PIN_MAP_INDEX(pin) pin
259
+#define PARSED_PIN_INDEX(code, dval) parser.intval(code, dval)
290
 
260
 
291
-  // The current value of the ADC register
292
-  static uint16_t adc_value() { return adc_result; }
261
+#define JTAG_DISABLE() afio_cfg_debug_ports(AFIO_DEBUG_SW_ONLY)
262
+#define JTAGSWD_DISABLE() afio_cfg_debug_ports(AFIO_DEBUG_NONE)
293
 
263
 
294
-  /**
295
-   * Set the PWM duty cycle for the pin to the given value.
296
-   * Optionally invert the duty cycle [default = false]
297
-   * Optionally change the maximum size of the provided value to enable finer PWM duty control [default = 255]
298
-   * The timer must be pre-configured with set_pwm_frequency() if the default frequency is not desired.
299
-   */
300
-  static inline void set_pwm_duty(const pin_t pin, const uint16_t v, const uint16_t=255, const bool=false);
264
+#define PLATFORM_M997_SUPPORT
265
+void flashFirmware(const int16_t);
301
 
266
 
302
-  /**
303
-   * Set the frequency of the timer for the given pin.
304
-   * All Timer PWM pins run at the same frequency.
305
-   */
306
-  static void set_pwm_frequency(const pin_t pin, int f_desired);
267
+#ifndef PWM_FREQUENCY
268
+  #define PWM_FREQUENCY      1000 // Default PWM Frequency
269
+#endif
270
+#define HAL_CAN_SET_PWM_FREQ      // This HAL supports PWM Frequency adjustment
307
 
271
 
308
-};
272
+/**
273
+ * set_pwm_frequency
274
+ *  Set the frequency of the timer corresponding to the provided pin
275
+ *  All Timer PWM pins run at the same frequency
276
+ */
277
+void set_pwm_frequency(const pin_t pin, int f_desired);
309
 
278
 
310
-extern MarlinHAL hal;
279
+/**
280
+ * set_pwm_duty
281
+ *  Set the PWM duty cycle of the provided pin to the provided value
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]
284
+ *  The timer must be pre-configured with set_pwm_frequency() if the default frequency is not desired.
285
+ */
286
+void set_pwm_duty(const pin_t pin, const uint16_t v, const uint16_t v_size=255, const bool invert=false);

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

35
 #define SERVO_DEFAULT_MIN_ANGLE         0
35
 #define SERVO_DEFAULT_MIN_ANGLE         0
36
 #define SERVO_DEFAULT_MAX_ANGLE         180
36
 #define SERVO_DEFAULT_MAX_ANGLE         180
37
 
37
 
38
-class libServo;
39
-typedef libServo hal_servo_t;
38
+#define HAL_SERVO_LIB libServo
40
 
39
 
41
 class libServo {
40
 class libServo {
42
   public:
41
   public:

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

21
  */
21
  */
22
 #ifdef __STM32F1__
22
 #ifdef __STM32F1__
23
 
23
 
24
-#include "../../inc/MarlinConfig.h"
24
+#include "../../inc/MarlinConfigPre.h"
25
 
25
 
26
 #include <pwm.h>
26
 #include <pwm.h>
27
+#include "HAL.h"
28
+#include "timers.h"
27
 
29
 
28
 #define NR_TIMERS TERN(STM32_XL_DENSITY, 14, 8) // Maple timers, 14 for STM32_XL_DENSITY (F/G chips), 8 for HIGH density (C D E)
30
 #define NR_TIMERS TERN(STM32_XL_DENSITY, 14, 8) // Maple timers, 14 for STM32_XL_DENSITY (F/G chips), 8 for HIGH density (C D E)
29
 
31
 
36
   return 0;
38
   return 0;
37
 }
39
 }
38
 
40
 
39
-void MarlinHAL::set_pwm_duty(const pin_t pin, const uint16_t v, const uint16_t v_size/*=255*/, const bool invert/*=false*/) {
41
+void set_pwm_duty(const pin_t pin, const uint16_t v, const uint16_t v_size/*=255*/, const bool invert/*=false*/) {
40
   if (!PWM_PIN(pin)) return;
42
   if (!PWM_PIN(pin)) return;
41
 
43
 
42
   timer_dev *timer; UNUSED(timer);
44
   timer_dev *timer; UNUSED(timer);
49
   timer_set_mode(timer, channel, TIMER_PWM); // PWM Output Mode
51
   timer_set_mode(timer, channel, TIMER_PWM); // PWM Output Mode
50
 }
52
 }
51
 
53
 
52
-void MarlinHAL::set_pwm_frequency(const pin_t pin, int f_desired) {
54
+void set_pwm_frequency(const pin_t pin, int f_desired) {
53
   if (!PWM_PIN(pin)) return;                    // Don't proceed if no hardware timer
55
   if (!PWM_PIN(pin)) return;                    // Don't proceed if no hardware timer
54
 
56
 
55
   timer_dev *timer; UNUSED(timer);
57
   timer_dev *timer; UNUSED(timer);

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

188
   }
188
   }
189
 }
189
 }
190
 
190
 
191
-#define HAL_timer_isr_epilogue(T) NOOP
191
+#define HAL_timer_isr_epilogue(T)
192
 
192
 
193
 // No command is available in framework to turn off ARPE bit, which is turned on by default in libmaple.
193
 // No command is available in framework to turn off ARPE bit, which is turned on by default in libmaple.
194
 // Needed here to reset ARPE=0 for stepper timer
194
 // Needed here to reset ARPE=0 for stepper timer

+ 38
- 41
Marlin/src/HAL/TEENSY31_32/HAL.cpp View File

31
 
31
 
32
 #include <Wire.h>
32
 #include <Wire.h>
33
 
33
 
34
-// ------------------------
35
-// Serial ports
36
-// ------------------------
37
-
38
 #define _IMPLEMENT_SERIAL(X) DefaultSerial##X MSerial##X(false, Serial##X)
34
 #define _IMPLEMENT_SERIAL(X) DefaultSerial##X MSerial##X(false, Serial##X)
39
 #define IMPLEMENT_SERIAL(X)  _IMPLEMENT_SERIAL(X)
35
 #define IMPLEMENT_SERIAL(X)  _IMPLEMENT_SERIAL(X)
40
 #if WITHIN(SERIAL_PORT, 0, 3)
36
 #if WITHIN(SERIAL_PORT, 0, 3)
44
 #endif
40
 #endif
45
 USBSerialType USBSerial(false, SerialUSB);
41
 USBSerialType USBSerial(false, SerialUSB);
46
 
42
 
47
-// ------------------------
48
-// Class Utilities
49
-// ------------------------
43
+uint16_t HAL_adc_result;
50
 
44
 
51
-extern "C" {
52
-  extern char __bss_end;
53
-  extern char __heap_start;
54
-  extern void* __brkval;
45
+static const uint8_t pin2sc1a[] = {
46
+    5, 14, 8, 9, 13, 12, 6, 7, 15, 4, 0, 19, 3, 31, // 0-13, we treat them as A0-A13
47
+    5, 14, 8, 9, 13, 12, 6, 7, 15, 4, // 14-23 (A0-A9)
48
+    31, 31, 31, 31, 31, 31, 31, 31, 31, 31, // 24-33
49
+    0+64, 19+64, 3+64, 31+64, // 34-37 (A10-A13)
50
+    26, 22, 23, 27, 29, 30 // 38-43: temp. sensor, VREF_OUT, A14, bandgap, VREFH, VREFL. A14 isn't connected to anything in Teensy 3.0.
51
+};
55
 
52
 
56
-  int freeMemory() {
57
-    int free_memory;
58
-    if ((int)__brkval == 0)
59
-      free_memory = ((int)&free_memory) - ((int)&__bss_end);
60
-    else
61
-      free_memory = ((int)&free_memory) - ((int)__brkval);
62
-    return free_memory;
63
-  }
64
-}
53
+/*
54
+  // disable interrupts
55
+  void cli() { noInterrupts(); }
65
 
56
 
66
-// ------------------------
67
-// MarlinHAL Class
68
-// ------------------------
57
+  // enable interrupts
58
+  void sei() { interrupts(); }
59
+*/
60
+
61
+void HAL_adc_init() {
62
+  analog_init();
63
+  while (ADC0_SC3 & ADC_SC3_CAL) {}; // Wait for calibration to finish
64
+  NVIC_ENABLE_IRQ(IRQ_FTM1);
65
+}
69
 
66
 
70
-void MarlinHAL::reboot() { _reboot_Teensyduino_(); }
67
+void HAL_clear_reset_source() { }
71
 
68
 
72
-uint8_t MarlinHAL::get_reset_source() {
69
+uint8_t HAL_get_reset_source() {
73
   switch (RCM_SRS0) {
70
   switch (RCM_SRS0) {
74
     case 128: return RST_POWER_ON; break;
71
     case 128: return RST_POWER_ON; break;
75
     case 64: return RST_EXTERNAL; break;
72
     case 64: return RST_EXTERNAL; break;
81
   return 0;
78
   return 0;
82
 }
79
 }
83
 
80
 
84
-// ADC
81
+void HAL_reboot() { _reboot_Teensyduino_(); }
85
 
82
 
86
-void MarlinHAL::adc_init() {
87
-  analog_init();
88
-  while (ADC0_SC3 & ADC_SC3_CAL) {}; // Wait for calibration to finish
89
-  NVIC_ENABLE_IRQ(IRQ_FTM1);
90
-}
83
+extern "C" {
84
+  extern char __bss_end;
85
+  extern char __heap_start;
86
+  extern void* __brkval;
91
 
87
 
92
-void MarlinHAL::adc_start(const pin_t pin) {
93
-  static const uint8_t pin2sc1a[] = {
94
-      5, 14, 8, 9, 13, 12, 6, 7, 15, 4, 0, 19, 3, 31, // 0-13, we treat them as A0-A13
95
-      5, 14, 8, 9, 13, 12, 6, 7, 15, 4, // 14-23 (A0-A9)
96
-      31, 31, 31, 31, 31, 31, 31, 31, 31, 31, // 24-33
97
-      0+64, 19+64, 3+64, 31+64, // 34-37 (A10-A13)
98
-      26, 22, 23, 27, 29, 30 // 38-43: temp. sensor, VREF_OUT, A14, bandgap, VREFH, VREFL. A14 isn't connected to anything in Teensy 3.0.
99
-  };
100
-  ADC0_SC1A = pin2sc1a[pin];
88
+  int freeMemory() {
89
+    int free_memory;
90
+    if ((int)__brkval == 0)
91
+      free_memory = ((int)&free_memory) - ((int)&__bss_end);
92
+    else
93
+      free_memory = ((int)&free_memory) - ((int)__brkval);
94
+    return free_memory;
95
+  }
101
 }
96
 }
102
 
97
 
103
-uint16_t MarlinHAL::adc_value() { return ADC0_RA; }
98
+void HAL_adc_start_conversion(const uint8_t adc_pin) { ADC0_SC1A = pin2sc1a[adc_pin]; }
99
+
100
+uint16_t HAL_adc_get_result() { return ADC0_RA; }
104
 
101
 
105
 #endif // __MK20DX256__
102
 #endif // __MK20DX256__

+ 38
- 93
Marlin/src/HAL/TEENSY31_32/HAL.h View File

36
 
36
 
37
 #include <stdint.h>
37
 #include <stdint.h>
38
 
38
 
39
-// ------------------------
40
-// Defines
41
-// ------------------------
39
+#define CPU_ST7920_DELAY_1 600
40
+#define CPU_ST7920_DELAY_2 750
41
+#define CPU_ST7920_DELAY_3 750
42
+
43
+//#undef MOTHERBOARD
44
+//#define MOTHERBOARD BOARD_TEENSY31_32
42
 
45
 
43
 #define IS_32BIT_TEENSY 1
46
 #define IS_32BIT_TEENSY 1
44
 #define IS_TEENSY_31_32 1
47
 #define IS_TEENSY_31_32 1
46
   #define IS_TEENSY32 1
49
   #define IS_TEENSY32 1
47
 #endif
50
 #endif
48
 
51
 
49
-#define CPU_ST7920_DELAY_1 600
50
-#define CPU_ST7920_DELAY_2 750
51
-#define CPU_ST7920_DELAY_3 750
52
-
53
-// ------------------------
54
-// Serial ports
55
-// ------------------------
56
-
57
 #include "../../core/serial_hook.h"
52
 #include "../../core/serial_hook.h"
58
 
53
 
59
 #define Serial0 Serial
54
 #define Serial0 Serial
77
   #error "The required SERIAL_PORT must be from 0 to 3, or -1 for Native USB."
72
   #error "The required SERIAL_PORT must be from 0 to 3, or -1 for Native USB."
78
 #endif
73
 #endif
79
 
74
 
80
-// ------------------------
81
-// Types
82
-// ------------------------
83
-
84
-class libServo;
85
-typedef libServo hal_servo_t;
75
+#define HAL_SERVO_LIB libServo
86
 
76
 
87
 typedef int8_t pin_t;
77
 typedef int8_t pin_t;
88
 
78
 
89
-// ------------------------
90
-// Interrupts
91
-// ------------------------
92
-
93
-uint32_t __get_PRIMASK(void); // CMSIS
94
-#define CRITICAL_SECTION_START()  const bool irqon = !__get_PRIMASK(); __disable_irq()
95
-#define CRITICAL_SECTION_END()    if (irqon) __enable_irq()
96
-
97
-// ------------------------
98
-// ADC
99
-// ------------------------
100
-
101
 #ifndef analogInputToDigitalPin
79
 #ifndef analogInputToDigitalPin
102
   #define analogInputToDigitalPin(p) ((p < 12U) ? (p) + 54U : -1)
80
   #define analogInputToDigitalPin(p) ((p < 12U) ? (p) + 54U : -1)
103
 #endif
81
 #endif
104
 
82
 
105
-#define HAL_ADC_VREF         3.3
106
-#define HAL_ADC_RESOLUTION  10
83
+#define CRITICAL_SECTION_START()  uint32_t primask = __get_PRIMASK(); __disable_irq()
84
+#define CRITICAL_SECTION_END()    if (!primask) __enable_irq()
85
+#define ISRS_ENABLED() (!__get_PRIMASK())
86
+#define ENABLE_ISRS()  __enable_irq()
87
+#define DISABLE_ISRS() __disable_irq()
107
 
88
 
108
-//
109
-// Pin Mapping for M42, M43, M226
110
-//
111
-#define GET_PIN_MAP_PIN(index) index
112
-#define GET_PIN_MAP_INDEX(pin) pin
113
-#define PARSED_PIN_INDEX(code, dval) parser.intval(code, dval)
89
+inline void HAL_init() {}
114
 
90
 
115
-// ------------------------
116
-// Class Utilities
117
-// ------------------------
91
+// Clear the reset reason
92
+void HAL_clear_reset_source();
93
+
94
+// Get the reason for the reset
95
+uint8_t HAL_get_reset_source();
96
+
97
+void HAL_reboot();
98
+
99
+FORCE_INLINE void _delay_ms(const int delay_ms) { delay(delay_ms); }
118
 
100
 
119
 #pragma GCC diagnostic push
101
 #pragma GCC diagnostic push
120
 #if GCC_VERSION <= 50000
102
 #if GCC_VERSION <= 50000
125
 
107
 
126
 #pragma GCC diagnostic pop
108
 #pragma GCC diagnostic pop
127
 
109
 
128
-// ------------------------
129
-// MarlinHAL Class
130
-// ------------------------
131
-
132
-class MarlinHAL {
133
-public:
134
-
135
-  // Earliest possible init, before setup()
136
-  MarlinHAL() {}
137
-
138
-  static inline void init() {}        // Called early in setup()
139
-  static inline void init_board() {}  // Called less early in setup()
140
-  static void reboot();               // Restart the firmware from 0x0
141
-
142
-  static inline bool isr_state() { return !__get_PRIMASK(); }
143
-  static inline void isr_on()  { __enable_irq(); }
144
-  static inline void isr_off() { __disable_irq(); }
145
-
146
-  static inline void delay_ms(const int ms) { delay(ms); }
147
-
148
-  // Tasks, called from idle()
149
-  static inline void idletask() {}
150
-
151
-  // Reset
152
-  static uint8_t get_reset_source();
153
-  static inline void clear_reset_source() {}
154
-
155
-  // Free SRAM
156
-  static inline int freeMemory() { return ::freeMemory(); }
157
-
158
-  //
159
-  // ADC Methods
160
-  //
110
+// ADC
161
 
111
 
162
-  // Called by Temperature::init once at startup
163
-  static void adc_init();
112
+void HAL_adc_init();
164
 
113
 
165
-  // Called by Temperature::init for each sensor at startup
166
-  static inline void adc_enable(const pin_t ch) {}
114
+#define HAL_ADC_VREF         3.3
115
+#define HAL_ADC_RESOLUTION  10
116
+#define HAL_START_ADC(pin)  HAL_adc_start_conversion(pin)
117
+#define HAL_READ_ADC()      HAL_adc_get_result()
118
+#define HAL_ADC_READY()     true
167
 
119
 
168
-  // Begin ADC sampling on the given channel
169
-  static void adc_start(const pin_t ch);
120
+#define HAL_ANALOG_SELECT(pin)
170
 
121
 
171
-  // Is the ADC ready for reading?
172
-  static inline bool adc_ready() { return true; }
122
+void HAL_adc_start_conversion(const uint8_t adc_pin);
123
+uint16_t HAL_adc_get_result();
173
 
124
 
174
-  // The current value of the ADC register
175
-  static uint16_t adc_value();
125
+// PWM
176
 
126
 
177
-  /**
178
-   * Set the PWM duty cycle for the pin to the given value.
179
-   * No option to invert the duty cycle [default = false]
180
-   * No option to change the scale of the provided value to enable finer PWM duty control [default = 255]
181
-   */
182
-  static inline void set_pwm_duty(const pin_t pin, const uint16_t v, const uint16_t=255, const bool=false) {
183
-    analogWrite(pin, v);
184
-  }
127
+inline void set_pwm_duty(const pin_t pin, const uint16_t v, const uint16_t=255, const bool=false) { analogWrite(pin, v); }
185
 
128
 
186
-};
129
+// Pin Map
187
 
130
 
188
-extern MarlinHAL hal;
131
+#define GET_PIN_MAP_PIN(index) index
132
+#define GET_PIN_MAP_INDEX(pin) pin
133
+#define PARSED_PIN_INDEX(code, dval) parser.intval(code, dval)

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

110
 bool HAL_timer_interrupt_enabled(const uint8_t timer_num);
110
 bool HAL_timer_interrupt_enabled(const uint8_t timer_num);
111
 
111
 
112
 void HAL_timer_isr_prologue(const uint8_t timer_num);
112
 void HAL_timer_isr_prologue(const uint8_t timer_num);
113
-#define HAL_timer_isr_epilogue(T) NOOP
113
+#define HAL_timer_isr_epilogue(T)

+ 53
- 57
Marlin/src/HAL/TEENSY35_36/HAL.cpp View File

31
 
31
 
32
 #include <Wire.h>
32
 #include <Wire.h>
33
 
33
 
34
-// ------------------------
35
-// Serial ports
36
-// ------------------------
37
-
38
 #define _IMPLEMENT_SERIAL(X) DefaultSerial##X MSerial##X(false, Serial##X)
34
 #define _IMPLEMENT_SERIAL(X) DefaultSerial##X MSerial##X(false, Serial##X)
39
 #define IMPLEMENT_SERIAL(X)  _IMPLEMENT_SERIAL(X)
35
 #define IMPLEMENT_SERIAL(X)  _IMPLEMENT_SERIAL(X)
40
 #if WITHIN(SERIAL_PORT, 0, 3)
36
 #if WITHIN(SERIAL_PORT, 0, 3)
43
 
39
 
44
 USBSerialType USBSerial(false, SerialUSB);
40
 USBSerialType USBSerial(false, SerialUSB);
45
 
41
 
46
-// ------------------------
47
-// Class Utilities
48
-// ------------------------
49
-
50
-extern "C" {
51
-  extern char __bss_end;
52
-  extern char __heap_start;
53
-  extern void* __brkval;
54
-
55
-  int freeMemory() {
56
-    int free_memory;
57
-    if ((int)__brkval == 0)
58
-      free_memory = ((int)&free_memory) - ((int)&__bss_end);
59
-    else
60
-      free_memory = ((int)&free_memory) - ((int)__brkval);
61
-    return free_memory;
62
-  }
42
+uint16_t HAL_adc_result, HAL_adc_select;
43
+
44
+static const uint8_t pin2sc1a[] = {
45
+  5, 14, 8, 9, 13, 12, 6, 7, 15, 4, 3, 19+128, 14+128, 15+128, // 0-13 -> A0-A13
46
+  5, 14, 8, 9, 13, 12, 6, 7, 15, 4, // 14-23 are A0-A9
47
+  255, 255, 255, 255, 255, 255, 255, // 24-30 are digital only
48
+  14+128, 15+128, 17, 18, 4+128, 5+128, 6+128, 7+128, 17+128,  // 31-39 are A12-A20
49
+  255, 255, 255, 255, 255, 255, 255, 255, 255,  // 40-48 are digital only
50
+  10+128, 11+128, // 49-50 are A23-A24
51
+  255, 255, 255, 255, 255, 255, 255, // 51-57 are digital only
52
+  255, 255, 255, 255, 255, 255, // 58-63 (sd card pins) are digital only
53
+  3, 19+128, // 64-65 are A10-A11
54
+  23, 23+128,// 66-67 are A21-A22 (DAC pins)
55
+  1, 1+128,  // 68-69 are A25-A26 (unused USB host port on Teensy 3.5)
56
+  26,        // 70 is Temperature Sensor
57
+  18+128     // 71 is Vref
58
+};
59
+
60
+/*
61
+  // disable interrupts
62
+  void cli() { noInterrupts(); }
63
+
64
+  // enable interrupts
65
+  void sei() { interrupts(); }
66
+*/
67
+
68
+void HAL_adc_init() {
69
+  analog_init();
70
+  while (ADC0_SC3 & ADC_SC3_CAL) {}; // Wait for calibration to finish
71
+  while (ADC1_SC3 & ADC_SC3_CAL) {}; // Wait for calibration to finish
72
+  NVIC_ENABLE_IRQ(IRQ_FTM1);
63
 }
73
 }
64
 
74
 
65
-// ------------------------
66
-// MarlinHAL Class
67
-// ------------------------
75
+void HAL_clear_reset_source() { }
68
 
76
 
69
-void MarlinHAL::reboot() { _reboot_Teensyduino_(); }
70
-
71
-// Reset
72
-
73
-uint8_t MarlinHAL::get_reset_source() {
77
+uint8_t HAL_get_reset_source() {
74
   switch (RCM_SRS0) {
78
   switch (RCM_SRS0) {
75
     case 128: return RST_POWER_ON; break;
79
     case 128: return RST_POWER_ON; break;
76
     case 64: return RST_EXTERNAL; break;
80
     case 64: return RST_EXTERNAL; break;
82
   return 0;
86
   return 0;
83
 }
87
 }
84
 
88
 
85
-// ADC
89
+void HAL_reboot() { _reboot_Teensyduino_(); }
86
 
90
 
87
-int8_t MarlinHAL::adc_select;
91
+extern "C" {
92
+  extern char __bss_end;
93
+  extern char __heap_start;
94
+  extern void* __brkval;
88
 
95
 
89
-void MarlinHAL::adc_init() {
90
-  analog_init();
91
-  while (ADC0_SC3 & ADC_SC3_CAL) { /* Wait for calibration to finish */ }
92
-  while (ADC1_SC3 & ADC_SC3_CAL) { /* Wait for calibration to finish */ }
93
-  NVIC_ENABLE_IRQ(IRQ_FTM1);
96
+  int freeMemory() {
97
+    int free_memory;
98
+    if ((int)__brkval == 0)
99
+      free_memory = ((int)&free_memory) - ((int)&__bss_end);
100
+    else
101
+      free_memory = ((int)&free_memory) - ((int)__brkval);
102
+    return free_memory;
103
+  }
94
 }
104
 }
95
 
105
 
96
-void MarlinHAL::adc_start(const pin_t adc_pin) {
97
-  static const uint8_t pin2sc1a[] = {
98
-    5, 14, 8, 9, 13, 12, 6, 7, 15, 4, 3, 19+128, 14+128, 15+128, // 0-13 -> A0-A13
99
-    5, 14, 8, 9, 13, 12, 6, 7, 15, 4, // 14-23 are A0-A9
100
-    255, 255, 255, 255, 255, 255, 255, // 24-30 are digital only
101
-    14+128, 15+128, 17, 18, 4+128, 5+128, 6+128, 7+128, 17+128,  // 31-39 are A12-A20
102
-    255, 255, 255, 255, 255, 255, 255, 255, 255,  // 40-48 are digital only
103
-    10+128, 11+128, // 49-50 are A23-A24
104
-    255, 255, 255, 255, 255, 255, 255, // 51-57 are digital only
105
-    255, 255, 255, 255, 255, 255, // 58-63 (sd card pins) are digital only
106
-    3, 19+128, // 64-65 are A10-A11
107
-    23, 23+128,// 66-67 are A21-A22 (DAC pins)
108
-    1, 1+128,  // 68-69 are A25-A26 (unused USB host port on Teensy 3.5)
109
-    26,        // 70 is Temperature Sensor
110
-    18+128     // 71 is Vref
111
-  };
106
+void HAL_adc_start_conversion(const uint8_t adc_pin) {
112
   const uint16_t pin = pin2sc1a[adc_pin];
107
   const uint16_t pin = pin2sc1a[adc_pin];
113
   if (pin == 0xFF) {
108
   if (pin == 0xFF) {
114
-    adc_select = -1;    // Digital only
109
+    // Digital only
110
+    HAL_adc_select = -1;
115
   }
111
   }
116
   else if (pin & 0x80) {
112
   else if (pin & 0x80) {
117
-    adc_select = 1;
113
+    HAL_adc_select = 1;
118
     ADC1_SC1A = pin & 0x7F;
114
     ADC1_SC1A = pin & 0x7F;
119
   }
115
   }
120
   else {
116
   else {
121
-    adc_select = 0;
117
+    HAL_adc_select = 0;
122
     ADC0_SC1A = pin;
118
     ADC0_SC1A = pin;
123
   }
119
   }
124
 }
120
 }
125
 
121
 
126
-uint16_t MarlinHAL::adc_value() {
127
-  switch (adc_select) {
122
+uint16_t HAL_adc_get_result() {
123
+  switch (HAL_adc_select) {
128
     case 0: return ADC0_RA;
124
     case 0: return ADC0_RA;
129
     case 1: return ADC1_RA;
125
     case 1: return ADC1_RA;
130
   }
126
   }

+ 39
- 94
Marlin/src/HAL/TEENSY35_36/HAL.h View File

37
 #include <stdint.h>
37
 #include <stdint.h>
38
 #include <util/atomic.h>
38
 #include <util/atomic.h>
39
 
39
 
40
+#define CPU_ST7920_DELAY_1 600
41
+#define CPU_ST7920_DELAY_2 750
42
+#define CPU_ST7920_DELAY_3 750
43
+
40
 // ------------------------
44
 // ------------------------
41
 // Defines
45
 // Defines
42
 // ------------------------
46
 // ------------------------
49
   #define IS_TEENSY35 1
53
   #define IS_TEENSY35 1
50
 #endif
54
 #endif
51
 
55
 
52
-#define CPU_ST7920_DELAY_1 600
53
-#define CPU_ST7920_DELAY_2 750
54
-#define CPU_ST7920_DELAY_3 750
55
-
56
-#undef sq
57
-#define sq(x) ((x)*(x))
58
-
59
-// ------------------------
60
-// Serial ports
61
-// ------------------------
62
-
63
 #include "../../core/serial_hook.h"
56
 #include "../../core/serial_hook.h"
64
 
57
 
65
 #define Serial0 Serial
58
 #define Serial0 Serial
83
   #error "SERIAL_PORT must be from 0 to 3, or -1 for Native USB."
76
   #error "SERIAL_PORT must be from 0 to 3, or -1 for Native USB."
84
 #endif
77
 #endif
85
 
78
 
86
-// ------------------------
87
-// Types
88
-// ------------------------
89
-
90
-class libServo;
91
-typedef libServo hal_servo_t;
79
+#define HAL_SERVO_LIB libServo
92
 
80
 
93
 typedef int8_t pin_t;
81
 typedef int8_t pin_t;
94
 
82
 
95
-// ------------------------
96
-// Interrupts
97
-// ------------------------
98
-
99
-#define CRITICAL_SECTION_START()  const bool irqon = !__get_primask(); __disable_irq()
100
-#define CRITICAL_SECTION_END()    if (irqon) __enable_irq()
101
-
102
-// ------------------------
103
-// ADC
104
-// ------------------------
105
-
106
 #ifndef analogInputToDigitalPin
83
 #ifndef analogInputToDigitalPin
107
   #define analogInputToDigitalPin(p) ((p < 12U) ? (p) + 54U : -1)
84
   #define analogInputToDigitalPin(p) ((p < 12U) ? (p) + 54U : -1)
108
 #endif
85
 #endif
109
 
86
 
110
-#define HAL_ADC_VREF         3.3
111
-#define HAL_ADC_RESOLUTION  10
87
+#define CRITICAL_SECTION_START()  uint32_t primask = __get_primask(); __disable_irq()
88
+#define CRITICAL_SECTION_END()    if (!primask) __enable_irq()
89
+#define ISRS_ENABLED() (!__get_primask())
90
+#define ENABLE_ISRS()  __enable_irq()
91
+#define DISABLE_ISRS() __disable_irq()
112
 
92
 
113
-//
114
-// Pin Mapping for M42, M43, M226
115
-//
116
-#define GET_PIN_MAP_PIN(index) index
117
-#define GET_PIN_MAP_INDEX(pin) pin
118
-#define PARSED_PIN_INDEX(code, dval) parser.intval(code, dval)
93
+#undef sq
94
+#define sq(x) ((x)*(x))
119
 
95
 
120
-// ------------------------
121
-// Class Utilities
122
-// ------------------------
96
+inline void HAL_init() {}
97
+
98
+// Clear reset reason
99
+void HAL_clear_reset_source();
100
+
101
+// Reset reason
102
+uint8_t HAL_get_reset_source();
103
+
104
+void HAL_reboot();
105
+
106
+FORCE_INLINE void _delay_ms(const int delay_ms) { delay(delay_ms); }
123
 
107
 
124
 #pragma GCC diagnostic push
108
 #pragma GCC diagnostic push
125
 #if GCC_VERSION <= 50000
109
 #if GCC_VERSION <= 50000
130
 
114
 
131
 #pragma GCC diagnostic pop
115
 #pragma GCC diagnostic pop
132
 
116
 
133
-// ------------------------
134
-// MarlinHAL Class
135
-// ------------------------
136
-
137
-class MarlinHAL {
138
-public:
139
-
140
-  // Earliest possible init, before setup()
141
-  MarlinHAL() {}
142
-
143
-  static inline void init() {}        // Called early in setup()
144
-  static inline void init_board() {}  // Called less early in setup()
145
-  static void reboot();               // Restart the firmware from 0x0
146
-
147
-  static inline bool isr_state() { return true; }
148
-  static inline void isr_on()  { __enable_irq(); }
149
-  static inline void isr_off() { __disable_irq(); }
150
-
151
-  static inline void delay_ms(const int ms) { delay(ms); }
152
-
153
-  // Tasks, called from idle()
154
-  static inline void idletask() {}
155
-
156
-  // Reset
157
-  static uint8_t get_reset_source();
158
-  static inline void clear_reset_source() {}
159
-
160
-  // Free SRAM
161
-  static inline int freeMemory() { return ::freeMemory(); }
162
-
163
-  //
164
-  // ADC Methods
165
-  //
166
-
167
-  static int8_t adc_select;
117
+// ADC
168
 
118
 
169
-  // Called by Temperature::init once at startup
170
-  static void adc_init();
119
+void HAL_adc_init();
171
 
120
 
172
-  // Called by Temperature::init for each sensor at startup
173
-  static inline void adc_enable(const pin_t) {}
121
+#define HAL_ADC_VREF         3.3
122
+#define HAL_ADC_RESOLUTION  10
123
+#define HAL_START_ADC(pin)  HAL_adc_start_conversion(pin)
124
+#define HAL_READ_ADC()      HAL_adc_get_result()
125
+#define HAL_ADC_READY()     true
174
 
126
 
175
-  // Begin ADC sampling on the given channel
176
-  static void adc_start(const pin_t pin);
127
+#define HAL_ANALOG_SELECT(pin)
177
 
128
 
178
-  // Is the ADC ready for reading?
179
-  static inline bool adc_ready() { return true; }
129
+void HAL_adc_start_conversion(const uint8_t adc_pin);
130
+uint16_t HAL_adc_get_result();
180
 
131
 
181
-  // The current value of the ADC register
182
-  static uint16_t adc_value();
132
+// PWM
183
 
133
 
184
-  /**
185
-   * Set the PWM duty cycle for the pin to the given value.
186
-   * No option to invert the duty cycle [default = false]
187
-   * No option to change the scale of the provided value to enable finer PWM duty control [default = 255]
188
-   */
189
-  static inline void set_pwm_duty(const pin_t pin, const uint16_t v, const uint16_t=255, const bool=false) {
190
-    analogWrite(pin, v);
191
-  }
134
+inline void set_pwm_duty(const pin_t pin, const uint16_t v, const uint16_t=255, const bool=false) { analogWrite(pin, v); }
192
 
135
 
193
-};
136
+// Pin Map
194
 
137
 
195
-extern MarlinHAL hal;
138
+#define GET_PIN_MAP_PIN(index) index
139
+#define GET_PIN_MAP_INDEX(pin) pin
140
+#define PARSED_PIN_INDEX(code, dval) parser.intval(code, dval)

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

109
 bool HAL_timer_interrupt_enabled(const uint8_t timer_num);
109
 bool HAL_timer_interrupt_enabled(const uint8_t timer_num);
110
 
110
 
111
 void HAL_timer_isr_prologue(const uint8_t timer_num);
111
 void HAL_timer_isr_prologue(const uint8_t timer_num);
112
-#define HAL_timer_isr_epilogue(T) NOOP
112
+#define HAL_timer_isr_epilogue(T)

+ 94
- 100
Marlin/src/HAL/TEENSY40_41/HAL.cpp View File

33
 #include "timers.h"
33
 #include "timers.h"
34
 #include <Wire.h>
34
 #include <Wire.h>
35
 
35
 
36
-// ------------------------
37
-// Serial ports
38
-// ------------------------
39
-
40
 #define _IMPLEMENT_SERIAL(X) DefaultSerial##X MSerial##X(false, Serial##X)
36
 #define _IMPLEMENT_SERIAL(X) DefaultSerial##X MSerial##X(false, Serial##X)
41
 #define IMPLEMENT_SERIAL(X)  _IMPLEMENT_SERIAL(X)
37
 #define IMPLEMENT_SERIAL(X)  _IMPLEMENT_SERIAL(X)
42
 #if WITHIN(SERIAL_PORT, 0, 3)
38
 #if WITHIN(SERIAL_PORT, 0, 3)
44
 #endif
40
 #endif
45
 USBSerialType USBSerial(false, SerialUSB);
41
 USBSerialType USBSerial(false, SerialUSB);
46
 
42
 
47
-// ------------------------
48
-// Class Utilities
49
-// ------------------------
50
-
51
-#define __bss_end _ebss
52
-
53
-extern "C" {
54
-  extern char __bss_end;
55
-  extern char __heap_start;
56
-  extern void* __brkval;
57
-
58
-  // Doesn't work on Teensy 4.x
59
-  uint32_t freeMemory() {
60
-    uint32_t free_memory;
61
-    free_memory = ((uint32_t)&free_memory) - (((uint32_t)__brkval) ?: ((uint32_t)&__bss_end));
62
-    return free_memory;
63
-  }
43
+uint16_t HAL_adc_result, HAL_adc_select;
44
+
45
+static const uint8_t pin2sc1a[] = {
46
+  0x07,  // 0/A0  AD_B1_02
47
+  0x08,  // 1/A1  AD_B1_03
48
+  0x0C,  // 2/A2  AD_B1_07
49
+  0x0B,  // 3/A3  AD_B1_06
50
+  0x06,  // 4/A4  AD_B1_01
51
+  0x05,  // 5/A5  AD_B1_00
52
+  0x0F,  // 6/A6  AD_B1_10
53
+  0x00,  // 7/A7  AD_B1_11
54
+  0x0D,  // 8/A8  AD_B1_08
55
+  0x0E,  // 9/A9  AD_B1_09
56
+  0x01,  // 24/A10 AD_B0_12
57
+  0x02,  // 25/A11 AD_B0_13
58
+  0x83,  // 26/A12 AD_B1_14 - only on ADC2, 3
59
+  0x84,  // 27/A13 AD_B1_15 - only on ADC2, 4
60
+  0x07,  // 14/A0  AD_B1_02
61
+  0x08,  // 15/A1  AD_B1_03
62
+  0x0C,  // 16/A2  AD_B1_07
63
+  0x0B,  // 17/A3  AD_B1_06
64
+  0x06,  // 18/A4  AD_B1_01
65
+  0x05,  // 19/A5  AD_B1_00
66
+  0x0F,  // 20/A6  AD_B1_10
67
+  0x00,  // 21/A7  AD_B1_11
68
+  0x0D,  // 22/A8  AD_B1_08
69
+  0x0E,  // 23/A9  AD_B1_09
70
+  0x01,  // 24/A10 AD_B0_12
71
+  0x02,  // 25/A11 AD_B0_13
72
+  0x83,  // 26/A12 AD_B1_14 - only on ADC2, 3
73
+  0x84,  // 27/A13 AD_B1_15 - only on ADC2, 4
74
+  #ifdef ARDUINO_TEENSY41
75
+    0xFF,  // 28
76
+    0xFF,  // 29
77
+    0xFF,  // 30
78
+    0xFF,  // 31
79
+    0xFF,  // 32
80
+    0xFF,  // 33
81
+    0xFF,  // 34
82
+    0xFF,  // 35
83
+    0xFF,  // 36
84
+    0xFF,  // 37
85
+    0x81,  // 38/A14 AD_B1_12 - only on ADC2, 1
86
+    0x82,  // 39/A15 AD_B1_13 - only on ADC2, 2
87
+    0x09,  // 40/A16 AD_B1_04
88
+    0x0A,  // 41/A17 AD_B1_05
89
+  #endif
90
+};
91
+
92
+/*
93
+// disable interrupts
94
+void cli() { noInterrupts(); }
95
+
96
+// enable interrupts
97
+void sei() { interrupts(); }
98
+*/
99
+
100
+void HAL_adc_init() {
101
+  analog_init();
102
+  while (ADC1_GC & ADC_GC_CAL) ;
103
+  while (ADC2_GC & ADC_GC_CAL) ;
64
 }
104
 }
65
 
105
 
66
-// ------------------------
67
-// FastIO
68
-// ------------------------
69
-
70
-bool is_output(pin_t pin) {
71
-  const struct digital_pin_bitband_and_config_table_struct *p;
72
-  p = digital_pin_to_info_PGM + pin;
73
-  return (*(p->reg + 1) & p->mask);
106
+void HAL_clear_reset_source() {
107
+  uint32_t reset_source = SRC_SRSR;
108
+  SRC_SRSR = reset_source;
74
 }
109
 }
75
 
110
 
76
-// ------------------------
77
-// MarlinHAL Class
78
-// ------------------------
79
-
80
-void MarlinHAL::reboot() { _reboot_Teensyduino_(); }
81
-
82
-uint8_t MarlinHAL::get_reset_source() {
111
+uint8_t HAL_get_reset_source() {
83
   switch (SRC_SRSR & 0xFF) {
112
   switch (SRC_SRSR & 0xFF) {
84
     case 1: return RST_POWER_ON; break;
113
     case 1: return RST_POWER_ON; break;
85
     case 2: return RST_SOFTWARE; break;
114
     case 2: return RST_SOFTWARE; break;
92
   return 0;
121
   return 0;
93
 }
122
 }
94
 
123
 
95
-void MarlinHAL::clear_reset_source() {
96
-  uint32_t reset_source = SRC_SRSR;
97
-  SRC_SRSR = reset_source;
98
-}
124
+void HAL_reboot() { _reboot_Teensyduino_(); }
99
 
125
 
100
-// ADC
126
+#define __bss_end _ebss
101
 
127
 
102
-int8_t MarlinHAL::adc_select;
128
+extern "C" {
129
+  extern char __bss_end;
130
+  extern char __heap_start;
131
+  extern void* __brkval;
103
 
132
 
104
-void MarlinHAL::adc_init() {
105
-  analog_init();
106
-  while (ADC1_GC & ADC_GC_CAL) { /* wait */ }
107
-  while (ADC2_GC & ADC_GC_CAL) { /* wait */ }
133
+  // Doesn't work on Teensy 4.x
134
+  uint32_t freeMemory() {
135
+    uint32_t free_memory;
136
+    if ((uint32_t)__brkval == 0)
137
+      free_memory = ((uint32_t)&free_memory) - ((uint32_t)&__bss_end);
138
+    else
139
+      free_memory = ((uint32_t)&free_memory) - ((uint32_t)__brkval);
140
+    return free_memory;
141
+  }
108
 }
142
 }
109
 
143
 
110
-void MarlinHAL::adc_start(const pin_t adc_pin) {
111
-  static const uint8_t pin2sc1a[] = {
112
-    0x07,  // 0/A0  AD_B1_02
113
-    0x08,  // 1/A1  AD_B1_03
114
-    0x0C,  // 2/A2  AD_B1_07
115
-    0x0B,  // 3/A3  AD_B1_06
116
-    0x06,  // 4/A4  AD_B1_01
117
-    0x05,  // 5/A5  AD_B1_00
118
-    0x0F,  // 6/A6  AD_B1_10
119
-    0x00,  // 7/A7  AD_B1_11
120
-    0x0D,  // 8/A8  AD_B1_08
121
-    0x0E,  // 9/A9  AD_B1_09
122
-    0x01,  // 24/A10 AD_B0_12
123
-    0x02,  // 25/A11 AD_B0_13
124
-    0x83,  // 26/A12 AD_B1_14 - only on ADC2, 3
125
-    0x84,  // 27/A13 AD_B1_15 - only on ADC2, 4
126
-    0x07,  // 14/A0  AD_B1_02
127
-    0x08,  // 15/A1  AD_B1_03
128
-    0x0C,  // 16/A2  AD_B1_07
129
-    0x0B,  // 17/A3  AD_B1_06
130
-    0x06,  // 18/A4  AD_B1_01
131
-    0x05,  // 19/A5  AD_B1_00
132
-    0x0F,  // 20/A6  AD_B1_10
133
-    0x00,  // 21/A7  AD_B1_11
134
-    0x0D,  // 22/A8  AD_B1_08
135
-    0x0E,  // 23/A9  AD_B1_09
136
-    0x01,  // 24/A10 AD_B0_12
137
-    0x02,  // 25/A11 AD_B0_13
138
-    0x83,  // 26/A12 AD_B1_14 - only on ADC2, 3
139
-    0x84,  // 27/A13 AD_B1_15 - only on ADC2, 4
140
-    #ifdef ARDUINO_TEENSY41
141
-      0xFF,  // 28
142
-      0xFF,  // 29
143
-      0xFF,  // 30
144
-      0xFF,  // 31
145
-      0xFF,  // 32
146
-      0xFF,  // 33
147
-      0xFF,  // 34
148
-      0xFF,  // 35
149
-      0xFF,  // 36
150
-      0xFF,  // 37
151
-      0x81,  // 38/A14 AD_B1_12 - only on ADC2, 1
152
-      0x82,  // 39/A15 AD_B1_13 - only on ADC2, 2
153
-      0x09,  // 40/A16 AD_B1_04
154
-      0x0A,  // 41/A17 AD_B1_05
155
-    #endif
156
-  };
144
+void HAL_adc_start_conversion(const uint8_t adc_pin) {
157
   const uint16_t pin = pin2sc1a[adc_pin];
145
   const uint16_t pin = pin2sc1a[adc_pin];
158
   if (pin == 0xFF) {
146
   if (pin == 0xFF) {
159
-    adc_select = -1; // Digital only
147
+    HAL_adc_select = -1; // Digital only
160
   }
148
   }
161
   else if (pin & 0x80) {
149
   else if (pin & 0x80) {
162
-    adc_select = 1;
150
+    HAL_adc_select = 1;
163
     ADC2_HC0 = pin & 0x7F;
151
     ADC2_HC0 = pin & 0x7F;
164
   }
152
   }
165
   else {
153
   else {
166
-    adc_select = 0;
154
+    HAL_adc_select = 0;
167
     ADC1_HC0 = pin;
155
     ADC1_HC0 = pin;
168
   }
156
   }
169
 }
157
 }
170
 
158
 
171
-uint16_t MarlinHAL::adc_value() {
172
-  switch (adc_select) {
159
+uint16_t HAL_adc_get_result() {
160
+  switch (HAL_adc_select) {
173
     case 0:
161
     case 0:
174
-      while (!(ADC1_HS & ADC_HS_COCO0)) { /* wait */ }
162
+      while (!(ADC1_HS & ADC_HS_COCO0)) ; // wait
175
       return ADC1_R0;
163
       return ADC1_R0;
176
     case 1:
164
     case 1:
177
-      while (!(ADC2_HS & ADC_HS_COCO0)) { /* wait */ }
165
+      while (!(ADC2_HS & ADC_HS_COCO0)) ; // wait
178
       return ADC2_R0;
166
       return ADC2_R0;
179
   }
167
   }
180
   return 0;
168
   return 0;
181
 }
169
 }
182
 
170
 
171
+bool is_output(pin_t pin) {
172
+  const struct digital_pin_bitband_and_config_table_struct *p;
173
+  p = digital_pin_to_info_PGM + pin;
174
+  return (*(p->reg + 1) & p->mask);
175
+}
176
+
183
 #endif // __IMXRT1062__
177
 #endif // __IMXRT1062__

+ 47
- 101
Marlin/src/HAL/TEENSY40_41/HAL.h View File

41
   #include "../../feature/ethernet.h"
41
   #include "../../feature/ethernet.h"
42
 #endif
42
 #endif
43
 
43
 
44
+#define CPU_ST7920_DELAY_1 600
45
+#define CPU_ST7920_DELAY_2 750
46
+#define CPU_ST7920_DELAY_3 750
47
+
44
 // ------------------------
48
 // ------------------------
45
 // Defines
49
 // Defines
46
 // ------------------------
50
 // ------------------------
51
   #define IS_TEENSY41 1
55
   #define IS_TEENSY41 1
52
 #endif
56
 #endif
53
 
57
 
54
-#define CPU_ST7920_DELAY_1 600
55
-#define CPU_ST7920_DELAY_2 750
56
-#define CPU_ST7920_DELAY_3 750
57
-
58
-#undef sq
59
-#define sq(x) ((x)*(x))
60
-
61
-// Don't place string constants in PROGMEM
62
-#undef PSTR
63
-#define PSTR(str) ({static const char *data = (str); &data[0];})
64
-
65
-// ------------------------
66
-// Serial ports
67
-// ------------------------
68
-
69
 #include "../../core/serial_hook.h"
58
 #include "../../core/serial_hook.h"
70
-
71
 #define Serial0 Serial
59
 #define Serial0 Serial
72
 #define _DECLARE_SERIAL(X) \
60
 #define _DECLARE_SERIAL(X) \
73
   typedef ForwardSerial1Class<decltype(Serial##X)> DefaultSerial##X; \
61
   typedef ForwardSerial1Class<decltype(Serial##X)> DefaultSerial##X; \
101
   #endif
89
   #endif
102
 #endif
90
 #endif
103
 
91
 
104
-// ------------------------
105
-// Types
106
-// ------------------------
107
-
108
-class libServo;
109
-typedef libServo hal_servo_t;
92
+#define HAL_SERVO_LIB libServo
110
 
93
 
111
 typedef int8_t pin_t;
94
 typedef int8_t pin_t;
112
 
95
 
113
-// ------------------------
114
-// Interrupts
115
-// ------------------------
116
-
117
-#define CRITICAL_SECTION_START()  const bool irqon = !__get_primask(); __disable_irq()
118
-#define CRITICAL_SECTION_END()    if (irqon) __enable_irq()
119
-
120
-// ------------------------
121
-// ADC
122
-// ------------------------
123
-
124
 #ifndef analogInputToDigitalPin
96
 #ifndef analogInputToDigitalPin
125
   #define analogInputToDigitalPin(p) ((p < 12U) ? (p) + 54U : -1)
97
   #define analogInputToDigitalPin(p) ((p < 12U) ? (p) + 54U : -1)
126
 #endif
98
 #endif
127
 
99
 
128
-#define HAL_ADC_VREF         3.3
129
-#define HAL_ADC_RESOLUTION  10
130
-#define HAL_ADC_FILTERED      // turn off ADC oversampling
100
+#define CRITICAL_SECTION_START()  uint32_t primask = __get_primask(); __disable_irq()
101
+#define CRITICAL_SECTION_END()    if (!primask) __enable_irq()
102
+#define ISRS_ENABLED() (!__get_primask())
103
+#define ENABLE_ISRS()  __enable_irq()
104
+#define DISABLE_ISRS() __disable_irq()
131
 
105
 
132
-//
133
-// Pin Mapping for M42, M43, M226
134
-//
135
-#define GET_PIN_MAP_PIN(index) index
136
-#define GET_PIN_MAP_INDEX(pin) pin
137
-#define PARSED_PIN_INDEX(code, dval) parser.intval(code, dval)
106
+#undef sq
107
+#define sq(x) ((x)*(x))
138
 
108
 
139
-// FastIO
140
-bool is_output(pin_t pin);
109
+// Don't place string constants in PROGMEM
110
+#undef PSTR
111
+#define PSTR(str) ({static const char *data = (str); &data[0];})
141
 
112
 
142
-// ------------------------
143
-// Class Utilities
144
-// ------------------------
113
+// Enable hooks into idle and setup for HAL
114
+#define HAL_IDLETASK 1
115
+FORCE_INLINE void HAL_idletask() {}
116
+FORCE_INLINE void HAL_init() {}
117
+
118
+// Clear reset reason
119
+void HAL_clear_reset_source();
120
+
121
+// Reset reason
122
+uint8_t HAL_get_reset_source();
123
+
124
+void HAL_reboot();
125
+
126
+FORCE_INLINE void _delay_ms(const int delay_ms) { delay(delay_ms); }
145
 
127
 
146
 #pragma GCC diagnostic push
128
 #pragma GCC diagnostic push
147
 #if GCC_VERSION <= 50000
129
 #if GCC_VERSION <= 50000
152
 
134
 
153
 #pragma GCC diagnostic pop
135
 #pragma GCC diagnostic pop
154
 
136
 
155
-// ------------------------
156
-// MarlinHAL Class
157
-// ------------------------
158
-
159
-class MarlinHAL {
160
-public:
161
-
162
-  // Earliest possible init, before setup()
163
-  MarlinHAL() {}
164
-
165
-  static inline void init() {}        // Called early in setup()
166
-  static inline void init_board() {}  // Called less early in setup()
167
-  static void reboot();               // Restart the firmware from 0x0
168
-
169
-  static inline bool isr_state() { return !__get_primask(); }
170
-  static inline void isr_on()  { __enable_irq(); }
171
-  static inline void isr_off() { __disable_irq(); }
172
-
173
-  static inline void delay_ms(const int ms) { delay(ms); }
174
-
175
-  // Tasks, called from idle()
176
-  static inline void idletask() {}
177
-
178
-  // Reset
179
-  static uint8_t get_reset_source();
180
-  static void clear_reset_source();
181
-
182
-  // Free SRAM
183
-  static inline int freeMemory() { return ::freeMemory(); }
184
-
185
-  //
186
-  // ADC Methods
187
-  //
137
+// ADC
188
 
138
 
189
-  static int8_t adc_select;
139
+void HAL_adc_init();
190
 
140
 
191
-  // Called by Temperature::init once at startup
192
-  static void adc_init();
141
+#define HAL_ADC_VREF         3.3
142
+#define HAL_ADC_RESOLUTION  10
143
+#define HAL_ADC_FILTERED      // turn off ADC oversampling
144
+#define HAL_START_ADC(pin)  HAL_adc_start_conversion(pin)
145
+#define HAL_READ_ADC()      HAL_adc_get_result()
146
+#define HAL_ADC_READY()     true
193
 
147
 
194
-  // Called by Temperature::init for each sensor at startup
195
-  static inline void adc_enable(const pin_t pin) {}
148
+#define HAL_ANALOG_SELECT(pin)
196
 
149
 
197
-  // Begin ADC sampling on the given channel
198
-  static void adc_start(const pin_t pin);
150
+void HAL_adc_start_conversion(const uint8_t adc_pin);
151
+uint16_t HAL_adc_get_result();
199
 
152
 
200
-  // Is the ADC ready for reading?
201
-  static inline bool adc_ready() { return true; }
153
+// PWM
202
 
154
 
203
-  // The current value of the ADC register
204
-  static uint16_t adc_value();
155
+inline void set_pwm_duty(const pin_t pin, const uint16_t v, const uint16_t=255, const bool=false) { analogWrite(pin, v); }
205
 
156
 
206
-  /**
207
-   * Set the PWM duty cycle for the pin to the given value.
208
-   * No option to invert the duty cycle [default = false]
209
-   * No option to change the scale of the provided value to enable finer PWM duty control [default = 255]
210
-   */
211
-  static inline void set_pwm_duty(const pin_t pin, const uint16_t v, const uint16_t=255, const bool=false) {
212
-    analogWrite(pin, v);
213
-  }
157
+// Pin Map
214
 
158
 
215
-};
159
+#define GET_PIN_MAP_PIN(index) index
160
+#define GET_PIN_MAP_INDEX(pin) pin
161
+#define PARSED_PIN_INDEX(code, dval) parser.intval(code, dval)
216
 
162
 
217
-extern MarlinHAL hal;
163
+bool is_output(pin_t pin);

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

114
 
114
 
115
 void HAL_timer_isr_prologue(const uint8_t timer_num);
115
 void HAL_timer_isr_prologue(const uint8_t timer_num);
116
 //void HAL_timer_isr_epilogue(const uint8_t timer_num) {}
116
 //void HAL_timer_isr_epilogue(const uint8_t timer_num) {}
117
-#define HAL_timer_isr_epilogue(T) NOOP
117
+#define HAL_timer_isr_epilogue(T)

+ 0
- 36
Marlin/src/HAL/shared/HAL.cpp View File

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
-
23
-/**
24
- * HAL/shared/HAL.cpp
25
- */
26
-
27
-#include "../../inc/MarlinConfig.h"
28
-
29
-MarlinHAL hal;
30
-
31
-#if ENABLED(SOFT_RESET_VIA_SERIAL)
32
-
33
-  // Global for use by e_parser.h
34
-  void HAL_reboot() { hal.reboot(); }
35
-
36
-#endif

+ 4
- 4
Marlin/src/HAL/shared/HAL_spi_L6470.cpp View File

92
   // First device in chain has data sent last
92
   // First device in chain has data sent last
93
   extDigitalWrite(ss_pin, LOW);
93
   extDigitalWrite(ss_pin, LOW);
94
 
94
 
95
-  hal.isr_off();  // Disable interrupts during SPI transfer (can't allow partial command to chips)
95
+  DISABLE_ISRS(); // Disable interrupts during SPI transfer (can't allow partial command to chips)
96
   const uint8_t data_out = L6470_SpiTransfer_Mode_3(data);
96
   const uint8_t data_out = L6470_SpiTransfer_Mode_3(data);
97
-  hal.isr_on();   // Enable interrupts
97
+  ENABLE_ISRS();  // Enable interrupts
98
 
98
 
99
   extDigitalWrite(ss_pin, HIGH);
99
   extDigitalWrite(ss_pin, HIGH);
100
   return data_out;
100
   return data_out;
107
   extDigitalWrite(ss_pin, LOW);
107
   extDigitalWrite(ss_pin, LOW);
108
 
108
 
109
   for (uint8_t i = L64XX::chain[0]; !L64xxManager.spi_abort && i >= 1; i--) {   // Send data unless aborted
109
   for (uint8_t i = L64XX::chain[0]; !L64xxManager.spi_abort && i >= 1; i--) {   // Send data unless aborted
110
-    hal.isr_off();    // Disable interrupts during SPI transfer (can't allow partial command to chips)
110
+    DISABLE_ISRS();   // Disable interrupts during SPI transfer (can't allow partial command to chips)
111
     const uint8_t temp = L6470_SpiTransfer_Mode_3(uint8_t(i == chain_position ? data : dSPIN_NOP));
111
     const uint8_t temp = L6470_SpiTransfer_Mode_3(uint8_t(i == chain_position ? data : dSPIN_NOP));
112
-    hal.isr_on();     // Enable interrupts
112
+    ENABLE_ISRS();    // Enable interrupts
113
     if (i == chain_position) data_out = temp;
113
     if (i == chain_position) data_out = temp;
114
   }
114
   }
115
 
115
 

+ 27
- 21
Marlin/src/MarlinCore.cpp View File

790
   #endif
790
   #endif
791
 
791
 
792
   // Run HAL idle tasks
792
   // Run HAL idle tasks
793
-  hal.idletask();
793
+  TERN_(HAL_IDLETASK, HAL_idletask());
794
 
794
 
795
   // Check network connection
795
   // Check network connection
796
   TERN_(HAS_ETHERNET, ethernet.check());
796
   TERN_(HAS_ETHERNET, ethernet.check());
929
       watchdog_refresh();
929
       watchdog_refresh();
930
 
930
 
931
     // Reboot the board
931
     // Reboot the board
932
-    hal.reboot();
932
+    HAL_reboot();
933
 
933
 
934
   #else
934
   #else
935
 
935
 
1041
  *    • L64XX Stepper Drivers (SPI)
1041
  *    • L64XX Stepper Drivers (SPI)
1042
  *    • Stepper Driver Reset: DISABLE
1042
  *    • Stepper Driver Reset: DISABLE
1043
  *    • TMC Stepper Drivers (SPI)
1043
  *    • TMC Stepper Drivers (SPI)
1044
- *    • Run hal.init_board() for additional pins setup
1044
+ *    • Run BOARD_INIT if defined
1045
  *    • ESP WiFi
1045
  *    • ESP WiFi
1046
  *  - Get the Reset Reason and report it
1046
  *  - Get the Reset Reason and report it
1047
  *  - Print startup messages and diagnostics
1047
  *  - Print startup messages and diagnostics
1119
   tmc_standby_setup();  // TMC Low Power Standby pins must be set early or they're not usable
1119
   tmc_standby_setup();  // TMC Low Power Standby pins must be set early or they're not usable
1120
 
1120
 
1121
   // Check startup - does nothing if bootloader sets MCUSR to 0
1121
   // Check startup - does nothing if bootloader sets MCUSR to 0
1122
-  const byte mcu = hal.get_reset_source();
1123
-  hal.clear_reset_source();
1122
+  const byte mcu = HAL_get_reset_source();
1123
+  HAL_clear_reset_source();
1124
 
1124
 
1125
   #if ENABLED(MARLIN_DEV_MODE)
1125
   #if ENABLED(MARLIN_DEV_MODE)
1126
     auto log_current_ms = [&](PGM_P const msg) {
1126
     auto log_current_ms = [&](PGM_P const msg) {
1181
     JTAGSWD_RESET();
1181
     JTAGSWD_RESET();
1182
   #endif
1182
   #endif
1183
 
1183
 
1184
-  // Disable any hardware debug to free up pins for IO
1185
-  #if ENABLED(DISABLE_DEBUG) && defined(JTAGSWD_DISABLE)
1184
+  #if EITHER(DISABLE_DEBUG, DISABLE_JTAG)
1186
     delay(10);
1185
     delay(10);
1187
-    SETUP_LOG("JTAGSWD_DISABLE");
1188
-    JTAGSWD_DISABLE();
1189
-  #elif ENABLED(DISABLE_JTAG) && defined(JTAG_DISABLE)
1190
-    delay(10);
1191
-    SETUP_LOG("JTAG_DISABLE");
1192
-    JTAG_DISABLE();
1186
+    // Disable any hardware debug to free up pins for IO
1187
+    #if ENABLED(DISABLE_DEBUG) && defined(JTAGSWD_DISABLE)
1188
+      SETUP_LOG("JTAGSWD_DISABLE");
1189
+      JTAGSWD_DISABLE();
1190
+    #elif defined(JTAG_DISABLE)
1191
+      SETUP_LOG("JTAG_DISABLE");
1192
+      JTAG_DISABLE();
1193
+    #else
1194
+      #error "DISABLE_(DEBUG|JTAG) is not supported for the selected MCU/Board."
1195
+    #endif
1193
   #endif
1196
   #endif
1194
 
1197
 
1195
   TERN_(DYNAMIC_VECTORTABLE, hook_cpu_exceptions()); // If supported, install Marlin exception handlers at runtime
1198
   TERN_(DYNAMIC_VECTORTABLE, hook_cpu_exceptions()); // If supported, install Marlin exception handlers at runtime
1196
 
1199
 
1197
-  SETUP_RUN(hal.init());
1200
+  SETUP_RUN(HAL_init());
1198
 
1201
 
1199
   // Init and disable SPI thermocouples; this is still needed
1202
   // Init and disable SPI thermocouples; this is still needed
1200
   #if TEMP_SENSOR_0_IS_MAX_TC || (TEMP_SENSOR_REDUNDANT_IS_MAX_TC && REDUNDANT_TEMP_MATCH(SOURCE, E0))
1203
   #if TEMP_SENSOR_0_IS_MAX_TC || (TEMP_SENSOR_REDUNDANT_IS_MAX_TC && REDUNDANT_TEMP_MATCH(SOURCE, E0))
1240
     SETUP_RUN(tmc_init_cs_pins());
1243
     SETUP_RUN(tmc_init_cs_pins());
1241
   #endif
1244
   #endif
1242
 
1245
 
1243
-  SETUP_RUN(hal.init_board());
1246
+  #ifdef BOARD_INIT
1247
+    SETUP_LOG("BOARD_INIT");
1248
+    BOARD_INIT();
1249
+  #endif
1244
 
1250
 
1245
   SETUP_RUN(esp_wifi_init());
1251
   SETUP_RUN(esp_wifi_init());
1246
 
1252
 
1247
   // Report Reset Reason
1253
   // Report Reset Reason
1248
-  if (mcu & RST_POWER_ON)  SERIAL_ECHOLNPGM(STR_POWERUP);
1249
-  if (mcu & RST_EXTERNAL)  SERIAL_ECHOLNPGM(STR_EXTERNAL_RESET);
1254
+  if (mcu & RST_POWER_ON) SERIAL_ECHOLNPGM(STR_POWERUP);
1255
+  if (mcu & RST_EXTERNAL) SERIAL_ECHOLNPGM(STR_EXTERNAL_RESET);
1250
   if (mcu & RST_BROWN_OUT) SERIAL_ECHOLNPGM(STR_BROWNOUT_RESET);
1256
   if (mcu & RST_BROWN_OUT) SERIAL_ECHOLNPGM(STR_BROWNOUT_RESET);
1251
-  if (mcu & RST_WATCHDOG)  SERIAL_ECHOLNPGM(STR_WATCHDOG_RESET);
1252
-  if (mcu & RST_SOFTWARE)  SERIAL_ECHOLNPGM(STR_SOFTWARE_RESET);
1257
+  if (mcu & RST_WATCHDOG) SERIAL_ECHOLNPGM(STR_WATCHDOG_RESET);
1258
+  if (mcu & RST_SOFTWARE) SERIAL_ECHOLNPGM(STR_SOFTWARE_RESET);
1253
 
1259
 
1254
   // Identify myself as Marlin x.x.x
1260
   // Identify myself as Marlin x.x.x
1255
   SERIAL_ECHOLNPGM("Marlin " SHORT_BUILD_VERSION);
1261
   SERIAL_ECHOLNPGM("Marlin " SHORT_BUILD_VERSION);
1260
     );
1266
     );
1261
   #endif
1267
   #endif
1262
   SERIAL_ECHO_MSG(" Compiled: " __DATE__);
1268
   SERIAL_ECHO_MSG(" Compiled: " __DATE__);
1263
-  SERIAL_ECHO_MSG(STR_FREE_MEMORY, hal.freeMemory(), STR_PLANNER_BUFFER_BYTES, sizeof(block_t) * (BLOCK_BUFFER_SIZE));
1269
+  SERIAL_ECHO_MSG(STR_FREE_MEMORY, freeMemory(), STR_PLANNER_BUFFER_BYTES, sizeof(block_t) * (BLOCK_BUFFER_SIZE));
1264
 
1270
 
1265
   // Some HAL need precise delay adjustment
1271
   // Some HAL need precise delay adjustment
1266
   calibrate_delay_loop();
1272
   calibrate_delay_loop();
1532
   #endif
1538
   #endif
1533
 
1539
 
1534
   #if ENABLED(USE_WATCHDOG)
1540
   #if ENABLED(USE_WATCHDOG)
1535
-    SETUP_RUN(watchdog_init());       // Reinit watchdog after hal.get_reset_source call
1541
+    SETUP_RUN(watchdog_init());       // Reinit watchdog after HAL_get_reset_source call
1536
   #endif
1542
   #endif
1537
 
1543
 
1538
   #if ENABLED(EXTERNAL_CLOSED_LOOP_CONTROLLER)
1544
   #if ENABLED(EXTERNAL_CLOSED_LOOP_CONTROLLER)

+ 1
- 1
Marlin/src/feature/caselight.cpp View File

69
 
69
 
70
     #if CASELIGHT_USES_BRIGHTNESS
70
     #if CASELIGHT_USES_BRIGHTNESS
71
       if (pin_is_pwm())
71
       if (pin_is_pwm())
72
-        hal.set_pwm_duty(pin_t(CASE_LIGHT_PIN), (
72
+        set_pwm_duty(pin_t(CASE_LIGHT_PIN), (
73
           #if CASE_LIGHT_MAX_PWM == 255
73
           #if CASE_LIGHT_MAX_PWM == 255
74
             n10ct
74
             n10ct
75
           #else
75
           #else

+ 1
- 1
Marlin/src/feature/controllerfan.cpp View File

76
       thermalManager.soft_pwm_controller_speed = speed;
76
       thermalManager.soft_pwm_controller_speed = speed;
77
     #else
77
     #else
78
       if (PWM_PIN(CONTROLLER_FAN_PIN))
78
       if (PWM_PIN(CONTROLLER_FAN_PIN))
79
-        hal.set_pwm_duty(pin_t(CONTROLLER_FAN_PIN), speed);
79
+        set_pwm_duty(pin_t(CONTROLLER_FAN_PIN), speed);
80
       else
80
       else
81
         WRITE(CONTROLLER_FAN_PIN, speed > 0);
81
         WRITE(CONTROLLER_FAN_PIN, speed > 0);
82
     #endif
82
     #endif

+ 1
- 3
Marlin/src/feature/e_parser.h View File

41
   void quickresume_stepper();
41
   void quickresume_stepper();
42
 #endif
42
 #endif
43
 
43
 
44
-#if ENABLED(SOFT_RESET_VIA_SERIAL)
45
-  void HAL_reboot();
46
-#endif
44
+void HAL_reboot();
47
 
45
 
48
 class EmergencyParser {
46
 class EmergencyParser {
49
 
47
 

+ 1
- 1
Marlin/src/feature/leds/leds.cpp View File

123
     // If the pins can do PWM then their intensity will be set.
123
     // If the pins can do PWM then their intensity will be set.
124
     #define _UPDATE_RGBW(C,c) do {                 \
124
     #define _UPDATE_RGBW(C,c) do {                 \
125
       if (PWM_PIN(RGB_LED_##C##_PIN))              \
125
       if (PWM_PIN(RGB_LED_##C##_PIN))              \
126
-        hal.set_pwm_duty(pin_t(RGB_LED_##C##_PIN), c); \
126
+        set_pwm_duty(pin_t(RGB_LED_##C##_PIN), c); \
127
       else                                         \
127
       else                                         \
128
         WRITE(RGB_LED_##C##_PIN, c ? HIGH : LOW);  \
128
         WRITE(RGB_LED_##C##_PIN, c ? HIGH : LOW);  \
129
     }while(0)
129
     }while(0)

+ 5
- 5
Marlin/src/feature/spindle_laser.cpp View File

66
   #endif
66
   #endif
67
   #if ENABLED(SPINDLE_LASER_USE_PWM)
67
   #if ENABLED(SPINDLE_LASER_USE_PWM)
68
     SET_PWM(SPINDLE_LASER_PWM_PIN);
68
     SET_PWM(SPINDLE_LASER_PWM_PIN);
69
-    hal.set_pwm_duty(pin_t(SPINDLE_LASER_PWM_PIN), SPINDLE_LASER_PWM_OFF); // Set to lowest speed
69
+    set_pwm_duty(pin_t(SPINDLE_LASER_PWM_PIN), SPINDLE_LASER_PWM_OFF); // Set to lowest speed
70
   #endif
70
   #endif
71
   #if ENABLED(HAL_CAN_SET_PWM_FREQ) && defined(SPINDLE_LASER_FREQUENCY)
71
   #if ENABLED(HAL_CAN_SET_PWM_FREQ) && defined(SPINDLE_LASER_FREQUENCY)
72
-    hal.set_pwm_frequency(pin_t(SPINDLE_LASER_PWM_PIN), SPINDLE_LASER_FREQUENCY);
72
+    set_pwm_frequency(pin_t(SPINDLE_LASER_PWM_PIN), SPINDLE_LASER_FREQUENCY);
73
     TERN_(MARLIN_DEV_MODE, frequency = SPINDLE_LASER_FREQUENCY);
73
     TERN_(MARLIN_DEV_MODE, frequency = SPINDLE_LASER_FREQUENCY);
74
   #endif
74
   #endif
75
   #if ENABLED(AIR_EVACUATION)
75
   #if ENABLED(AIR_EVACUATION)
90
    * @param ocr Power value
90
    * @param ocr Power value
91
    */
91
    */
92
   void SpindleLaser::_set_ocr(const uint8_t ocr) {
92
   void SpindleLaser::_set_ocr(const uint8_t ocr) {
93
-    #if BOTH(NEEDS_HARDWARE_PWM, HAL_CAN_SET_PWM_FREQ) && SPINDLE_LASER_FREQUENCY
94
-      hal.set_pwm_frequency(pin_t(SPINDLE_LASER_PWM_PIN), TERN(MARLIN_DEV_MODE, frequency, SPINDLE_LASER_FREQUENCY));
93
+    #if NEEDS_HARDWARE_PWM && SPINDLE_LASER_FREQUENCY
94
+      set_pwm_frequency(pin_t(SPINDLE_LASER_PWM_PIN), TERN(MARLIN_DEV_MODE, frequency, SPINDLE_LASER_FREQUENCY));
95
     #endif
95
     #endif
96
-    hal.set_pwm_duty(pin_t(SPINDLE_LASER_PWM_PIN), ocr ^ SPINDLE_LASER_PWM_OFF);
96
+    set_pwm_duty(pin_t(SPINDLE_LASER_PWM_PIN), ocr ^ SPINDLE_LASER_PWM_OFF);
97
   }
97
   }
98
 
98
 
99
   void SpindleLaser::set_ocr(const uint8_t ocr) {
99
   void SpindleLaser::set_ocr(const uint8_t ocr) {

+ 1
- 1
Marlin/src/feature/spindle_laser.h View File

103
   static void init();
103
   static void init();
104
 
104
 
105
   #if ENABLED(MARLIN_DEV_MODE)
105
   #if ENABLED(MARLIN_DEV_MODE)
106
-    static inline void refresh_frequency() { hal.set_pwm_frequency(pin_t(SPINDLE_LASER_PWM_PIN), frequency); }
106
+    static inline void refresh_frequency() { set_pwm_frequency(pin_t(SPINDLE_LASER_PWM_PIN), frequency); }
107
   #endif
107
   #endif
108
 
108
 
109
   // Modifying this function should update everywhere
109
   // Modifying this function should update everywhere

+ 2
- 2
Marlin/src/gcode/control/M42.cpp View File

126
   extDigitalWrite(pin, pin_status);
126
   extDigitalWrite(pin, pin_status);
127
 
127
 
128
   #ifdef ARDUINO_ARCH_STM32
128
   #ifdef ARDUINO_ARCH_STM32
129
-    // A simple I/O will be set to 0 by hal.set_pwm_duty()
129
+    // A simple I/O will be set to 0 by set_pwm_duty()
130
     if (pin_status <= 1 && !PWM_PIN(pin)) return;
130
     if (pin_status <= 1 && !PWM_PIN(pin)) return;
131
   #endif
131
   #endif
132
-  hal.set_pwm_duty(pin, pin_status);
132
+  set_pwm_duty(pin, pin_status);
133
 }
133
 }
134
 
134
 
135
 #endif // DIRECT_PIN_CONTROL
135
 #endif // DIRECT_PIN_CONTROL

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

38
 #include "../sd/cardreader.h"
38
 #include "../sd/cardreader.h"
39
 #include "../MarlinCore.h" // for kill
39
 #include "../MarlinCore.h" // for kill
40
 
40
 
41
-void dump_delay_accuracy_check();
41
+extern void dump_delay_accuracy_check();
42
 
42
 
43
 /**
43
 /**
44
  * Dn: G-code for development and testing
44
  * Dn: G-code for development and testing
54
       for (;;) { /* loop forever (watchdog reset) */ }
54
       for (;;) { /* loop forever (watchdog reset) */ }
55
 
55
 
56
     case 0:
56
     case 0:
57
-      hal.reboot();
57
+      HAL_reboot();
58
       break;
58
       break;
59
 
59
 
60
     case 10:
60
     case 10:
74
         settings.reset();
74
         settings.reset();
75
         settings.save();
75
         settings.save();
76
       #endif
76
       #endif
77
-      hal.reboot();
77
+      HAL_reboot();
78
     } break;
78
     } break;
79
 
79
 
80
     case 2: { // D2 Read / Write SRAM
80
     case 2: { // D2 Read / Write SRAM
189
       SERIAL_ECHOLNPGM("(USE_WATCHDOG " TERN(USE_WATCHDOG, "ENABLED", "DISABLED") ")");
189
       SERIAL_ECHOLNPGM("(USE_WATCHDOG " TERN(USE_WATCHDOG, "ENABLED", "DISABLED") ")");
190
       thermalManager.disable_all_heaters();
190
       thermalManager.disable_all_heaters();
191
       delay(1000); // Allow time to print
191
       delay(1000); // Allow time to print
192
-      hal.isr_off();
192
+      DISABLE_ISRS();
193
       // Use a low-level delay that does not rely on interrupts to function
193
       // Use a low-level delay that does not rely on interrupts to function
194
       // Do not spin forever, to avoid thermal risks if heaters are enabled and
194
       // Do not spin forever, to avoid thermal risks if heaters are enabled and
195
       // watchdog does not work.
195
       // watchdog does not work.
196
       for (int i = 10000; i--;) DELAY_US(1000UL);
196
       for (int i = 10000; i--;) DELAY_US(1000UL);
197
-      hal.isr_on();
197
+      ENABLE_ISRS();
198
       SERIAL_ECHOLNPGM("FAILURE: Watchdog did not trigger board reset.");
198
       SERIAL_ECHOLNPGM("FAILURE: Watchdog did not trigger board reset.");
199
     } break;
199
     } break;
200
 
200
 

+ 0
- 7
Marlin/src/inc/SanityCheck.h View File

3850
 #undef _TEST_PWM
3850
 #undef _TEST_PWM
3851
 #undef _LINEAR_AXES_STR
3851
 #undef _LINEAR_AXES_STR
3852
 #undef _LOGICAL_AXES_STR
3852
 #undef _LOGICAL_AXES_STR
3853
-
3854
-// JTAG support in the HAL
3855
-#if ENABLED(DISABLE_DEBUG) && !defined(JTAGSWD_DISABLE)
3856
-  #error "DISABLE_DEBUG is not supported for the selected MCU/Board."
3857
-#elif ENABLED(DISABLE_JTAG) && !defined(JTAG_DISABLE)
3858
-  #error "DISABLE_JTAG is not supported for the selected MCU/Board."
3859
-#endif

+ 2
- 2
Marlin/src/lcd/dogm/marlinui_DOGM.cpp View File

282
   #if PIN_EXISTS(LCD_RESET)
282
   #if PIN_EXISTS(LCD_RESET)
283
     // Perform a clean hardware reset with needed delays
283
     // Perform a clean hardware reset with needed delays
284
     OUT_WRITE(LCD_RESET_PIN, LOW);
284
     OUT_WRITE(LCD_RESET_PIN, LOW);
285
-    hal.delay_ms(5);
285
+    _delay_ms(5);
286
     WRITE(LCD_RESET_PIN, HIGH);
286
     WRITE(LCD_RESET_PIN, HIGH);
287
-    hal.delay_ms(5);
287
+    _delay_ms(5);
288
     u8g.begin();
288
     u8g.begin();
289
   #endif
289
   #endif
290
 
290
 

+ 1
- 1
Marlin/src/lcd/e3v2/enhanced/dwin.cpp View File

2149
   thermalManager.disable_all_heaters();
2149
   thermalManager.disable_all_heaters();
2150
   planner.finish_and_disable();
2150
   planner.finish_and_disable();
2151
   DWIN_RebootScreen();
2151
   DWIN_RebootScreen();
2152
-  hal.reboot();
2152
+  HAL_reboot();
2153
 }
2153
 }
2154
 
2154
 
2155
 void Goto_InfoMenu(){
2155
 void Goto_InfoMenu(){

+ 1
- 1
Marlin/src/module/endstops.cpp View File

1345
         ES_REPORT_CHANGE(K_MAX);
1345
         ES_REPORT_CHANGE(K_MAX);
1346
       #endif
1346
       #endif
1347
       SERIAL_ECHOLNPGM("\n");
1347
       SERIAL_ECHOLNPGM("\n");
1348
-      hal.set_pwm_duty(pin_t(LED_PIN), local_LED_status);
1348
+      set_pwm_duty(pin_t(LED_PIN), local_LED_status);
1349
       local_LED_status ^= 255;
1349
       local_LED_status ^= 255;
1350
       old_live_state_local = live_state_local;
1350
       old_live_state_local = live_state_local;
1351
     }
1351
     }

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

1264
     #if ENABLED(FAN_SOFT_PWM)
1264
     #if ENABLED(FAN_SOFT_PWM)
1265
       #define _FAN_SET(F) thermalManager.soft_pwm_amount_fan[F] = CALC_FAN_SPEED(F);
1265
       #define _FAN_SET(F) thermalManager.soft_pwm_amount_fan[F] = CALC_FAN_SPEED(F);
1266
     #else
1266
     #else
1267
-      #define _FAN_SET(F) hal.set_pwm_duty(pin_t(FAN##F##_PIN), CALC_FAN_SPEED(F));
1267
+      #define _FAN_SET(F) set_pwm_duty(pin_t(FAN##F##_PIN), CALC_FAN_SPEED(F));
1268
     #endif
1268
     #endif
1269
     #define FAN_SET(F) do{ kickstart_fan(fan_speed, ms, F); _FAN_SET(F); }while(0)
1269
     #define FAN_SET(F) do{ kickstart_fan(fan_speed, ms, F); _FAN_SET(F); }while(0)
1270
 
1270
 
1400
   TERN_(AUTOTEMP, autotemp_task());
1400
   TERN_(AUTOTEMP, autotemp_task());
1401
 
1401
 
1402
   #if ENABLED(BARICUDA)
1402
   #if ENABLED(BARICUDA)
1403
-    TERN_(HAS_HEATER_1, hal.set_pwm_duty(pin_t(HEATER_1_PIN), tail_valve_pressure));
1404
-    TERN_(HAS_HEATER_2, hal.set_pwm_duty(pin_t(HEATER_2_PIN), tail_e_to_p_pressure));
1403
+    TERN_(HAS_HEATER_1, set_pwm_duty(pin_t(HEATER_1_PIN), tail_valve_pressure));
1404
+    TERN_(HAS_HEATER_2, set_pwm_duty(pin_t(HEATER_2_PIN), tail_e_to_p_pressure));
1405
   #endif
1405
   #endif
1406
 }
1406
 }
1407
 
1407
 

+ 1
- 1
Marlin/src/module/servo.cpp View File

30
 
30
 
31
 #include "servo.h"
31
 #include "servo.h"
32
 
32
 
33
-hal_servo_t servo[NUM_SERVOS];
33
+HAL_SERVO_LIB servo[NUM_SERVOS];
34
 
34
 
35
 #if ENABLED(EDITABLE_SERVO_ANGLES)
35
 #if ENABLED(EDITABLE_SERVO_ANGLES)
36
   uint16_t servo_angles[NUM_SERVOS][2];
36
   uint16_t servo_angles[NUM_SERVOS][2];

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

112
 #define MOVE_SERVO(I, P) servo[I].move(P)
112
 #define MOVE_SERVO(I, P) servo[I].move(P)
113
 #define DETACH_SERVO(I) servo[I].detach()
113
 #define DETACH_SERVO(I) servo[I].detach()
114
 
114
 
115
-extern hal_servo_t servo[NUM_SERVOS];
115
+extern HAL_SERVO_LIB servo[NUM_SERVOS];
116
 void servo_init();
116
 void servo_init();

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

1474
   #ifndef __AVR__
1474
   #ifndef __AVR__
1475
     // Disable interrupts, to avoid ISR preemption while we reprogram the period
1475
     // Disable interrupts, to avoid ISR preemption while we reprogram the period
1476
     // (AVR enters the ISR with global interrupts disabled, so no need to do it here)
1476
     // (AVR enters the ISR with global interrupts disabled, so no need to do it here)
1477
-    hal.isr_off();
1477
+    DISABLE_ISRS();
1478
   #endif
1478
   #endif
1479
 
1479
 
1480
   // Program timer compare for the maximum period, so it does NOT
1480
   // Program timer compare for the maximum period, so it does NOT
1492
   hal_timer_t min_ticks;
1492
   hal_timer_t min_ticks;
1493
   do {
1493
   do {
1494
     // Enable ISRs to reduce USART processing latency
1494
     // Enable ISRs to reduce USART processing latency
1495
-    hal.isr_on();
1495
+    ENABLE_ISRS();
1496
 
1496
 
1497
     if (!nextMainISR) pulse_phase_isr();                            // 0 = Do coordinated axes Stepper pulses
1497
     if (!nextMainISR) pulse_phase_isr();                            // 0 = Do coordinated axes Stepper pulses
1498
 
1498
 
1576
      * is less than the current count due to something preempting between the
1576
      * is less than the current count due to something preempting between the
1577
      * read and the write of the new period value).
1577
      * read and the write of the new period value).
1578
      */
1578
      */
1579
-    hal.isr_off();
1579
+    DISABLE_ISRS();
1580
 
1580
 
1581
     /**
1581
     /**
1582
      * Get the current tick value + margin
1582
      * Get the current tick value + margin
1611
   HAL_timer_set_compare(MF_TIMER_STEP, 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
-  hal.isr_on();
1614
+  ENABLE_ISRS();
1615
 }
1615
 }
1616
 
1616
 
1617
 #if MINIMUM_STEPPER_PULSE || MAXIMUM_STEPPER_RATE
1617
 #if MINIMUM_STEPPER_PULSE || MAXIMUM_STEPPER_RATE
3261
 
3261
 
3262
       #elif HAS_MOTOR_CURRENT_PWM
3262
       #elif HAS_MOTOR_CURRENT_PWM
3263
 
3263
 
3264
-        #define _WRITE_CURRENT_PWM(P) hal.set_pwm_duty(pin_t(MOTOR_CURRENT_PWM_## P ##_PIN), 255L * current / (MOTOR_CURRENT_PWM_RANGE))
3264
+        #define _WRITE_CURRENT_PWM(P) set_pwm_duty(pin_t(MOTOR_CURRENT_PWM_## P ##_PIN), 255L * current / (MOTOR_CURRENT_PWM_RANGE))
3265
         switch (driver) {
3265
         switch (driver) {
3266
           case 0:
3266
           case 0:
3267
             #if PIN_EXISTS(MOTOR_CURRENT_PWM_X)
3267
             #if PIN_EXISTS(MOTOR_CURRENT_PWM_X)

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

326
   #define _INIT_FAN_PIN(P) do{ if (PWM_PIN(P)) SET_PWM(P); else _INIT_SOFT_FAN(P); }while(0)
326
   #define _INIT_FAN_PIN(P) do{ if (PWM_PIN(P)) SET_PWM(P); else _INIT_SOFT_FAN(P); }while(0)
327
 #endif
327
 #endif
328
 #if ENABLED(FAST_PWM_FAN)
328
 #if ENABLED(FAST_PWM_FAN)
329
-  #define SET_FAST_PWM_FREQ(P) hal.set_pwm_frequency(pin_t(P), FAST_PWM_FAN_FREQUENCY)
329
+  #define SET_FAST_PWM_FREQ(P) set_pwm_frequency(P, FAST_PWM_FAN_FREQUENCY)
330
 #else
330
 #else
331
   #define SET_FAST_PWM_FREQ(P) NOOP
331
   #define SET_FAST_PWM_FREQ(P) NOOP
332
 #endif
332
 #endif
813
       }
813
       }
814
 
814
 
815
       // Run HAL idle tasks
815
       // Run HAL idle tasks
816
-      hal.idletask();
816
+      TERN_(HAL_IDLETASK, HAL_idletask());
817
 
817
 
818
       // Run UI update
818
       // Run UI update
819
       TERN(HAS_DWIN_E3V2_BASIC, DWIN_Update(), ui.update());
819
       TERN(HAS_DWIN_E3V2_BASIC, DWIN_Update(), ui.update());
912
 
912
 
913
     #define _UPDATE_AUTO_FAN(P,D,A) do{                   \
913
     #define _UPDATE_AUTO_FAN(P,D,A) do{                   \
914
       if (PWM_PIN(P##_AUTO_FAN_PIN) && A < 255)           \
914
       if (PWM_PIN(P##_AUTO_FAN_PIN) && A < 255)           \
915
-        hal.set_pwm_duty(pin_t(P##_AUTO_FAN_PIN), D ? A : 0); \
915
+        set_pwm_duty(pin_t(P##_AUTO_FAN_PIN), D ? A : 0); \
916
       else                                                \
916
       else                                                \
917
         WRITE(P##_AUTO_FAN_PIN, D);                       \
917
         WRITE(P##_AUTO_FAN_PIN, D);                       \
918
     }while(0)
918
     }while(0)
2326
 
2326
 
2327
   TERN_(HAS_MAXTC_SW_SPI, max_tc_spi.init());
2327
   TERN_(HAS_MAXTC_SW_SPI, max_tc_spi.init());
2328
 
2328
 
2329
-  hal.adc_init();
2329
+  HAL_adc_init();
2330
 
2330
 
2331
   #if HAS_TEMP_ADC_0
2331
   #if HAS_TEMP_ADC_0
2332
-    hal.adc_enable(TEMP_0_PIN);
2332
+    HAL_ANALOG_SELECT(TEMP_0_PIN);
2333
   #endif
2333
   #endif
2334
   #if HAS_TEMP_ADC_1
2334
   #if HAS_TEMP_ADC_1
2335
-    hal.adc_enable(TEMP_1_PIN);
2335
+    HAL_ANALOG_SELECT(TEMP_1_PIN);
2336
   #endif
2336
   #endif
2337
   #if HAS_TEMP_ADC_2
2337
   #if HAS_TEMP_ADC_2
2338
-    hal.adc_enable(TEMP_2_PIN);
2338
+    HAL_ANALOG_SELECT(TEMP_2_PIN);
2339
   #endif
2339
   #endif
2340
   #if HAS_TEMP_ADC_3
2340
   #if HAS_TEMP_ADC_3
2341
-    hal.adc_enable(TEMP_3_PIN);
2341
+    HAL_ANALOG_SELECT(TEMP_3_PIN);
2342
   #endif
2342
   #endif
2343
   #if HAS_TEMP_ADC_4
2343
   #if HAS_TEMP_ADC_4
2344
-    hal.adc_enable(TEMP_4_PIN);
2344
+    HAL_ANALOG_SELECT(TEMP_4_PIN);
2345
   #endif
2345
   #endif
2346
   #if HAS_TEMP_ADC_5
2346
   #if HAS_TEMP_ADC_5
2347
-    hal.adc_enable(TEMP_5_PIN);
2347
+    HAL_ANALOG_SELECT(TEMP_5_PIN);
2348
   #endif
2348
   #endif
2349
   #if HAS_TEMP_ADC_6
2349
   #if HAS_TEMP_ADC_6
2350
-    hal.adc_enable(TEMP_6_PIN);
2350
+    HAL_ANALOG_SELECT(TEMP_6_PIN);
2351
   #endif
2351
   #endif
2352
   #if HAS_TEMP_ADC_7
2352
   #if HAS_TEMP_ADC_7
2353
-    hal.adc_enable(TEMP_7_PIN);
2353
+    HAL_ANALOG_SELECT(TEMP_7_PIN);
2354
   #endif
2354
   #endif
2355
   #if HAS_JOY_ADC_X
2355
   #if HAS_JOY_ADC_X
2356
-    hal.adc_enable(JOY_X_PIN);
2356
+    HAL_ANALOG_SELECT(JOY_X_PIN);
2357
   #endif
2357
   #endif
2358
   #if HAS_JOY_ADC_Y
2358
   #if HAS_JOY_ADC_Y
2359
-    hal.adc_enable(JOY_Y_PIN);
2359
+    HAL_ANALOG_SELECT(JOY_Y_PIN);
2360
   #endif
2360
   #endif
2361
   #if HAS_JOY_ADC_Z
2361
   #if HAS_JOY_ADC_Z
2362
-    hal.adc_enable(JOY_Z_PIN);
2362
+    HAL_ANALOG_SELECT(JOY_Z_PIN);
2363
   #endif
2363
   #endif
2364
   #if HAS_JOY_ADC_EN
2364
   #if HAS_JOY_ADC_EN
2365
     SET_INPUT_PULLUP(JOY_EN_PIN);
2365
     SET_INPUT_PULLUP(JOY_EN_PIN);
2366
   #endif
2366
   #endif
2367
   #if HAS_TEMP_ADC_BED
2367
   #if HAS_TEMP_ADC_BED
2368
-    hal.adc_enable(TEMP_BED_PIN);
2368
+    HAL_ANALOG_SELECT(TEMP_BED_PIN);
2369
   #endif
2369
   #endif
2370
   #if HAS_TEMP_ADC_CHAMBER
2370
   #if HAS_TEMP_ADC_CHAMBER
2371
-    hal.adc_enable(TEMP_CHAMBER_PIN);
2371
+    HAL_ANALOG_SELECT(TEMP_CHAMBER_PIN);
2372
   #endif
2372
   #endif
2373
   #if HAS_TEMP_ADC_COOLER
2373
   #if HAS_TEMP_ADC_COOLER
2374
-    hal.adc_enable(TEMP_COOLER_PIN);
2374
+    HAL_ANALOG_SELECT(TEMP_COOLER_PIN);
2375
   #endif
2375
   #endif
2376
   #if HAS_TEMP_ADC_PROBE
2376
   #if HAS_TEMP_ADC_PROBE
2377
-    hal.adc_enable(TEMP_PROBE_PIN);
2377
+    HAL_ANALOG_SELECT(TEMP_PROBE_PIN);
2378
   #endif
2378
   #endif
2379
   #if HAS_TEMP_ADC_BOARD
2379
   #if HAS_TEMP_ADC_BOARD
2380
-    hal.adc_enable(TEMP_BOARD_PIN);
2380
+    HAL_ANALOG_SELECT(TEMP_BOARD_PIN);
2381
   #endif
2381
   #endif
2382
   #if HAS_TEMP_ADC_REDUNDANT
2382
   #if HAS_TEMP_ADC_REDUNDANT
2383
-    hal.adc_enable(TEMP_REDUNDANT_PIN);
2383
+    HAL_ANALOG_SELECT(TEMP_REDUNDANT_PIN);
2384
   #endif
2384
   #endif
2385
   #if ENABLED(FILAMENT_WIDTH_SENSOR)
2385
   #if ENABLED(FILAMENT_WIDTH_SENSOR)
2386
-    hal.adc_enable(FILWIDTH_PIN);
2386
+    HAL_ANALOG_SELECT(FILWIDTH_PIN);
2387
   #endif
2387
   #endif
2388
   #if HAS_ADC_BUTTONS
2388
   #if HAS_ADC_BUTTONS
2389
-    hal.adc_enable(ADC_KEYPAD_PIN);
2389
+    HAL_ANALOG_SELECT(ADC_KEYPAD_PIN);
2390
   #endif
2390
   #endif
2391
   #if ENABLED(POWER_MONITOR_CURRENT)
2391
   #if ENABLED(POWER_MONITOR_CURRENT)
2392
-    hal.adc_enable(POWER_MONITOR_CURRENT_PIN);
2392
+    HAL_ANALOG_SELECT(POWER_MONITOR_CURRENT_PIN);
2393
   #endif
2393
   #endif
2394
   #if ENABLED(POWER_MONITOR_VOLTAGE)
2394
   #if ENABLED(POWER_MONITOR_VOLTAGE)
2395
-    hal.adc_enable(POWER_MONITOR_VOLTAGE_PIN);
2395
+    HAL_ANALOG_SELECT(POWER_MONITOR_VOLTAGE_PIN);
2396
   #endif
2396
   #endif
2397
 
2397
 
2398
   HAL_timer_start(MF_TIMER_TEMP, TEMP_TIMER_FREQUENCY);
2398
   HAL_timer_start(MF_TIMER_TEMP, TEMP_TIMER_FREQUENCY);
3333
    * This gives each ADC 0.9765ms to charge up.
3333
    * This gives each ADC 0.9765ms to charge up.
3334
    */
3334
    */
3335
   #define ACCUMULATE_ADC(obj) do{ \
3335
   #define ACCUMULATE_ADC(obj) do{ \
3336
-    if (!hal.adc_ready()) next_sensor_state = adc_sensor_state; \
3337
-    else obj.sample(hal.adc_value()); \
3336
+    if (!HAL_ADC_READY()) next_sensor_state = adc_sensor_state; \
3337
+    else obj.sample(HAL_READ_ADC()); \
3338
   }while(0)
3338
   }while(0)
3339
 
3339
 
3340
   ADCSensorState next_sensor_state = adc_sensor_state < SensorsReady ? (ADCSensorState)(int(adc_sensor_state) + 1) : StartSampling;
3340
   ADCSensorState next_sensor_state = adc_sensor_state < SensorsReady ? (ADCSensorState)(int(adc_sensor_state) + 1) : StartSampling;
3366
       break;
3366
       break;
3367
 
3367
 
3368
     #if HAS_TEMP_ADC_0
3368
     #if HAS_TEMP_ADC_0
3369
-      case PrepareTemp_0: hal.adc_start(TEMP_0_PIN); break;
3369
+      case PrepareTemp_0: HAL_START_ADC(TEMP_0_PIN); break;
3370
       case MeasureTemp_0: ACCUMULATE_ADC(temp_hotend[0]); break;
3370
       case MeasureTemp_0: ACCUMULATE_ADC(temp_hotend[0]); break;
3371
     #endif
3371
     #endif
3372
 
3372
 
3373
     #if HAS_TEMP_ADC_BED
3373
     #if HAS_TEMP_ADC_BED
3374
-      case PrepareTemp_BED: hal.adc_start(TEMP_BED_PIN); break;
3374
+      case PrepareTemp_BED: HAL_START_ADC(TEMP_BED_PIN); break;
3375
       case MeasureTemp_BED: ACCUMULATE_ADC(temp_bed); break;
3375
       case MeasureTemp_BED: ACCUMULATE_ADC(temp_bed); break;
3376
     #endif
3376
     #endif
3377
 
3377
 
3378
     #if HAS_TEMP_ADC_CHAMBER
3378
     #if HAS_TEMP_ADC_CHAMBER
3379
-      case PrepareTemp_CHAMBER: hal.adc_start(TEMP_CHAMBER_PIN); break;
3379
+      case PrepareTemp_CHAMBER: HAL_START_ADC(TEMP_CHAMBER_PIN); break;
3380
       case MeasureTemp_CHAMBER: ACCUMULATE_ADC(temp_chamber); break;
3380
       case MeasureTemp_CHAMBER: ACCUMULATE_ADC(temp_chamber); break;
3381
     #endif
3381
     #endif
3382
 
3382
 
3383
     #if HAS_TEMP_ADC_COOLER
3383
     #if HAS_TEMP_ADC_COOLER
3384
-      case PrepareTemp_COOLER: hal.adc_start(TEMP_COOLER_PIN); break;
3384
+      case PrepareTemp_COOLER: HAL_START_ADC(TEMP_COOLER_PIN); break;
3385
       case MeasureTemp_COOLER: ACCUMULATE_ADC(temp_cooler); break;
3385
       case MeasureTemp_COOLER: ACCUMULATE_ADC(temp_cooler); break;
3386
     #endif
3386
     #endif
3387
 
3387
 
3388
     #if HAS_TEMP_ADC_PROBE
3388
     #if HAS_TEMP_ADC_PROBE
3389
-      case PrepareTemp_PROBE: hal.adc_start(TEMP_PROBE_PIN); break;
3389
+      case PrepareTemp_PROBE: HAL_START_ADC(TEMP_PROBE_PIN); break;
3390
       case MeasureTemp_PROBE: ACCUMULATE_ADC(temp_probe); break;
3390
       case MeasureTemp_PROBE: ACCUMULATE_ADC(temp_probe); break;
3391
     #endif
3391
     #endif
3392
 
3392
 
3393
     #if HAS_TEMP_ADC_BOARD
3393
     #if HAS_TEMP_ADC_BOARD
3394
-      case PrepareTemp_BOARD: hal.adc_start(TEMP_BOARD_PIN); break;
3394
+      case PrepareTemp_BOARD: HAL_START_ADC(TEMP_BOARD_PIN); break;
3395
       case MeasureTemp_BOARD: ACCUMULATE_ADC(temp_board); break;
3395
       case MeasureTemp_BOARD: ACCUMULATE_ADC(temp_board); break;
3396
     #endif
3396
     #endif
3397
 
3397
 
3398
     #if HAS_TEMP_ADC_REDUNDANT
3398
     #if HAS_TEMP_ADC_REDUNDANT
3399
-      case PrepareTemp_REDUNDANT: hal.adc_start(TEMP_REDUNDANT_PIN); break;
3399
+      case PrepareTemp_REDUNDANT: HAL_START_ADC(TEMP_REDUNDANT_PIN); break;
3400
       case MeasureTemp_REDUNDANT: ACCUMULATE_ADC(temp_redundant); break;
3400
       case MeasureTemp_REDUNDANT: ACCUMULATE_ADC(temp_redundant); break;
3401
     #endif
3401
     #endif
3402
 
3402
 
3403
     #if HAS_TEMP_ADC_1
3403
     #if HAS_TEMP_ADC_1
3404
-      case PrepareTemp_1: hal.adc_start(TEMP_1_PIN); break;
3404
+      case PrepareTemp_1: HAL_START_ADC(TEMP_1_PIN); break;
3405
       case MeasureTemp_1: ACCUMULATE_ADC(temp_hotend[1]); break;
3405
       case MeasureTemp_1: ACCUMULATE_ADC(temp_hotend[1]); break;
3406
     #endif
3406
     #endif
3407
 
3407
 
3408
     #if HAS_TEMP_ADC_2
3408
     #if HAS_TEMP_ADC_2
3409
-      case PrepareTemp_2: hal.adc_start(TEMP_2_PIN); break;
3409
+      case PrepareTemp_2: HAL_START_ADC(TEMP_2_PIN); break;
3410
       case MeasureTemp_2: ACCUMULATE_ADC(temp_hotend[2]); break;
3410
       case MeasureTemp_2: ACCUMULATE_ADC(temp_hotend[2]); break;
3411
     #endif
3411
     #endif
3412
 
3412
 
3413
     #if HAS_TEMP_ADC_3
3413
     #if HAS_TEMP_ADC_3
3414
-      case PrepareTemp_3: hal.adc_start(TEMP_3_PIN); break;
3414
+      case PrepareTemp_3: HAL_START_ADC(TEMP_3_PIN); break;
3415
       case MeasureTemp_3: ACCUMULATE_ADC(temp_hotend[3]); break;
3415
       case MeasureTemp_3: ACCUMULATE_ADC(temp_hotend[3]); break;
3416
     #endif
3416
     #endif
3417
 
3417
 
3418
     #if HAS_TEMP_ADC_4
3418
     #if HAS_TEMP_ADC_4
3419
-      case PrepareTemp_4: hal.adc_start(TEMP_4_PIN); break;
3419
+      case PrepareTemp_4: HAL_START_ADC(TEMP_4_PIN); break;
3420
       case MeasureTemp_4: ACCUMULATE_ADC(temp_hotend[4]); break;
3420
       case MeasureTemp_4: ACCUMULATE_ADC(temp_hotend[4]); break;
3421
     #endif
3421
     #endif
3422
 
3422
 
3423
     #if HAS_TEMP_ADC_5
3423
     #if HAS_TEMP_ADC_5
3424
-      case PrepareTemp_5: hal.adc_start(TEMP_5_PIN); break;
3424
+      case PrepareTemp_5: HAL_START_ADC(TEMP_5_PIN); break;
3425
       case MeasureTemp_5: ACCUMULATE_ADC(temp_hotend[5]); break;
3425
       case MeasureTemp_5: ACCUMULATE_ADC(temp_hotend[5]); break;
3426
     #endif
3426
     #endif
3427
 
3427
 
3428
     #if HAS_TEMP_ADC_6
3428
     #if HAS_TEMP_ADC_6
3429
-      case PrepareTemp_6: hal.adc_start(TEMP_6_PIN); break;
3429
+      case PrepareTemp_6: HAL_START_ADC(TEMP_6_PIN); break;
3430
       case MeasureTemp_6: ACCUMULATE_ADC(temp_hotend[6]); break;
3430
       case MeasureTemp_6: ACCUMULATE_ADC(temp_hotend[6]); break;
3431
     #endif
3431
     #endif
3432
 
3432
 
3433
     #if HAS_TEMP_ADC_7
3433
     #if HAS_TEMP_ADC_7
3434
-      case PrepareTemp_7: hal.adc_start(TEMP_7_PIN); break;
3434
+      case PrepareTemp_7: HAL_START_ADC(TEMP_7_PIN); break;
3435
       case MeasureTemp_7: ACCUMULATE_ADC(temp_hotend[7]); break;
3435
       case MeasureTemp_7: ACCUMULATE_ADC(temp_hotend[7]); break;
3436
     #endif
3436
     #endif
3437
 
3437
 
3438
     #if ENABLED(FILAMENT_WIDTH_SENSOR)
3438
     #if ENABLED(FILAMENT_WIDTH_SENSOR)
3439
-      case Prepare_FILWIDTH: hal.adc_start(FILWIDTH_PIN); break;
3439
+      case Prepare_FILWIDTH: HAL_START_ADC(FILWIDTH_PIN); break;
3440
       case Measure_FILWIDTH:
3440
       case Measure_FILWIDTH:
3441
-        if (!hal.adc_ready()) next_sensor_state = adc_sensor_state; // Redo this state
3442
-        else filwidth.accumulate(hal.adc_value());
3441
+        if (!HAL_ADC_READY()) next_sensor_state = adc_sensor_state; // Redo this state
3442
+        else filwidth.accumulate(HAL_READ_ADC());
3443
       break;
3443
       break;
3444
     #endif
3444
     #endif
3445
 
3445
 
3446
     #if ENABLED(POWER_MONITOR_CURRENT)
3446
     #if ENABLED(POWER_MONITOR_CURRENT)
3447
       case Prepare_POWER_MONITOR_CURRENT:
3447
       case Prepare_POWER_MONITOR_CURRENT:
3448
-        hal.adc_start(POWER_MONITOR_CURRENT_PIN);
3448
+        HAL_START_ADC(POWER_MONITOR_CURRENT_PIN);
3449
         break;
3449
         break;
3450
       case Measure_POWER_MONITOR_CURRENT:
3450
       case Measure_POWER_MONITOR_CURRENT:
3451
-        if (!hal.adc_ready()) next_sensor_state = adc_sensor_state; // Redo this state
3452
-        else power_monitor.add_current_sample(hal.adc_value());
3451
+        if (!HAL_ADC_READY()) next_sensor_state = adc_sensor_state; // Redo this state
3452
+        else power_monitor.add_current_sample(HAL_READ_ADC());
3453
         break;
3453
         break;
3454
     #endif
3454
     #endif
3455
 
3455
 
3456
     #if ENABLED(POWER_MONITOR_VOLTAGE)
3456
     #if ENABLED(POWER_MONITOR_VOLTAGE)
3457
       case Prepare_POWER_MONITOR_VOLTAGE:
3457
       case Prepare_POWER_MONITOR_VOLTAGE:
3458
-        hal.adc_start(POWER_MONITOR_VOLTAGE_PIN);
3458
+        HAL_START_ADC(POWER_MONITOR_VOLTAGE_PIN);
3459
         break;
3459
         break;
3460
       case Measure_POWER_MONITOR_VOLTAGE:
3460
       case Measure_POWER_MONITOR_VOLTAGE:
3461
-        if (!hal.adc_ready()) next_sensor_state = adc_sensor_state; // Redo this state
3462
-        else power_monitor.add_voltage_sample(hal.adc_value());
3461
+        if (!HAL_ADC_READY()) next_sensor_state = adc_sensor_state; // Redo this state
3462
+        else power_monitor.add_voltage_sample(HAL_READ_ADC());
3463
         break;
3463
         break;
3464
     #endif
3464
     #endif
3465
 
3465
 
3466
     #if HAS_JOY_ADC_X
3466
     #if HAS_JOY_ADC_X
3467
-      case PrepareJoy_X: hal.adc_start(JOY_X_PIN); break;
3467
+      case PrepareJoy_X: HAL_START_ADC(JOY_X_PIN); break;
3468
       case MeasureJoy_X: ACCUMULATE_ADC(joystick.x); break;
3468
       case MeasureJoy_X: ACCUMULATE_ADC(joystick.x); break;
3469
     #endif
3469
     #endif
3470
 
3470
 
3471
     #if HAS_JOY_ADC_Y
3471
     #if HAS_JOY_ADC_Y
3472
-      case PrepareJoy_Y: hal.adc_start(JOY_Y_PIN); break;
3472
+      case PrepareJoy_Y: HAL_START_ADC(JOY_Y_PIN); break;
3473
       case MeasureJoy_Y: ACCUMULATE_ADC(joystick.y); break;
3473
       case MeasureJoy_Y: ACCUMULATE_ADC(joystick.y); break;
3474
     #endif
3474
     #endif
3475
 
3475
 
3476
     #if HAS_JOY_ADC_Z
3476
     #if HAS_JOY_ADC_Z
3477
-      case PrepareJoy_Z: hal.adc_start(JOY_Z_PIN); break;
3477
+      case PrepareJoy_Z: HAL_START_ADC(JOY_Z_PIN); break;
3478
       case MeasureJoy_Z: ACCUMULATE_ADC(joystick.z); break;
3478
       case MeasureJoy_Z: ACCUMULATE_ADC(joystick.z); break;
3479
     #endif
3479
     #endif
3480
 
3480
 
3482
       #ifndef ADC_BUTTON_DEBOUNCE_DELAY
3482
       #ifndef ADC_BUTTON_DEBOUNCE_DELAY
3483
         #define ADC_BUTTON_DEBOUNCE_DELAY 16
3483
         #define ADC_BUTTON_DEBOUNCE_DELAY 16
3484
       #endif
3484
       #endif
3485
-      case Prepare_ADC_KEY: hal.adc_start(ADC_KEYPAD_PIN); break;
3485
+      case Prepare_ADC_KEY: HAL_START_ADC(ADC_KEYPAD_PIN); break;
3486
       case Measure_ADC_KEY:
3486
       case Measure_ADC_KEY:
3487
-        if (!hal.adc_ready())
3487
+        if (!HAL_ADC_READY())
3488
           next_sensor_state = adc_sensor_state; // redo this state
3488
           next_sensor_state = adc_sensor_state; // redo this state
3489
         else if (ADCKey_count < ADC_BUTTON_DEBOUNCE_DELAY) {
3489
         else if (ADCKey_count < ADC_BUTTON_DEBOUNCE_DELAY) {
3490
-          raw_ADCKey_value = hal.adc_value();
3490
+          raw_ADCKey_value = HAL_READ_ADC();
3491
           if (raw_ADCKey_value <= 900UL * HAL_ADC_RANGE / 1024UL) {
3491
           if (raw_ADCKey_value <= 900UL * HAL_ADC_RANGE / 1024UL) {
3492
             NOMORE(current_ADCKey_raw, raw_ADCKey_value);
3492
             NOMORE(current_ADCKey_raw, raw_ADCKey_value);
3493
             ADCKey_count++;
3493
             ADCKey_count++;

+ 2
- 2
ini/native.ini View File

34
 [simulator_common]
34
 [simulator_common]
35
 platform          = native
35
 platform          = native
36
 framework         =
36
 framework         =
37
-build_flags       = ${common.build_flags} -std=gnu++17 -D__PLAT_NATIVE_SIM__ -DU8G_HAL_LINKS -I/usr/include/SDL2 -IMarlin -IMarlin/src/HAL/NATIVE_SIM/u8g
37
+build_flags       = ${common.build_flags} -std=gnu++17 -D__PLAT_NATIVE_SIM__ -DU8G_HAL_LINKS -I/usr/include/SDL2 -IMarlin -IMarlin/src/HAL/NATIVE_SIM/include -IMarlin/src/HAL/NATIVE_SIM/u8g
38
 src_build_flags   = -Wall -Wno-expansion-to-defined -Wcast-align
38
 src_build_flags   = -Wall -Wno-expansion-to-defined -Wcast-align
39
 release_flags     = -g0 -O3 -flto
39
 release_flags     = -g0 -O3 -flto
40
 debug_build_flags = -fstack-protector-strong -g -g3 -ggdb
40
 debug_build_flags = -fstack-protector-strong -g -g3 -ggdb
41
 lib_compat_mode   = off
41
 lib_compat_mode   = off
42
 src_filter        = ${common.default_src_filter} +<src/HAL/NATIVE_SIM>
42
 src_filter        = ${common.default_src_filter} +<src/HAL/NATIVE_SIM>
43
 lib_deps          = ${common.lib_deps}
43
 lib_deps          = ${common.lib_deps}
44
-  MarlinSimUI=https://github.com/thinkyhead/MarlinSimUI/archive/updated_marlin_hal_2093.zip
44
+  MarlinSimUI=https://github.com/p3p/MarlinSimUI/archive/master.zip
45
   Adafruit NeoPixel=https://github.com/p3p/Adafruit_NeoPixel/archive/marlin_sim_native.zip
45
   Adafruit NeoPixel=https://github.com/p3p/Adafruit_NeoPixel/archive/marlin_sim_native.zip
46
   LiquidCrystal=https://github.com/p3p/LiquidCrystal/archive/master.zip
46
   LiquidCrystal=https://github.com/p3p/LiquidCrystal/archive/master.zip
47
 extra_scripts = ${common.extra_scripts}
47
 extra_scripts = ${common.extra_scripts}

Loading…
Cancel
Save