Selaa lähdekoodia

Retire HAL for STM32F4 / F7 (#20153)

Jason Smith 3 vuotta sitten
vanhempi
commit
3a396a25dc
No account linked to committer's email address
49 muutettua tiedostoa jossa 399 lisäystä ja 4958 poistoa
  1. 10
    11
      .github/workflows/test-builds.yml
  2. 249
    9
      Marlin/src/HAL/STM32/pinsDebug.h
  3. 0
    125
      Marlin/src/HAL/STM32/pinsDebug_STM32GENERIC.h
  4. 0
    273
      Marlin/src/HAL/STM32/pinsDebug_STM32duino.h
  5. 98
    6
      Marlin/src/HAL/STM32F1/pinsDebug.h
  6. 0
    95
      Marlin/src/HAL/STM32_F4_F7/HAL.cpp
  7. 0
    203
      Marlin/src/HAL/STM32_F4_F7/HAL.h
  8. 0
    164
      Marlin/src/HAL/STM32_F4_F7/HAL_SPI.cpp
  9. 0
    6
      Marlin/src/HAL/STM32_F4_F7/README.md
  10. 0
    12
      Marlin/src/HAL/STM32_F4_F7/STM32F4/README.md
  11. 0
    113
      Marlin/src/HAL/STM32_F4_F7/STM32F4/timers.cpp
  12. 0
    134
      Marlin/src/HAL/STM32_F4_F7/STM32F4/timers.h
  13. 0
    27
      Marlin/src/HAL/STM32_F4_F7/STM32F7/README.md
  14. 0
    898
      Marlin/src/HAL/STM32_F4_F7/STM32F7/TMC2660.cpp
  15. 0
    593
      Marlin/src/HAL/STM32_F4_F7/STM32F7/TMC2660.h
  16. 0
    127
      Marlin/src/HAL/STM32_F4_F7/STM32F7/timers.cpp
  17. 0
    107
      Marlin/src/HAL/STM32_F4_F7/STM32F7/timers.h
  18. 0
    51
      Marlin/src/HAL/STM32_F4_F7/Servo.cpp
  19. 0
    41
      Marlin/src/HAL/STM32_F4_F7/Servo.h
  20. 0
    535
      Marlin/src/HAL/STM32_F4_F7/eeprom_emul.cpp
  21. 0
    114
      Marlin/src/HAL/STM32_F4_F7/eeprom_emul.h
  22. 0
    111
      Marlin/src/HAL/STM32_F4_F7/eeprom_flash.cpp
  23. 0
    77
      Marlin/src/HAL/STM32_F4_F7/eeprom_wired.cpp
  24. 0
    49
      Marlin/src/HAL/STM32_F4_F7/endstop_interrupts.h
  25. 0
    310
      Marlin/src/HAL/STM32_F4_F7/fastio.h
  26. 0
    26
      Marlin/src/HAL/STM32_F4_F7/inc/Conditionals_LCD.h
  27. 0
    22
      Marlin/src/HAL/STM32_F4_F7/inc/Conditionals_adv.h
  28. 0
    29
      Marlin/src/HAL/STM32_F4_F7/inc/Conditionals_post.h
  29. 0
    41
      Marlin/src/HAL/STM32_F4_F7/inc/SanityCheck.h
  30. 0
    27
      Marlin/src/HAL/STM32_F4_F7/pinsDebug.h
  31. 0
    35
      Marlin/src/HAL/STM32_F4_F7/spi_pins.h
  32. 0
    28
      Marlin/src/HAL/STM32_F4_F7/timers.h
  33. 0
    57
      Marlin/src/HAL/STM32_F4_F7/watchdog.cpp
  34. 0
    27
      Marlin/src/HAL/STM32_F4_F7/watchdog.h
  35. 0
    2
      Marlin/src/HAL/platforms.h
  36. 0
    11
      Marlin/src/HAL/shared/backtrace/unwmemaccess.cpp
  37. 0
    2
      Marlin/src/HAL/shared/servo.h
  38. 24
    26
      Marlin/src/core/boards.h
  39. 1
    5
      Marlin/src/core/macros.h
  40. 1
    5
      Marlin/src/module/stepper/TMC26X.h
  41. 7
    11
      Marlin/src/pins/pins.h
  42. 2
    2
      Marlin/src/pins/stm32f1/pins_BEAST.h
  43. 0
    197
      Marlin/src/pins/stm32f4/pins_GENERIC_STM32F4.h
  44. 0
    183
      Marlin/src/pins/stm32f7/pins_THE_BORG.h
  45. 1
    1
      buildroot/tests/BIGTREE_SKR_PRO-tests
  46. 1
    1
      buildroot/tests/REMRAM_V1-tests
  47. 1
    0
      buildroot/tests/STM32F103RC_btt-tests
  48. 0
    16
      buildroot/tests/STM32F4-tests
  49. 4
    13
      platformio.ini

+ 10
- 11
.github/workflows/test-builds.yml Näytä tiedosto

@@ -54,7 +54,7 @@ jobs:
54 54
         - sanguino1284p
55 55
         - sanguino644p
56 56
 
57
-        # Extended STM32 Environments
57
+        # STM32F1 (Maple) Environments
58 58
 
59 59
         - STM32F103RC_btt
60 60
         - STM32F103RC_btt_USB
@@ -64,38 +64,37 @@ jobs:
64 64
         - STM32F103RC_meeb
65 65
         - jgaurora_a5s_a1
66 66
         - STM32F103VE_longer
67
+        - mks_robin
68
+        - mks_robin_lite
69
+        - mks_robin_pro
70
+        - STM32F103RET6_creality
71
+        - mks_robin_nano35
72
+
73
+        # STM32 (ST) Environments
74
+
67 75
         - STM32F407VE_black
68 76
         - STM32F401VE_STEVAL
69 77
         - BIGTREE_BTT002
70 78
         - BIGTREE_SKR_PRO
71 79
         - BIGTREE_GTR_V1_0
72
-        - mks_robin
73 80
         - mks_robin_stm32
74 81
         - ARMED
75 82
         - FYSETC_S6
76 83
         - STM32F070CB_malyan
77 84
         - STM32F070RB_malyan
78 85
         - malyan_M300
79
-        - mks_robin_lite
80 86
         - FLYF407ZG
81 87
         - rumba32
82
-        - mks_robin_pro
83
-        - STM32F103RET6_creality
84 88
         - LERDGEX
85
-        - mks_robin_nano35
86 89
         - mks_robin_nano35_stm32
87 90
         - NUCLEO_F767ZI
91
+        - REMRAM_V1
88 92
 
89 93
         # Put lengthy tests last
90 94
 
91 95
         - LPC1768
92 96
         - LPC1769
93 97
 
94
-        # STM32 with non-STM framework. both broken for now. they should use HAL_STM32 which is working.
95
-
96
-        #- STM32F4
97
-        #- STM32F7
98
-
99 98
         # Non-working environment tests
100 99
         #- at90usb1286_cdc
101 100
         #- STM32F103CB_malyan

+ 249
- 9
Marlin/src/HAL/STM32/pinsDebug.h Näytä tiedosto

@@ -18,17 +18,257 @@
18 18
  */
19 19
 #pragma once
20 20
 
21
-#if !(defined(NUM_DIGITAL_PINS) || defined(BOARD_NR_GPIO_PINS))
22
-  #error "M43 not supported for this board"
21
+#include <Arduino.h>
22
+
23
+#ifndef NUM_DIGITAL_PINS
24
+   // Only in ST's Arduino core (STM32duino, STM32Core)
25
+   #error "Expected NUM_DIGITAL_PINS not found"
23 26
 #endif
24 27
 
25
-// Strange - STM32F4 comes to HAL_STM32 rather than HAL_STM32F4 for these files
26
-#ifdef STM32F4
27
-  #ifdef NUM_DIGITAL_PINS            // Only in ST's Arduino core (STM32duino, STM32Core)
28
-    #include "pinsDebug_STM32duino.h"
29
-  #elif defined(BOARD_NR_GPIO_PINS)  // Only in STM32GENERIC (Maple)
30
-    #include "pinsDebug_STM32GENERIC.h"
28
+/**
29
+ *  Life gets complicated if you want an easy to use 'M43 I' output (in port/pin order)
30
+ *  because the variants in this platform do not always define all the I/O port/pins
31
+ *  that a CPU has.
32
+ *
33
+ *  VARIABLES:
34
+ *     Ard_num - Arduino pin number - defined by the platform. It is used by digitalRead and
35
+ *               digitalWrite commands and by M42.
36
+ *             - does not contain port/pin info
37
+ *             - is not in port/pin order
38
+ *             - typically a variant will only assign Ard_num to port/pins that are actually used
39
+ *     Index - M43 counter - only used to get Ard_num
40
+ *     x - a parameter/argument used to search the pin_array to try to find a signal name
41
+ *         associated with a Ard_num
42
+ *     Port_pin - port number and pin number for use with CPU registers and printing reports
43
+ *
44
+ *  Since M43 uses digitalRead and digitalWrite commands, only the Port_pins with an Ard_num
45
+ *  are accessed and/or displayed.
46
+ *
47
+ *  Three arrays are used.
48
+ *
49
+ *  digitalPin[] is provided by the platform.  It consists of the Port_pin numbers in
50
+ *  Arduino pin number order.
51
+ *
52
+ *  pin_array is a structure generated by the pins/pinsDebug.h header file.  It is generated by
53
+ *  the preprocessor. Only the signals associated with enabled options are in this table.
54
+ *  It contains:
55
+ *    - name of the signal
56
+ *    - the Ard_num assigned by the pins_YOUR_BOARD.h file using the platform defines.
57
+ *        EXAMPLE:  "#define KILL_PIN  PB1" results in Ard_num of 57.  57 is then used as the
58
+ *                  argument to digitalPinToPinName(IO) to get the Port_pin number
59
+ *    - if it is a digital or analog signal.  PWMs are considered digital here.
60
+ *
61
+ *  pin_xref is a structure generated by this header file.  It is generated by the
62
+ *  preprocessor. It is in port/pin order.  It contains just the port/pin numbers defined by the
63
+ *  platform for this variant.
64
+ *    - Ard_num
65
+ *    - printable version of Port_pin
66
+ *
67
+ *  Routines with an "x" as a parameter/argument are used to search the pin_array to try to
68
+ *  find a signal name associated with a port/pin.
69
+ *
70
+ *  NOTE -  the Arduino pin number is what is used by the M42 command, NOT the port/pin for that
71
+ *          signal.  The Arduino pin number is listed by the M43 I command.
72
+ */
73
+
74
+////////////////////////////////////////////////////////
75
+//
76
+// make a list of the Arduino pin numbers in the Port/Pin order
77
+//
78
+
79
+#define _PIN_ADD_2(NAME_ALPHA, ARDUINO_NUM) { {NAME_ALPHA}, ARDUINO_NUM },
80
+#define _PIN_ADD(NAME_ALPHA, ARDUINO_NUM) { NAME_ALPHA, ARDUINO_NUM },
81
+#define PIN_ADD(NAME) _PIN_ADD(#NAME, NAME)
82
+
83
+typedef struct {
84
+  char Port_pin_alpha[5];
85
+  pin_t Ard_num;
86
+} XrefInfo;
87
+
88
+const XrefInfo pin_xref[] PROGMEM = {
89
+  #include "pins_Xref.h"
90
+};
91
+
92
+////////////////////////////////////////////////////////////
93
+
94
+#define MODE_PIN_INPUT  0 // Input mode (reset state)
95
+#define MODE_PIN_OUTPUT 1 // General purpose output mode
96
+#define MODE_PIN_ALT    2 // Alternate function mode
97
+#define MODE_PIN_ANALOG 3 // Analog mode
98
+
99
+#define PIN_NUM(P) (P & 0x000F)
100
+#define PIN_NUM_ALPHA_LEFT(P) (((P & 0x000F) < 10) ? ('0' + (P & 0x000F)) : '1')
101
+#define PIN_NUM_ALPHA_RIGHT(P) (((P & 0x000F) > 9)  ? ('0' + (P & 0x000F) - 10) : 0 )
102
+#define PORT_NUM(P) ((P  >> 4) & 0x0007)
103
+#define PORT_ALPHA(P) ('A' + (P  >> 4))
104
+
105
+/**
106
+ * Translation of routines & variables used by pinsDebug.h
107
+ */
108
+#define NUMBER_PINS_TOTAL NUM_DIGITAL_PINS
109
+#define VALID_PIN(ANUM) ((ANUM) >= 0 && (ANUM) < NUMBER_PINS_TOTAL)
110
+#define digitalRead_mod(Ard_num) extDigitalRead(Ard_num)  // must use Arduino pin numbers when doing reads
111
+#define PRINT_PIN(Q)
112
+#define PRINT_PORT(ANUM) port_print(ANUM)
113
+#define DIGITAL_PIN_TO_ANALOG_PIN(ANUM) -1  // will report analog pin number in the print port routine
114
+#define GET_PIN_MAP_PIN_M43(Index) pin_xref[Index].Ard_num
115
+
116
+// x is a variable used to search pin_array
117
+#define GET_ARRAY_IS_DIGITAL(x) ((bool) pin_array[x].is_digital)
118
+#define GET_ARRAY_PIN(x) ((pin_t) pin_array[x].pin)
119
+#define PRINT_ARRAY_NAME(x) do{ sprintf_P(buffer, PSTR("%-" STRINGIFY(MAX_NAME_LENGTH) "s"), pin_array[x].name); SERIAL_ECHO(buffer); }while(0)
120
+#define MULTI_NAME_PAD 33 // space needed to be pretty if not first name assigned to a pin
121
+
122
+#ifndef M43_NEVER_TOUCH
123
+  #define _M43_NEVER_TOUCH(Index) (Index >= 9 && Index <= 12) // SERIAL/USB pins: PA9(TX) PA10(RX) PA11(USB_DM) PA12(USB_DP)
124
+  #ifdef KILL_PIN
125
+    #define M43_NEVER_TOUCH(Index) m43_never_touch(Index)
126
+
127
+    bool m43_never_touch(const pin_t Index) {
128
+      static pin_t M43_kill_index = -1;
129
+      if (M43_kill_index < 0)
130
+        for (M43_kill_index = 0; M43_kill_index < NUMBER_PINS_TOTAL; M43_kill_index++)
131
+          if (KILL_PIN == GET_PIN_MAP_PIN_M43(M43_kill_index)) break;
132
+      return _M43_NEVER_TOUCH(Index) || Index == M43_kill_index; // KILL_PIN and SERIAL/USB
133
+    }
31 134
   #else
32
-    #error "M43 not supported for this board"
135
+    #define M43_NEVER_TOUCH(Index) _M43_NEVER_TOUCH(Index)
33 136
   #endif
34 137
 #endif
138
+
139
+uint8_t get_pin_mode(const pin_t Ard_num) {
140
+  uint32_t mode_all = 0;
141
+  const PinName dp = digitalPinToPinName(Ard_num);
142
+  switch (PORT_ALPHA(dp)) {
143
+    case 'A' : mode_all = GPIOA->MODER; break;
144
+    case 'B' : mode_all = GPIOB->MODER; break;
145
+    case 'C' : mode_all = GPIOC->MODER; break;
146
+    case 'D' : mode_all = GPIOD->MODER; break;
147
+    #ifdef PE_0
148
+      case 'E' : mode_all = GPIOE->MODER; break;
149
+    #elif defined(PF_0)
150
+      case 'F' : mode_all = GPIOF->MODER; break;
151
+    #elif defined(PG_0)
152
+      case 'G' : mode_all = GPIOG->MODER; break;
153
+    #elif defined(PH_0)
154
+      case 'H' : mode_all = GPIOH->MODER; break;
155
+    #elif defined(PI_0)
156
+      case 'I' : mode_all = GPIOI->MODER; break;
157
+    #elif defined(PJ_0)
158
+      case 'J' : mode_all = GPIOJ->MODER; break;
159
+    #elif defined(PK_0)
160
+      case 'K' : mode_all = GPIOK->MODER; break;
161
+    #elif defined(PL_0)
162
+      case 'L' : mode_all = GPIOL->MODER; break;
163
+    #endif
164
+  }
165
+  return (mode_all >> (2 * uint8_t(PIN_NUM(dp)))) & 0x03;
166
+}
167
+
168
+bool GET_PINMODE(const pin_t Ard_num) {
169
+  const uint8_t pin_mode = get_pin_mode(Ard_num);
170
+  return pin_mode == MODE_PIN_OUTPUT || pin_mode == MODE_PIN_ALT;  // assume all alt definitions are PWM
171
+}
172
+
173
+int8_t digital_pin_to_analog_pin(pin_t Ard_num) {
174
+  Ard_num -= NUM_ANALOG_FIRST;
175
+  return (Ard_num >= 0 && Ard_num < NUM_ANALOG_INPUTS) ? Ard_num : -1;
176
+}
177
+
178
+bool IS_ANALOG(const pin_t Ard_num) {
179
+  return get_pin_mode(Ard_num) == MODE_PIN_ANALOG;
180
+}
181
+
182
+bool is_digital(const pin_t x) {
183
+  const uint8_t pin_mode = get_pin_mode(pin_array[x].pin);
184
+  return pin_mode == MODE_PIN_INPUT || pin_mode == MODE_PIN_OUTPUT;
185
+}
186
+
187
+void port_print(const pin_t Ard_num) {
188
+  char buffer[16];
189
+  pin_t Index;
190
+  for (Index = 0; Index < NUMBER_PINS_TOTAL; Index++)
191
+    if (Ard_num == GET_PIN_MAP_PIN_M43(Index)) break;
192
+
193
+  const char * ppa = pin_xref[Index].Port_pin_alpha;
194
+  sprintf_P(buffer, PSTR("%s"), ppa);
195
+  SERIAL_ECHO(buffer);
196
+  if (ppa[3] == '\0') SERIAL_CHAR(' ');
197
+
198
+  // print analog pin number
199
+  const int8_t Port_pin = digital_pin_to_analog_pin(Ard_num);
200
+  if (Port_pin >= 0) {
201
+    sprintf_P(buffer, PSTR(" (A%d) "), Port_pin);
202
+    SERIAL_ECHO(buffer);
203
+    if (Port_pin < 10) SERIAL_CHAR(' ');
204
+  }
205
+  else
206
+    SERIAL_ECHO_SP(7);
207
+
208
+  // Print number to be used with M42
209
+  sprintf_P(buffer, PSTR(" M42 P%d "), Ard_num);
210
+  SERIAL_ECHO(buffer);
211
+  if (Ard_num < 10) SERIAL_CHAR(' ');
212
+  if (Ard_num < 100) SERIAL_CHAR(' ');
213
+}
214
+
215
+bool pwm_status(const pin_t Ard_num) {
216
+  return get_pin_mode(Ard_num) == MODE_PIN_ALT;
217
+}
218
+
219
+void pwm_details(const pin_t Ard_num) {
220
+  if (pwm_status(Ard_num)) {
221
+    uint32_t alt_all = 0;
222
+    const PinName dp = digitalPinToPinName(Ard_num);
223
+    pin_t pin_number = uint8_t(PIN_NUM(dp));
224
+    const bool over_7 = pin_number >= 8;
225
+    const uint8_t ind = over_7 ? 1 : 0;
226
+    switch (PORT_ALPHA(dp)) {  // get alt function
227
+      case 'A' : alt_all = GPIOA->AFR[ind]; break;
228
+      case 'B' : alt_all = GPIOB->AFR[ind]; break;
229
+      case 'C' : alt_all = GPIOC->AFR[ind]; break;
230
+      case 'D' : alt_all = GPIOD->AFR[ind]; break;
231
+      #ifdef PE_0
232
+        case 'E' : alt_all = GPIOE->AFR[ind]; break;
233
+      #elif defined (PF_0)
234
+        case 'F' : alt_all = GPIOF->AFR[ind]; break;
235
+      #elif defined (PG_0)
236
+        case 'G' : alt_all = GPIOG->AFR[ind]; break;
237
+      #elif defined (PH_0)
238
+        case 'H' : alt_all = GPIOH->AFR[ind]; break;
239
+      #elif defined (PI_0)
240
+        case 'I' : alt_all = GPIOI->AFR[ind]; break;
241
+      #elif defined (PJ_0)
242
+        case 'J' : alt_all = GPIOJ->AFR[ind]; break;
243
+      #elif defined (PK_0)
244
+        case 'K' : alt_all = GPIOK->AFR[ind]; break;
245
+      #elif defined (PL_0)
246
+        case 'L' : alt_all = GPIOL->AFR[ind]; break;
247
+      #endif
248
+    }
249
+    if (over_7) pin_number -= 8;
250
+
251
+    uint8_t alt_func = (alt_all >> (4 * pin_number)) & 0x0F;
252
+    SERIAL_ECHOPAIR("Alt Function: ", alt_func);
253
+    if (alt_func < 10) SERIAL_CHAR(' ');
254
+    SERIAL_ECHOPGM(" - ");
255
+    switch (alt_func) {
256
+      case  0 : SERIAL_ECHOPGM("system (misc. I/O)"); break;
257
+      case  1 : SERIAL_ECHOPGM("TIM1/TIM2 (probably PWM)"); break;
258
+      case  2 : SERIAL_ECHOPGM("TIM3..5 (probably PWM)"); break;
259
+      case  3 : SERIAL_ECHOPGM("TIM8..11 (probably PWM)"); break;
260
+      case  4 : SERIAL_ECHOPGM("I2C1..3"); break;
261
+      case  5 : SERIAL_ECHOPGM("SPI1/SPI2"); break;
262
+      case  6 : SERIAL_ECHOPGM("SPI3"); break;
263
+      case  7 : SERIAL_ECHOPGM("USART1..3"); break;
264
+      case  8 : SERIAL_ECHOPGM("USART4..6"); break;
265
+      case  9 : SERIAL_ECHOPGM("CAN1/CAN2, TIM12..14  (probably PWM)"); break;
266
+      case 10 : SERIAL_ECHOPGM("OTG"); break;
267
+      case 11 : SERIAL_ECHOPGM("ETH"); break;
268
+      case 12 : SERIAL_ECHOPGM("FSMC, SDIO, OTG"); break;
269
+      case 13 : SERIAL_ECHOPGM("DCMI"); break;
270
+      case 14 : SERIAL_ECHOPGM("unused (shouldn't see this)"); break;
271
+      case 15 : SERIAL_ECHOPGM("EVENTOUT"); break;
272
+    }
273
+  }
274
+} // pwm_details

+ 0
- 125
Marlin/src/HAL/STM32/pinsDebug_STM32GENERIC.h Näytä tiedosto

@@ -1,125 +0,0 @@
1
-/**
2
- * Marlin 3D Printer Firmware
3
- * Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
4
- *
5
- * This program is free software: you can redistribute it and/or modify
6
- * it under the terms of the GNU General Public License as published by
7
- * the Free Software Foundation, either version 3 of the License, or
8
- * (at your option) any later version.
9
- *
10
- * This program is distributed in the hope that it will be useful,
11
- * but WITHOUT ANY WARRANTY; without even the implied warranty of
12
- * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the
13
- * GNU General Public License for more details.
14
- *
15
- * You should have received a copy of the GNU General Public License
16
- * along with this program.  If not, see <https://www.gnu.org/licenses/>.
17
- *
18
- */
19
-#pragma once
20
-
21
-/**
22
- * Support routines for STM32GENERIC (Maple)
23
- */
24
-
25
-/**
26
- * Translation of routines & variables used by pinsDebug.h
27
- */
28
-
29
-#ifdef BOARD_NR_GPIO_PINS  // Only in STM32GENERIC (Maple)
30
-
31
-#ifdef __STM32F1__
32
-  #include "../STM32F1/fastio.h"
33
-#elif defined(STM32F4) || defined(STM32F7)
34
-  #include "../STM32_F4_F7/fastio.h"
35
-#else
36
-  #include "fastio.h"
37
-#endif
38
-
39
-extern const stm32_pin_info PIN_MAP[BOARD_NR_GPIO_PINS];
40
-
41
-#define NUM_DIGITAL_PINS BOARD_NR_GPIO_PINS
42
-#define NUMBER_PINS_TOTAL BOARD_NR_GPIO_PINS
43
-#define VALID_PIN(pin) (pin >= 0 && pin < BOARD_NR_GPIO_PINS)
44
-#define GET_ARRAY_PIN(p) pin_t(pin_array[p].pin)
45
-#define pwm_status(pin) PWM_PIN(pin)
46
-#define digitalRead_mod(p) extDigitalRead(p)
47
-#define PRINT_PIN(p) do{ sprintf_P(buffer, PSTR("%3hd "), int16_t(p)); SERIAL_ECHO(buffer); }while(0)
48
-#define PRINT_PORT(p) print_port(p)
49
-#define PRINT_ARRAY_NAME(x) do{ sprintf_P(buffer, PSTR("%-" STRINGIFY(MAX_NAME_LENGTH) "s"), pin_array[x].name); SERIAL_ECHO(buffer); }while(0)
50
-#define MULTI_NAME_PAD 21 // space needed to be pretty if not first name assigned to a pin
51
-
52
-// pins that will cause hang/reset/disconnect in M43 Toggle and Watch utilities
53
-#ifndef M43_NEVER_TOUCH
54
-  #define M43_NEVER_TOUCH(Q) (Q >= 9 && Q <= 12) // SERIAL/USB pins PA9(TX) PA10(RX)
55
-#endif
56
-
57
-static inline int8_t get_pin_mode(pin_t pin) {
58
-  return VALID_PIN(pin) ? _GET_MODE(pin) : -1;
59
-}
60
-
61
-static inline pin_t DIGITAL_PIN_TO_ANALOG_PIN(pin_t pin) {
62
-  if (!VALID_PIN(pin)) return -1;
63
-  int8_t adc_channel = int8_t(PIN_MAP[pin].adc_channel);
64
-  #ifdef NUM_ANALOG_INPUTS
65
-    if (adc_channel >= NUM_ANALOG_INPUTS) adc_channel = ADCx;
66
-  #endif
67
-  return pin_t(adc_channel);
68
-}
69
-
70
-static inline bool IS_ANALOG(pin_t pin) {
71
-  if (!VALID_PIN(pin)) return false;
72
-  if (PIN_MAP[pin].adc_channel != ADCx) {
73
-    #ifdef NUM_ANALOG_INPUTS
74
-      if (PIN_MAP[pin].adc_channel >= NUM_ANALOG_INPUTS) return false;
75
-    #endif
76
-    return _GET_MODE(pin) == GPIO_INPUT_ANALOG && !M43_NEVER_TOUCH(pin);
77
-  }
78
-  return false;
79
-}
80
-
81
-static inline bool GET_PINMODE(const pin_t pin) {
82
-  return VALID_PIN(pin) && !IS_INPUT(pin);
83
-}
84
-
85
-static inline bool GET_ARRAY_IS_DIGITAL(const int16_t array_pin) {
86
-  const pin_t pin = GET_ARRAY_PIN(array_pin);
87
-  return (!IS_ANALOG(pin)
88
-    #ifdef NUM_ANALOG_INPUTS
89
-      || PIN_MAP[pin].adc_channel >= NUM_ANALOG_INPUTS
90
-    #endif
91
-  );
92
-}
93
-
94
-#include "../../inc/MarlinConfig.h" // Allow pins/pins.h to set density
95
-
96
-static inline void pwm_details(const pin_t pin) {
97
-  if (PWM_PIN(pin)) {
98
-    timer_dev * const tdev = PIN_MAP[pin].timer_device;
99
-    const uint8_t channel = PIN_MAP[pin].timer_channel;
100
-    const char num = (
101
-      #if EITHER(STM32_HIGH_DENSITY, STM32_XL_DENSITY)
102
-        tdev == &timer8 ? '8' :
103
-        tdev == &timer5 ? '5' :
104
-      #endif
105
-      tdev == &timer4 ? '4' :
106
-      tdev == &timer3 ? '3' :
107
-      tdev == &timer2 ? '2' :
108
-      tdev == &timer1 ? '1' : '?'
109
-    );
110
-    char buffer[10];
111
-    sprintf_P(buffer, PSTR(" TIM%c CH%c"), num, ('0' + channel));
112
-    SERIAL_ECHO(buffer);
113
-  }
114
-}
115
-
116
-static inline void print_port(pin_t pin) {
117
-  const char port = 'A' + char(pin >> 4); // pin div 16
118
-  const int16_t gbit = PIN_MAP[pin].gpio_bit;
119
-  char buffer[8];
120
-  sprintf_P(buffer, PSTR("P%c%hd "), port, gbit);
121
-  if (gbit < 10) SERIAL_CHAR(' ');
122
-  SERIAL_ECHO(buffer);
123
-}
124
-
125
-#endif // BOARD_NR_GPIO_PINS

+ 0
- 273
Marlin/src/HAL/STM32/pinsDebug_STM32duino.h Näytä tiedosto

@@ -1,273 +0,0 @@
1
-/**
2
- * Marlin 3D Printer Firmware
3
- * Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
4
- *
5
- * This program is free software: you can redistribute it and/or modify
6
- * it under the terms of the GNU General Public License as published by
7
- * the Free Software Foundation, either version 3 of the License, or
8
- * (at your option) any later version.
9
- *
10
- * This program is distributed in the hope that it will be useful,
11
- * but WITHOUT ANY WARRANTY; without even the implied warranty of
12
- * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the
13
- * GNU General Public License for more details.
14
- *
15
- * You should have received a copy of the GNU General Public License
16
- * along with this program.  If not, see <https://www.gnu.org/licenses/>.
17
- *
18
- */
19
-#pragma once
20
-
21
-#include <Arduino.h>
22
-
23
-#ifdef NUM_DIGITAL_PINS  // Only in ST's Arduino core (STM32duino, STM32Core)
24
-
25
-/**
26
- *  Life gets complicated if you want an easy to use 'M43 I' output (in port/pin order)
27
- *  because the variants in this platform do not always define all the I/O port/pins
28
- *  that a CPU has.
29
- *
30
- *  VARIABLES:
31
- *     Ard_num - Arduino pin number - defined by the platform. It is used by digitalRead and
32
- *               digitalWrite commands and by M42.
33
- *             - does not contain port/pin info
34
- *             - is not in port/pin order
35
- *             - typically a variant will only assign Ard_num to port/pins that are actually used
36
- *     Index - M43 counter - only used to get Ard_num
37
- *     x - a parameter/argument used to search the pin_array to try to find a signal name
38
- *         associated with a Ard_num
39
- *     Port_pin - port number and pin number for use with CPU registers and printing reports
40
- *
41
- *  Since M43 uses digitalRead and digitalWrite commands, only the Port_pins with an Ard_num
42
- *  are accessed and/or displayed.
43
- *
44
- *  Three arrays are used.
45
- *
46
- *  digitalPin[] is provided by the platform.  It consists of the Port_pin numbers in
47
- *  Arduino pin number order.
48
- *
49
- *  pin_array is a structure generated by the pins/pinsDebug.h header file.  It is generated by
50
- *  the preprocessor. Only the signals associated with enabled options are in this table.
51
- *  It contains:
52
- *    - name of the signal
53
- *    - the Ard_num assigned by the pins_YOUR_BOARD.h file using the platform defines.
54
- *        EXAMPLE:  "#define KILL_PIN  PB1" results in Ard_num of 57.  57 is then used as the
55
- *                  argument to digitalPinToPinName(IO) to get the Port_pin number
56
- *    - if it is a digital or analog signal.  PWMs are considered digital here.
57
- *
58
- *  pin_xref is a structure generated by this header file.  It is generated by the
59
- *  preprocessor. It is in port/pin order.  It contains just the port/pin numbers defined by the
60
- *  platform for this variant.
61
- *    - Ard_num
62
- *    - printable version of Port_pin
63
- *
64
- *  Routines with an "x" as a parameter/argument are used to search the pin_array to try to
65
- *  find a signal name associated with a port/pin.
66
- *
67
- *  NOTE -  the Arduino pin number is what is used by the M42 command, NOT the port/pin for that
68
- *          signal.  The Arduino pin number is listed by the M43 I command.
69
- */
70
-
71
-////////////////////////////////////////////////////////
72
-//
73
-// make a list of the Arduino pin numbers in the Port/Pin order
74
-//
75
-
76
-#define _PIN_ADD_2(NAME_ALPHA, ARDUINO_NUM) { {NAME_ALPHA}, ARDUINO_NUM },
77
-#define _PIN_ADD(NAME_ALPHA, ARDUINO_NUM) { NAME_ALPHA, ARDUINO_NUM },
78
-#define PIN_ADD(NAME) _PIN_ADD(#NAME, NAME)
79
-
80
-typedef struct {
81
-  char Port_pin_alpha[5];
82
-  pin_t Ard_num;
83
-} XrefInfo;
84
-
85
-const XrefInfo pin_xref[] PROGMEM = {
86
-  #include "pins_Xref.h"
87
-};
88
-
89
-////////////////////////////////////////////////////////////
90
-
91
-#define MODE_PIN_INPUT  0 // Input mode (reset state)
92
-#define MODE_PIN_OUTPUT 1 // General purpose output mode
93
-#define MODE_PIN_ALT    2 // Alternate function mode
94
-#define MODE_PIN_ANALOG 3 // Analog mode
95
-
96
-#define PIN_NUM(P) (P & 0x000F)
97
-#define PIN_NUM_ALPHA_LEFT(P) (((P & 0x000F) < 10) ? ('0' + (P & 0x000F)) : '1')
98
-#define PIN_NUM_ALPHA_RIGHT(P) (((P & 0x000F) > 9)  ? ('0' + (P & 0x000F) - 10) : 0 )
99
-#define PORT_NUM(P) ((P  >> 4) & 0x0007)
100
-#define PORT_ALPHA(P) ('A' + (P  >> 4))
101
-
102
-/**
103
- * Translation of routines & variables used by pinsDebug.h
104
- */
105
-#define NUMBER_PINS_TOTAL NUM_DIGITAL_PINS
106
-#define VALID_PIN(ANUM) ((ANUM) >= 0 && (ANUM) < NUMBER_PINS_TOTAL)
107
-#define digitalRead_mod(Ard_num) extDigitalRead(Ard_num)  // must use Arduino pin numbers when doing reads
108
-#define PRINT_PIN(Q)
109
-#define PRINT_PORT(ANUM) port_print(ANUM)
110
-#define DIGITAL_PIN_TO_ANALOG_PIN(ANUM) -1  // will report analog pin number in the print port routine
111
-#define GET_PIN_MAP_PIN_M43(Index) pin_xref[Index].Ard_num
112
-
113
-// x is a variable used to search pin_array
114
-#define GET_ARRAY_IS_DIGITAL(x) ((bool) pin_array[x].is_digital)
115
-#define GET_ARRAY_PIN(x) ((pin_t) pin_array[x].pin)
116
-#define PRINT_ARRAY_NAME(x) do{ sprintf_P(buffer, PSTR("%-" STRINGIFY(MAX_NAME_LENGTH) "s"), pin_array[x].name); SERIAL_ECHO(buffer); }while(0)
117
-#define MULTI_NAME_PAD 33 // space needed to be pretty if not first name assigned to a pin
118
-
119
-#ifndef M43_NEVER_TOUCH
120
-  #define _M43_NEVER_TOUCH(Index) (Index >= 9 && Index <= 12) // SERIAL/USB pins: PA9(TX) PA10(RX) PA11(USB_DM) PA12(USB_DP)
121
-  #ifdef KILL_PIN
122
-    #define M43_NEVER_TOUCH(Index) m43_never_touch(Index)
123
-
124
-    bool m43_never_touch(const pin_t Index) {
125
-      static pin_t M43_kill_index = -1;
126
-      if (M43_kill_index < 0)
127
-        for (M43_kill_index = 0; M43_kill_index < NUMBER_PINS_TOTAL; M43_kill_index++)
128
-          if (KILL_PIN == GET_PIN_MAP_PIN_M43(M43_kill_index)) break;
129
-      return _M43_NEVER_TOUCH(Index) || Index == M43_kill_index; // KILL_PIN and SERIAL/USB
130
-    }
131
-  #else
132
-    #define M43_NEVER_TOUCH(Index) _M43_NEVER_TOUCH(Index)
133
-  #endif
134
-#endif
135
-
136
-uint8_t get_pin_mode(const pin_t Ard_num) {
137
-  uint32_t mode_all = 0;
138
-  const PinName dp = digitalPinToPinName(Ard_num);
139
-  switch (PORT_ALPHA(dp)) {
140
-    case 'A' : mode_all = GPIOA->MODER; break;
141
-    case 'B' : mode_all = GPIOB->MODER; break;
142
-    case 'C' : mode_all = GPIOC->MODER; break;
143
-    case 'D' : mode_all = GPIOD->MODER; break;
144
-    #ifdef PE_0
145
-      case 'E' : mode_all = GPIOE->MODER; break;
146
-    #elif defined(PF_0)
147
-      case 'F' : mode_all = GPIOF->MODER; break;
148
-    #elif defined(PG_0)
149
-      case 'G' : mode_all = GPIOG->MODER; break;
150
-    #elif defined(PH_0)
151
-      case 'H' : mode_all = GPIOH->MODER; break;
152
-    #elif defined(PI_0)
153
-      case 'I' : mode_all = GPIOI->MODER; break;
154
-    #elif defined(PJ_0)
155
-      case 'J' : mode_all = GPIOJ->MODER; break;
156
-    #elif defined(PK_0)
157
-      case 'K' : mode_all = GPIOK->MODER; break;
158
-    #elif defined(PL_0)
159
-      case 'L' : mode_all = GPIOL->MODER; break;
160
-    #endif
161
-  }
162
-  return (mode_all >> (2 * uint8_t(PIN_NUM(dp)))) & 0x03;
163
-}
164
-
165
-bool GET_PINMODE(const pin_t Ard_num) {
166
-  const uint8_t pin_mode = get_pin_mode(Ard_num);
167
-  return pin_mode == MODE_PIN_OUTPUT || pin_mode == MODE_PIN_ALT;  // assume all alt definitions are PWM
168
-}
169
-
170
-int8_t digital_pin_to_analog_pin(pin_t Ard_num) {
171
-  Ard_num -= NUM_ANALOG_FIRST;
172
-  return (Ard_num >= 0 && Ard_num < NUM_ANALOG_INPUTS) ? Ard_num : -1;
173
-}
174
-
175
-bool IS_ANALOG(const pin_t Ard_num) {
176
-  return get_pin_mode(Ard_num) == MODE_PIN_ANALOG;
177
-}
178
-
179
-bool is_digital(const pin_t x) {
180
-  const uint8_t pin_mode = get_pin_mode(pin_array[x].pin);
181
-  return pin_mode == MODE_PIN_INPUT || pin_mode == MODE_PIN_OUTPUT;
182
-}
183
-
184
-void port_print(const pin_t Ard_num) {
185
-  char buffer[16];
186
-  pin_t Index;
187
-  for (Index = 0; Index < NUMBER_PINS_TOTAL; Index++)
188
-    if (Ard_num == GET_PIN_MAP_PIN_M43(Index)) break;
189
-
190
-  const char * ppa = pin_xref[Index].Port_pin_alpha;
191
-  sprintf_P(buffer, PSTR("%s"), ppa);
192
-  SERIAL_ECHO(buffer);
193
-  if (ppa[3] == '\0') SERIAL_CHAR(' ');
194
-
195
-  // print analog pin number
196
-  const int8_t Port_pin = digital_pin_to_analog_pin(Ard_num);
197
-  if (Port_pin >= 0) {
198
-    sprintf_P(buffer, PSTR(" (A%d) "), Port_pin);
199
-    SERIAL_ECHO(buffer);
200
-    if (Port_pin < 10) SERIAL_CHAR(' ');
201
-  }
202
-  else
203
-    SERIAL_ECHO_SP(7);
204
-
205
-  // Print number to be used with M42
206
-  sprintf_P(buffer, PSTR(" M42 P%d "), Ard_num);
207
-  SERIAL_ECHO(buffer);
208
-  if (Ard_num < 10) SERIAL_CHAR(' ');
209
-  if (Ard_num < 100) SERIAL_CHAR(' ');
210
-}
211
-
212
-bool pwm_status(const pin_t Ard_num) {
213
-  return get_pin_mode(Ard_num) == MODE_PIN_ALT;
214
-}
215
-
216
-void pwm_details(const pin_t Ard_num) {
217
-  if (pwm_status(Ard_num)) {
218
-    uint32_t alt_all = 0;
219
-    const PinName dp = digitalPinToPinName(Ard_num);
220
-    pin_t pin_number = uint8_t(PIN_NUM(dp));
221
-    const bool over_7 = pin_number >= 8;
222
-    const uint8_t ind = over_7 ? 1 : 0;
223
-    switch (PORT_ALPHA(dp)) {  // get alt function
224
-      case 'A' : alt_all = GPIOA->AFR[ind]; break;
225
-      case 'B' : alt_all = GPIOB->AFR[ind]; break;
226
-      case 'C' : alt_all = GPIOC->AFR[ind]; break;
227
-      case 'D' : alt_all = GPIOD->AFR[ind]; break;
228
-      #ifdef PE_0
229
-        case 'E' : alt_all = GPIOE->AFR[ind]; break;
230
-      #elif defined (PF_0)
231
-        case 'F' : alt_all = GPIOF->AFR[ind]; break;
232
-      #elif defined (PG_0)
233
-        case 'G' : alt_all = GPIOG->AFR[ind]; break;
234
-      #elif defined (PH_0)
235
-        case 'H' : alt_all = GPIOH->AFR[ind]; break;
236
-      #elif defined (PI_0)
237
-        case 'I' : alt_all = GPIOI->AFR[ind]; break;
238
-      #elif defined (PJ_0)
239
-        case 'J' : alt_all = GPIOJ->AFR[ind]; break;
240
-      #elif defined (PK_0)
241
-        case 'K' : alt_all = GPIOK->AFR[ind]; break;
242
-      #elif defined (PL_0)
243
-        case 'L' : alt_all = GPIOL->AFR[ind]; break;
244
-      #endif
245
-    }
246
-    if (over_7) pin_number -= 8;
247
-
248
-    uint8_t alt_func = (alt_all >> (4 * pin_number)) & 0x0F;
249
-    SERIAL_ECHOPAIR("Alt Function: ", alt_func);
250
-    if (alt_func < 10) SERIAL_CHAR(' ');
251
-    SERIAL_ECHOPGM(" - ");
252
-    switch (alt_func) {
253
-      case  0 : SERIAL_ECHOPGM("system (misc. I/O)"); break;
254
-      case  1 : SERIAL_ECHOPGM("TIM1/TIM2 (probably PWM)"); break;
255
-      case  2 : SERIAL_ECHOPGM("TIM3..5 (probably PWM)"); break;
256
-      case  3 : SERIAL_ECHOPGM("TIM8..11 (probably PWM)"); break;
257
-      case  4 : SERIAL_ECHOPGM("I2C1..3"); break;
258
-      case  5 : SERIAL_ECHOPGM("SPI1/SPI2"); break;
259
-      case  6 : SERIAL_ECHOPGM("SPI3"); break;
260
-      case  7 : SERIAL_ECHOPGM("USART1..3"); break;
261
-      case  8 : SERIAL_ECHOPGM("USART4..6"); break;
262
-      case  9 : SERIAL_ECHOPGM("CAN1/CAN2, TIM12..14  (probably PWM)"); break;
263
-      case 10 : SERIAL_ECHOPGM("OTG"); break;
264
-      case 11 : SERIAL_ECHOPGM("ETH"); break;
265
-      case 12 : SERIAL_ECHOPGM("FSMC, SDIO, OTG"); break;
266
-      case 13 : SERIAL_ECHOPGM("DCMI"); break;
267
-      case 14 : SERIAL_ECHOPGM("unused (shouldn't see this)"); break;
268
-      case 15 : SERIAL_ECHOPGM("EVENTOUT"); break;
269
-    }
270
-  }
271
-} // pwm_details
272
-
273
-#endif // NUM_DIGITAL_PINS

+ 98
- 6
Marlin/src/HAL/STM32F1/pinsDebug.h Näytä tiedosto

@@ -18,10 +18,102 @@
18 18
  */
19 19
 #pragma once
20 20
 
21
-#ifdef NUM_DIGITAL_PINS             // Only in ST's Arduino core (STM32duino, STM32Core)
22
-  #include "../STM32/pinsDebug_STM32duino.h"
23
-#elif defined(BOARD_NR_GPIO_PINS)   // Only in STM32GENERIC (Maple)
24
-  #include "../STM32/pinsDebug_STM32GENERIC.h"
25
-#else
26
-  #error "M43 not supported for this board"
21
+/**
22
+ * Support routines for STM32GENERIC (Maple)
23
+ */
24
+
25
+/**
26
+ * Translation of routines & variables used by pinsDebug.h
27
+ */
28
+
29
+#ifndef BOARD_NR_GPIO_PINS  // Only in STM32GENERIC (Maple)
30
+   #error "Expected BOARD_NR_GPIO_PINS not found"
27 31
 #endif
32
+
33
+#include "fastio.h"
34
+
35
+extern const stm32_pin_info PIN_MAP[BOARD_NR_GPIO_PINS];
36
+
37
+#define NUM_DIGITAL_PINS BOARD_NR_GPIO_PINS
38
+#define NUMBER_PINS_TOTAL BOARD_NR_GPIO_PINS
39
+#define VALID_PIN(pin) (pin >= 0 && pin < BOARD_NR_GPIO_PINS)
40
+#define GET_ARRAY_PIN(p) pin_t(pin_array[p].pin)
41
+#define pwm_status(pin) PWM_PIN(pin)
42
+#define digitalRead_mod(p) extDigitalRead(p)
43
+#define PRINT_PIN(p) do{ sprintf_P(buffer, PSTR("%3hd "), int16_t(p)); SERIAL_ECHO(buffer); }while(0)
44
+#define PRINT_PORT(p) print_port(p)
45
+#define PRINT_ARRAY_NAME(x) do{ sprintf_P(buffer, PSTR("%-" STRINGIFY(MAX_NAME_LENGTH) "s"), pin_array[x].name); SERIAL_ECHO(buffer); }while(0)
46
+#define MULTI_NAME_PAD 21 // space needed to be pretty if not first name assigned to a pin
47
+
48
+// pins that will cause hang/reset/disconnect in M43 Toggle and Watch utilities
49
+#ifndef M43_NEVER_TOUCH
50
+  #define M43_NEVER_TOUCH(Q) (Q >= 9 && Q <= 12) // SERIAL/USB pins PA9(TX) PA10(RX)
51
+#endif
52
+
53
+static inline int8_t get_pin_mode(pin_t pin) {
54
+  return VALID_PIN(pin) ? _GET_MODE(pin) : -1;
55
+}
56
+
57
+static inline pin_t DIGITAL_PIN_TO_ANALOG_PIN(pin_t pin) {
58
+  if (!VALID_PIN(pin)) return -1;
59
+  int8_t adc_channel = int8_t(PIN_MAP[pin].adc_channel);
60
+  #ifdef NUM_ANALOG_INPUTS
61
+    if (adc_channel >= NUM_ANALOG_INPUTS) adc_channel = ADCx;
62
+  #endif
63
+  return pin_t(adc_channel);
64
+}
65
+
66
+static inline bool IS_ANALOG(pin_t pin) {
67
+  if (!VALID_PIN(pin)) return false;
68
+  if (PIN_MAP[pin].adc_channel != ADCx) {
69
+    #ifdef NUM_ANALOG_INPUTS
70
+      if (PIN_MAP[pin].adc_channel >= NUM_ANALOG_INPUTS) return false;
71
+    #endif
72
+    return _GET_MODE(pin) == GPIO_INPUT_ANALOG && !M43_NEVER_TOUCH(pin);
73
+  }
74
+  return false;
75
+}
76
+
77
+static inline bool GET_PINMODE(const pin_t pin) {
78
+  return VALID_PIN(pin) && !IS_INPUT(pin);
79
+}
80
+
81
+static inline bool GET_ARRAY_IS_DIGITAL(const int16_t array_pin) {
82
+  const pin_t pin = GET_ARRAY_PIN(array_pin);
83
+  return (!IS_ANALOG(pin)
84
+    #ifdef NUM_ANALOG_INPUTS
85
+      || PIN_MAP[pin].adc_channel >= NUM_ANALOG_INPUTS
86
+    #endif
87
+  );
88
+}
89
+
90
+#include "../../inc/MarlinConfig.h" // Allow pins/pins.h to set density
91
+
92
+static inline void pwm_details(const pin_t pin) {
93
+  if (PWM_PIN(pin)) {
94
+    timer_dev * const tdev = PIN_MAP[pin].timer_device;
95
+    const uint8_t channel = PIN_MAP[pin].timer_channel;
96
+    const char num = (
97
+      #if EITHER(STM32_HIGH_DENSITY, STM32_XL_DENSITY)
98
+        tdev == &timer8 ? '8' :
99
+        tdev == &timer5 ? '5' :
100
+      #endif
101
+      tdev == &timer4 ? '4' :
102
+      tdev == &timer3 ? '3' :
103
+      tdev == &timer2 ? '2' :
104
+      tdev == &timer1 ? '1' : '?'
105
+    );
106
+    char buffer[10];
107
+    sprintf_P(buffer, PSTR(" TIM%c CH%c"), num, ('0' + channel));
108
+    SERIAL_ECHO(buffer);
109
+  }
110
+}
111
+
112
+static inline void print_port(pin_t pin) {
113
+  const char port = 'A' + char(pin >> 4); // pin div 16
114
+  const int16_t gbit = PIN_MAP[pin].gpio_bit;
115
+  char buffer[8];
116
+  sprintf_P(buffer, PSTR("P%c%hd "), port, gbit);
117
+  if (gbit < 10) SERIAL_CHAR(' ');
118
+  SERIAL_ECHO(buffer);
119
+}

+ 0
- 95
Marlin/src/HAL/STM32_F4_F7/HAL.cpp Näytä tiedosto

@@ -1,95 +0,0 @@
1
-/**
2
- * Marlin 3D Printer Firmware
3
- *
4
- * Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
5
- * Copyright (c) 2016 Bob Cousins bobcousins42@googlemail.com
6
- * Copyright (c) 2015-2016 Nico Tonnhofer wurstnase.reprap@gmail.com
7
- * Copyright (c) 2017 Victor Perez
8
- *
9
- * This program is free software: you can redistribute it and/or modify
10
- * it under the terms of the GNU General Public License as published by
11
- * the Free Software Foundation, either version 3 of the License, or
12
- * (at your option) any later version.
13
- *
14
- * This program is distributed in the hope that it will be useful,
15
- * but WITHOUT ANY WARRANTY; without even the implied warranty of
16
- * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the
17
- * GNU General Public License for more details.
18
- *
19
- * You should have received a copy of the GNU General Public License
20
- * along with this program.  If not, see <https://www.gnu.org/licenses/>.
21
- *
22
- */
23
-#if defined(STM32GENERIC) && (defined(STM32F4) || defined(STM32F7))
24
-
25
-#include "HAL.h"
26
-
27
-//#include <Wire.h>
28
-
29
-// ------------------------
30
-// Public Variables
31
-// ------------------------
32
-
33
-uint16_t HAL_adc_result;
34
-
35
-// ------------------------
36
-// Public functions
37
-// ------------------------
38
-
39
-/* VGPV Done with defines
40
-// disable interrupts
41
-void cli() { noInterrupts(); }
42
-
43
-// enable interrupts
44
-void sei() { interrupts(); }
45
-*/
46
-
47
-void HAL_clear_reset_source() { __HAL_RCC_CLEAR_RESET_FLAGS(); }
48
-
49
-uint8_t HAL_get_reset_source() {
50
-  if (__HAL_RCC_GET_FLAG(RCC_FLAG_IWDGRST) != RESET) return RST_WATCHDOG;
51
-  if (__HAL_RCC_GET_FLAG(RCC_FLAG_SFTRST)  != RESET) return RST_SOFTWARE;
52
-  if (__HAL_RCC_GET_FLAG(RCC_FLAG_PINRST)  != RESET) return RST_EXTERNAL;
53
-  if (__HAL_RCC_GET_FLAG(RCC_FLAG_PORRST)  != RESET) return RST_POWER_ON;
54
-  return 0;
55
-}
56
-
57
-void _delay_ms(const int delay_ms) { delay(delay_ms); }
58
-
59
-extern "C" {
60
-  extern unsigned int _ebss; // end of bss section
61
-}
62
-
63
-// return free memory between end of heap (or end bss) and whatever is current
64
-
65
-/*
66
-#include <wirish/syscalls.c>
67
-//extern caddr_t _sbrk(int incr);
68
-#ifndef CONFIG_HEAP_END
69
-extern char _lm_heap_end;
70
-#define CONFIG_HEAP_END ((caddr_t)&_lm_heap_end)
71
-#endif
72
-
73
-extern "C" {
74
-  static int freeMemory() {
75
-    char top = 't';
76
-    return &top - reinterpret_cast<char*>(sbrk(0));
77
-  }
78
-  int freeMemory() {
79
-    int free_memory;
80
-    int heap_end = (int)_sbrk(0);
81
-    free_memory = ((int)&free_memory) - ((int)heap_end);
82
-    return free_memory;
83
-  }
84
-}
85
-*/
86
-
87
-// ------------------------
88
-// ADC
89
-// ------------------------
90
-
91
-void HAL_adc_start_conversion(const uint8_t adc_pin) { HAL_adc_result = analogRead(adc_pin); }
92
-
93
-uint16_t HAL_adc_get_result() { return HAL_adc_result; }
94
-
95
-#endif // STM32GENERIC && (STM32F4 || STM32F7)

+ 0
- 203
Marlin/src/HAL/STM32_F4_F7/HAL.h Näytä tiedosto

@@ -1,203 +0,0 @@
1
-/**
2
- * Marlin 3D Printer Firmware
3
- *
4
- * Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
5
- * Copyright (c) 2016 Bob Cousins bobcousins42@googlemail.com
6
- * Copyright (c) 2015-2016 Nico Tonnhofer wurstnase.reprap@gmail.com
7
- * Copyright (c) 2017 Victor Perez
8
- *
9
- * This program is free software: you can redistribute it and/or modify
10
- * it under the terms of the GNU General Public License as published by
11
- * the Free Software Foundation, either version 3 of the License, or
12
- * (at your option) any later version.
13
- *
14
- * This program is distributed in the hope that it will be useful,
15
- * but WITHOUT ANY WARRANTY; without even the implied warranty of
16
- * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the
17
- * GNU General Public License for more details.
18
- *
19
- * You should have received a copy of the GNU General Public License
20
- * along with this program.  If not, see <https://www.gnu.org/licenses/>.
21
- *
22
- */
23
-#pragma once
24
-
25
-#define CPU_32_BIT
26
-
27
-#include "../../inc/MarlinConfigPre.h"
28
-
29
-#include "../shared/Marduino.h"
30
-#include "../shared/math_32bit.h"
31
-#include "../shared/HAL_SPI.h"
32
-
33
-#include "fastio.h"
34
-#include "watchdog.h"
35
-
36
-#include <stdint.h>
37
-
38
-#if defined(STM32F4) && USBCON
39
-  #include <USBSerial.h>
40
-#endif
41
-
42
-// ------------------------
43
-// Defines
44
-// ------------------------
45
-
46
-// Serial override
47
-//extern HalSerial usb_serial;
48
-
49
-#define _MSERIAL(X) SerialUART##X
50
-#define MSERIAL(X) _MSERIAL(X)
51
-#define SerialUART0 Serial1
52
-
53
-#if defined(STM32F4) && SERIAL_PORT == 0
54
-  #error "SERIAL_PORT cannot be 0. (Port 0 does not exist.) Please update your configuration."
55
-#elif SERIAL_PORT == -1
56
-  #define MYSERIAL0 SerialUSB
57
-#elif WITHIN(SERIAL_PORT, 0, 6)
58
-  #define MYSERIAL0 MSERIAL(SERIAL_PORT)
59
-#else
60
-  #error "SERIAL_PORT must be from -1 to 6. Please update your configuration."
61
-#endif
62
-
63
-#ifdef SERIAL_PORT_2
64
-  #if defined(STM32F4) && SERIAL_PORT_2 == 0
65
-    #error "SERIAL_PORT_2 cannot be 0. (Port 0 does not exist.) Please update your configuration."
66
-  #elif SERIAL_PORT_2 == -1
67
-    #define MYSERIAL1 SerialUSB
68
-  #elif WITHIN(SERIAL_PORT_2, 0, 6)
69
-    #define MYSERIAL1 MSERIAL(SERIAL_PORT_2)
70
-  #else
71
-    #error "SERIAL_PORT_2 must be from -1 to 6. Please update your configuration."
72
-  #endif
73
-#endif
74
-
75
-#ifdef LCD_SERIAL_PORT
76
-  #if defined(STM32F4) && LCD_SERIAL_PORT == 0
77
-    #error "LCD_SERIAL_PORT cannot be 0. (Port 0 does not exist.) Please update your configuration."
78
-  #elif LCD_SERIAL_PORT == -1
79
-    #define LCD_SERIAL SerialUSB
80
-  #elif WITHIN(LCD_SERIAL_PORT, 0, 6)
81
-    #define LCD_SERIAL MSERIAL(LCD_SERIAL_PORT)
82
-  #else
83
-    #error "LCD_SERIAL_PORT must be from -1 to 6. Please update your configuration."
84
-  #endif
85
-#endif
86
-
87
-/**
88
- * TODO: review this to return 1 for pins that are not analog input
89
- */
90
-#ifndef analogInputToDigitalPin
91
-  #define analogInputToDigitalPin(p) (p)
92
-#endif
93
-
94
-#define CRITICAL_SECTION_START()  uint32_t primask = __get_PRIMASK(); __disable_irq()
95
-#define CRITICAL_SECTION_END()    if (!primask) __enable_irq()
96
-#define ISRS_ENABLED() (!__get_PRIMASK())
97
-#define ENABLE_ISRS()  __enable_irq()
98
-#define DISABLE_ISRS() __disable_irq()
99
-#define cli() __disable_irq()
100
-#define sei() __enable_irq()
101
-
102
-// On AVR this is in math.h?
103
-#define square(x) ((x)*(x))
104
-
105
-#ifndef strncpy_P
106
-  #define strncpy_P(dest, src, num) strncpy((dest), (src), (num))
107
-#endif
108
-
109
-// Fix bug in pgm_read_ptr
110
-#undef pgm_read_ptr
111
-#define pgm_read_ptr(addr) (*(addr))
112
-
113
-// ------------------------
114
-// Types
115
-// ------------------------
116
-
117
-typedef int8_t pin_t;
118
-
119
-#ifdef STM32F4
120
-  #define HAL_SERVO_LIB libServo
121
-#endif
122
-
123
-// ------------------------
124
-// Public Variables
125
-// ------------------------
126
-
127
-// Result of last ADC conversion
128
-extern uint16_t HAL_adc_result;
129
-
130
-// ------------------------
131
-// Public functions
132
-// ------------------------
133
-
134
-// Memory related
135
-#define __bss_end __bss_end__
136
-
137
-inline void HAL_init() {}
138
-
139
-// Clear reset reason
140
-void HAL_clear_reset_source();
141
-
142
-// Reset reason
143
-uint8_t HAL_get_reset_source();
144
-
145
-inline void HAL_reboot() {}  // reboot the board or restart the bootloader
146
-
147
-void _delay_ms(const int delay);
148
-
149
-/*
150
-extern "C" {
151
-  int freeMemory();
152
-}
153
-*/
154
-
155
-extern "C" char* _sbrk(int incr);
156
-
157
-/*
158
-int freeMemory() {
159
-  volatile int top;
160
-  top = (int)((char*)&top - reinterpret_cast<char*>(_sbrk(0)));
161
-  return top;
162
-}
163
-*/
164
-
165
-#if GCC_VERSION <= 50000
166
-  #pragma GCC diagnostic push
167
-  #pragma GCC diagnostic ignored "-Wunused-function"
168
-#endif
169
-
170
-static inline int freeMemory() {
171
-  volatile char top;
172
-  return &top - reinterpret_cast<char*>(_sbrk(0));
173
-}
174
-
175
-#if GCC_VERSION <= 50000
176
-  #pragma GCC diagnostic pop
177
-#endif
178
-
179
-//
180
-// ADC
181
-//
182
-
183
-#define HAL_ANALOG_SELECT(pin) pinMode(pin, INPUT)
184
-
185
-inline void HAL_adc_init() {}
186
-
187
-#define HAL_ADC_VREF         3.3
188
-#define HAL_ADC_RESOLUTION  10
189
-#define HAL_START_ADC(pin)  HAL_adc_start_conversion(pin)
190
-#define HAL_READ_ADC()      HAL_adc_result
191
-#define HAL_ADC_READY()     true
192
-
193
-void HAL_adc_start_conversion(const uint8_t adc_pin);
194
-uint16_t HAL_adc_get_result();
195
-
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)
199
-
200
-#ifdef STM32F4
201
-  #define JTAG_DISABLE() afio_cfg_debug_ports(AFIO_DEBUG_SW_ONLY)
202
-  #define JTAGSWD_DISABLE() afio_cfg_debug_ports(AFIO_DEBUG_NONE)
203
-#endif

+ 0
- 164
Marlin/src/HAL/STM32_F4_F7/HAL_SPI.cpp Näytä tiedosto

@@ -1,164 +0,0 @@
1
-/**
2
- * Marlin 3D Printer Firmware
3
- * Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
4
- *
5
- * Based on Sprinter and grbl.
6
- * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm
7
- * Copyright (c) 2017 Victor Perez
8
- *
9
- * This program is free software: you can redistribute it and/or modify
10
- * it under the terms of the GNU General Public License as published by
11
- * the Free Software Foundation, either version 3 of the License, or
12
- * (at your option) any later version.
13
- *
14
- * This program is distributed in the hope that it will be useful,
15
- * but WITHOUT ANY WARRANTY; without even the implied warranty of
16
- * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the
17
- * GNU General Public License for more details.
18
- *
19
- * You should have received a copy of the GNU General Public License
20
- * along with this program.  If not, see <https://www.gnu.org/licenses/>.
21
- *
22
- */
23
-#if defined(STM32GENERIC) && (defined(STM32F4) || defined(STM32F7))
24
-
25
-/**
26
- * Software SPI functions originally from Arduino Sd2Card Library
27
- * Copyright (c) 2009 by William Greiman
28
- */
29
-
30
-/**
31
- * Adapted to the Marlin STM32F4/7 HAL
32
- */
33
-
34
-#include "../../inc/MarlinConfig.h"
35
-
36
-#include <SPI.h>
37
-#include <pins_arduino.h>
38
-#include "../shared/HAL_SPI.h"
39
-#include "spi_pins.h"
40
-
41
-// ------------------------
42
-// Public Variables
43
-// ------------------------
44
-
45
-static SPISettings spiConfig;
46
-
47
-// ------------------------
48
-// Public functions
49
-// ------------------------
50
-
51
-#if ENABLED(SOFTWARE_SPI)
52
-  // ------------------------
53
-  // Software SPI
54
-  // ------------------------
55
-  #error "Software SPI not supported for STM32F4/7. Use Hardware SPI."
56
-#else
57
-
58
-// ------------------------
59
-// Hardware SPI
60
-// ------------------------
61
-
62
-/**
63
- * VGPV SPI speed start and F_CPU/2, by default 72/2 = 36Mhz
64
- */
65
-
66
-/**
67
- * @brief  Begin SPI port setup
68
- *
69
- * @return Nothing
70
- *
71
- * @details Only configures SS pin since libmaple creates and initialize the SPI object
72
- */
73
-void spiBegin() {
74
-  #if !defined(SS_PIN) || SS_PIN < 0
75
-    #error "SS_PIN not defined!"
76
-  #endif
77
-
78
-  OUT_WRITE(SS_PIN, HIGH);
79
-}
80
-
81
-/** Configure SPI for specified SPI speed */
82
-void spiInit(uint8_t spiRate) {
83
-  // Use datarates Marlin uses
84
-  uint32_t clock;
85
-  switch (spiRate) {
86
-    case SPI_FULL_SPEED:    clock = 20000000; break; // 13.9mhz=20000000  6.75mhz=10000000  3.38mhz=5000000  .833mhz=1000000
87
-    case SPI_HALF_SPEED:    clock =  5000000; break;
88
-    case SPI_QUARTER_SPEED: clock =  2500000; break;
89
-    case SPI_EIGHTH_SPEED:  clock =  1250000; break;
90
-    case SPI_SPEED_5:       clock =   625000; break;
91
-    case SPI_SPEED_6:       clock =   300000; break;
92
-    default:                clock =  4000000; // Default from the SPI libarary
93
-  }
94
-  spiConfig = SPISettings(clock, MSBFIRST, SPI_MODE0);
95
-  SPI.begin();
96
-}
97
-
98
-/**
99
- * @brief  Receives a single byte from the SPI port.
100
- *
101
- * @return Byte received
102
- *
103
- * @details
104
- */
105
-uint8_t spiRec() {
106
-  SPI.beginTransaction(spiConfig);
107
-  uint8_t returnByte = SPI.transfer(0xFF);
108
-  SPI.endTransaction();
109
-  return returnByte;
110
-}
111
-
112
-/**
113
- * @brief  Receives a number of bytes from the SPI port to a buffer
114
- *
115
- * @param  buf   Pointer to starting address of buffer to write to.
116
- * @param  nbyte Number of bytes to receive.
117
- * @return Nothing
118
- *
119
- * @details Uses DMA
120
- */
121
-void spiRead(uint8_t* buf, uint16_t nbyte) {
122
-  SPI.beginTransaction(spiConfig);
123
-  #ifndef STM32GENERIC
124
-    SPI.dmaTransfer(0, const_cast<uint8_t*>(buf), nbyte);
125
-  #else
126
-    SPI.transfer((uint8_t*)buf, nbyte);
127
-  #endif
128
-  SPI.endTransaction();
129
-}
130
-
131
-/**
132
- * @brief  Sends a single byte on SPI port
133
- *
134
- * @param  b Byte to send
135
- *
136
- * @details
137
- */
138
-void spiSend(uint8_t b) {
139
-  SPI.beginTransaction(spiConfig);
140
-  SPI.transfer(b);
141
-  SPI.endTransaction();
142
-}
143
-
144
-/**
145
- * @brief  Write token and then write from 512 byte buffer to SPI (for SD card)
146
- *
147
- * @param  buf   Pointer with buffer start address
148
- * @return Nothing
149
- *
150
- * @details Use DMA
151
- */
152
-void spiSendBlock(uint8_t token, const uint8_t* buf) {
153
-  SPI.beginTransaction(spiConfig);
154
-  SPI.transfer(token);
155
-  #ifndef STM32GENERIC
156
-    SPI.dmaSend(const_cast<uint8_t*>(buf), 512);
157
-  #else
158
-    SPI.transfer((uint8_t*)buf, nullptr, 512);
159
-  #endif
160
-  SPI.endTransaction();
161
-}
162
-
163
-#endif // SOFTWARE_SPI
164
-#endif // STM32GENERIC && (STM32F4 || STM32F7)

+ 0
- 6
Marlin/src/HAL/STM32_F4_F7/README.md Näytä tiedosto

@@ -1,6 +0,0 @@
1
-# This HAL is for...
2
-
3
-  - STM32F407 MCU with STM32Generic Arduino core by danieleff.
4
-  - STM32F765 board "The Borg" with STM32Generic.
5
-
6
-See the `README.md` files in HAL_STM32F4 and HAL_STM32F7 for the specifics of those hals.

+ 0
- 12
Marlin/src/HAL/STM32_F4_F7/STM32F4/README.md Näytä tiedosto

@@ -1,12 +0,0 @@
1
-# This HAL is for the STM32F407 MCU used with STM32Generic Arduino core by danieleff.
2
-
3
-# Arduino core is located at:
4
-
5
-https://github.com/danieleff/STM32GENERIC
6
-
7
-Unzip it into [Arduino]/hardware folder
8
-
9
-# This HAL is in development.
10
-
11
-This HAL is a modified version of Chris Barr's Picoprint STM32F4 HAL.
12
-

+ 0
- 113
Marlin/src/HAL/STM32_F4_F7/STM32F4/timers.cpp Näytä tiedosto

@@ -1,113 +0,0 @@
1
-/**
2
- * Marlin 3D Printer Firmware
3
- *
4
- * Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
5
- * Copyright (c) 2016 Bob Cousins bobcousins42@googlemail.com
6
- * Copyright (c) 2015-2016 Nico Tonnhofer wurstnase.reprap@gmail.com
7
- *
8
- * This program is free software: you can redistribute it and/or modify
9
- * it under the terms of the GNU General Public License as published by
10
- * the Free Software Foundation, either version 3 of the License, or
11
- * (at your option) any later version.
12
- *
13
- * This program is distributed in the hope that it will be useful,
14
- * but WITHOUT ANY WARRANTY; without even the implied warranty of
15
- * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the
16
- * GNU General Public License for more details.
17
- *
18
- * You should have received a copy of the GNU General Public License
19
- * along with this program.  If not, see <https://www.gnu.org/licenses/>.
20
- *
21
- */
22
-#if defined(STM32GENERIC) && defined(STM32F4)
23
-
24
-#include "../../../inc/MarlinConfig.h"
25
-
26
-// ------------------------
27
-// Local defines
28
-// ------------------------
29
-
30
-#define NUM_HARDWARE_TIMERS 2
31
-#define STEP_TIMER_IRQ_ID TIM5_IRQn
32
-#define TEMP_TIMER_IRQ_ID TIM7_IRQn
33
-
34
-// ------------------------
35
-// Private Variables
36
-// ------------------------
37
-
38
-stm32_timer_t TimerHandle[NUM_HARDWARE_TIMERS];
39
-
40
-// ------------------------
41
-// Public functions
42
-// ------------------------
43
-
44
-bool timers_initialized[NUM_HARDWARE_TIMERS] = {false};
45
-
46
-void HAL_timer_start(const uint8_t timer_num, const uint32_t frequency) {
47
-
48
-  if (!timers_initialized[timer_num]) {
49
-    constexpr uint32_t step_prescaler = STEPPER_TIMER_PRESCALE - 1,
50
-                       temp_prescaler = TEMP_TIMER_PRESCALE - 1;
51
-    switch (timer_num) {
52
-      case STEP_TIMER_NUM:
53
-        // STEPPER TIMER TIM5 - use a 32bit timer
54
-        __HAL_RCC_TIM5_CLK_ENABLE();
55
-        TimerHandle[timer_num].handle.Instance            = TIM5;
56
-        TimerHandle[timer_num].handle.Init.Prescaler      = step_prescaler;
57
-        TimerHandle[timer_num].handle.Init.CounterMode    = TIM_COUNTERMODE_UP;
58
-        TimerHandle[timer_num].handle.Init.ClockDivision  = TIM_CLOCKDIVISION_DIV1;
59
-        TimerHandle[timer_num].callback = (uint32_t)TC5_Handler;
60
-        HAL_NVIC_SetPriority(STEP_TIMER_IRQ_ID, 1, 0);
61
-        break;
62
-
63
-      case TEMP_TIMER_NUM:
64
-        // TEMP TIMER TIM7 - any available 16bit Timer (1 already used for PWM)
65
-        __HAL_RCC_TIM7_CLK_ENABLE();
66
-        TimerHandle[timer_num].handle.Instance            = TIM7;
67
-        TimerHandle[timer_num].handle.Init.Prescaler      = temp_prescaler;
68
-        TimerHandle[timer_num].handle.Init.CounterMode    = TIM_COUNTERMODE_UP;
69
-        TimerHandle[timer_num].handle.Init.ClockDivision  = TIM_CLOCKDIVISION_DIV1;
70
-        TimerHandle[timer_num].callback = (uint32_t)TC7_Handler;
71
-        HAL_NVIC_SetPriority(TEMP_TIMER_IRQ_ID, 2, 0);
72
-        break;
73
-    }
74
-    timers_initialized[timer_num] = true;
75
-  }
76
-
77
-  TimerHandle[timer_num].handle.Init.Period = (((HAL_TIMER_RATE) / TimerHandle[timer_num].handle.Init.Prescaler) / frequency) - 1;
78
-  if (HAL_TIM_Base_Init(&TimerHandle[timer_num].handle) == HAL_OK)
79
-    HAL_TIM_Base_Start_IT(&TimerHandle[timer_num].handle);
80
-}
81
-
82
-extern "C" {
83
-  void TIM5_IRQHandler() { ((void(*)())TimerHandle[0].callback)(); }
84
-  void TIM7_IRQHandler() { ((void(*)())TimerHandle[1].callback)(); }
85
-}
86
-
87
-void HAL_timer_enable_interrupt(const uint8_t timer_num) {
88
-  switch (timer_num) {
89
-    case STEP_TIMER_NUM: HAL_NVIC_EnableIRQ(STEP_TIMER_IRQ_ID); break;
90
-    case TEMP_TIMER_NUM: HAL_NVIC_EnableIRQ(TEMP_TIMER_IRQ_ID); break;
91
-  }
92
-}
93
-
94
-void HAL_timer_disable_interrupt(const uint8_t timer_num) {
95
-  switch (timer_num) {
96
-    case STEP_TIMER_NUM: HAL_NVIC_DisableIRQ(STEP_TIMER_IRQ_ID); break;
97
-    case TEMP_TIMER_NUM: HAL_NVIC_DisableIRQ(TEMP_TIMER_IRQ_ID); break;
98
-  }
99
-  // We NEED memory barriers to ensure Interrupts are actually disabled!
100
-  // ( https://dzone.com/articles/nvic-disabling-interrupts-on-arm-cortex-m-and-the )
101
-  __DSB();
102
-  __ISB();
103
-}
104
-
105
-bool HAL_timer_interrupt_enabled(const uint8_t timer_num) {
106
-  switch (timer_num) {
107
-    case STEP_TIMER_NUM: return NVIC->ISER[(uint32_t)((int32_t)STEP_TIMER_IRQ_ID) >> 5] & (uint32_t)(1 << ((uint32_t)((int32_t)STEP_TIMER_IRQ_ID) & (uint32_t)0x1F));
108
-    case TEMP_TIMER_NUM: return NVIC->ISER[(uint32_t)((int32_t)TEMP_TIMER_IRQ_ID) >> 5] & (uint32_t)(1 << ((uint32_t)((int32_t)TEMP_TIMER_IRQ_ID) & (uint32_t)0x1F));
109
-  }
110
-  return false;
111
-}
112
-
113
-#endif // STM32GENERIC && STM32F4

+ 0
- 134
Marlin/src/HAL/STM32_F4_F7/STM32F4/timers.h Näytä tiedosto

@@ -1,134 +0,0 @@
1
-/**
2
- * Marlin 3D Printer Firmware
3
- *
4
- * Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
5
- * Copyright (c) 2016 Bob Cousins bobcousins42@googlemail.com
6
- * Copyright (c) 2017 Victor Perez
7
- *
8
- * This program is free software: you can redistribute it and/or modify
9
- * it under the terms of the GNU General Public License as published by
10
- * the Free Software Foundation, either version 3 of the License, or
11
- * (at your option) any later version.
12
- *
13
- * This program is distributed in the hope that it will be useful,
14
- * but WITHOUT ANY WARRANTY; without even the implied warranty of
15
- * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the
16
- * GNU General Public License for more details.
17
- *
18
- * You should have received a copy of the GNU General Public License
19
- * along with this program.  If not, see <https://www.gnu.org/licenses/>.
20
- *
21
- */
22
-#pragma once
23
-
24
-#include <stdint.h>
25
-
26
-// ------------------------
27
-// Defines
28
-// ------------------------
29
-
30
-#define FORCE_INLINE __attribute__((always_inline)) inline
31
-
32
-#define hal_timer_t uint32_t  // TODO: One is 16-bit, one 32-bit - does this need to be checked?
33
-#define HAL_TIMER_TYPE_MAX 0xFFFF
34
-
35
-#define HAL_TIMER_RATE         (HAL_RCC_GetSysClockFreq() / 2)  // frequency of timer peripherals
36
-
37
-#ifndef STEP_TIMER_NUM
38
-  #define STEP_TIMER_NUM        0  // Timer Index for Stepper
39
-#endif
40
-#ifndef PULSE_TIMER_NUM
41
-  #define PULSE_TIMER_NUM       STEP_TIMER_NUM
42
-#endif
43
-#ifndef TEMP_TIMER_NUM
44
-  #define TEMP_TIMER_NUM        1  // Timer Index for Temperature
45
-#endif
46
-
47
-#define TEMP_TIMER_PRESCALE     1000 // prescaler for setting Temp timer, 72Khz
48
-#define TEMP_TIMER_FREQUENCY    1000 // temperature interrupt frequency
49
-
50
-#define STEPPER_TIMER_PRESCALE 54 // was 40,prescaler for setting stepper timer, 2Mhz
51
-#define STEPPER_TIMER_RATE     (HAL_TIMER_RATE / STEPPER_TIMER_PRESCALE)   // frequency of stepper timer
52
-#define STEPPER_TIMER_TICKS_PER_US ((STEPPER_TIMER_RATE) / 1000000) // stepper timer ticks per µs
53
-
54
-#define PULSE_TIMER_RATE       STEPPER_TIMER_RATE   // frequency of pulse timer
55
-#define PULSE_TIMER_PRESCALE   STEPPER_TIMER_PRESCALE
56
-#define PULSE_TIMER_TICKS_PER_US STEPPER_TIMER_TICKS_PER_US
57
-
58
-#define ENABLE_STEPPER_DRIVER_INTERRUPT() HAL_timer_enable_interrupt(STEP_TIMER_NUM)
59
-#define DISABLE_STEPPER_DRIVER_INTERRUPT() HAL_timer_disable_interrupt(STEP_TIMER_NUM)
60
-#define STEPPER_ISR_ENABLED() HAL_timer_interrupt_enabled(STEP_TIMER_NUM)
61
-
62
-#define ENABLE_TEMPERATURE_INTERRUPT() HAL_timer_enable_interrupt(TEMP_TIMER_NUM)
63
-#define DISABLE_TEMPERATURE_INTERRUPT() HAL_timer_disable_interrupt(TEMP_TIMER_NUM)
64
-
65
-// TODO change this
66
-
67
-#ifdef STM32GENERIC
68
-  #define TC_TIMER_ARGS
69
-#else
70
-  #define TC_TIMER_ARGS stimer_t *htim
71
-#endif
72
-
73
-extern void TC5_Handler(TC_TIMER_ARGS);
74
-extern void TC7_Handler(TC_TIMER_ARGS);
75
-#ifndef HAL_STEP_TIMER_ISR
76
-  #define HAL_STEP_TIMER_ISR() void TC5_Handler(TC_TIMER_ARGS)
77
-#endif
78
-#ifndef HAL_TEMP_TIMER_ISR
79
-  #define HAL_TEMP_TIMER_ISR() void TC7_Handler(TC_TIMER_ARGS)
80
-#endif
81
-
82
-// ------------------------
83
-// Types
84
-// ------------------------
85
-
86
-#ifdef STM32GENERIC
87
-  typedef struct {
88
-    TIM_HandleTypeDef handle;
89
-    uint32_t callback;
90
-  } tTimerConfig;
91
-  typedef tTimerConfig stm32_timer_t;
92
-#else
93
-  typedef stimer_t stm32_timer_t;
94
-#endif
95
-
96
-// ------------------------
97
-// Public Variables
98
-// ------------------------
99
-
100
-extern stm32_timer_t TimerHandle[];
101
-
102
-// ------------------------
103
-// Public functions
104
-// ------------------------
105
-
106
-void HAL_timer_start(const uint8_t timer_num, const uint32_t frequency);
107
-void HAL_timer_enable_interrupt(const uint8_t timer_num);
108
-void HAL_timer_disable_interrupt(const uint8_t timer_num);
109
-bool HAL_timer_interrupt_enabled(const uint8_t timer_num);
110
-
111
-FORCE_INLINE static uint32_t HAL_timer_get_count(const uint8_t timer_num) {
112
-  return __HAL_TIM_GET_COUNTER(&TimerHandle[timer_num].handle);
113
-}
114
-
115
-FORCE_INLINE static void HAL_timer_set_compare(const uint8_t timer_num, const uint32_t compare) {
116
-  __HAL_TIM_SET_AUTORELOAD(&TimerHandle[timer_num].handle, compare);
117
-  if (HAL_timer_get_count(timer_num) >= compare)
118
-    TimerHandle[timer_num].handle.Instance->EGR |= TIM_EGR_UG; // Generate an immediate update interrupt
119
-}
120
-
121
-FORCE_INLINE static hal_timer_t HAL_timer_get_compare(const uint8_t timer_num) {
122
-  return __HAL_TIM_GET_AUTORELOAD(&TimerHandle[timer_num].handle);
123
-}
124
-
125
-#ifdef STM32GENERIC
126
-  FORCE_INLINE static void HAL_timer_isr_prologue(const uint8_t timer_num) {
127
-    if (__HAL_TIM_GET_FLAG(&TimerHandle[timer_num].handle, TIM_FLAG_UPDATE) == SET)
128
-      __HAL_TIM_CLEAR_FLAG(&TimerHandle[timer_num].handle, TIM_FLAG_UPDATE);
129
-  }
130
-#else
131
-  #define HAL_timer_isr_prologue(TIMER_NUM)
132
-#endif
133
-
134
-#define HAL_timer_isr_epilogue(TIMER_NUM)

+ 0
- 27
Marlin/src/HAL/STM32_F4_F7/STM32F7/README.md Näytä tiedosto

@@ -1,27 +0,0 @@
1
-# This HAL is for the STM32F765 board "The Borg" used with STM32Generic Arduino core by danieleff.
2
-
3
-# Original core is located at:
4
-
5
-https://github.com/danieleff/STM32GENERIC
6
-
7
-but I haven't committed the changes needed for the Borg there yet, so please use:
8
-
9
-https://github.com/Spawn32/STM32GENERIC
10
-
11
-Unzip it into [Arduino]/hardware folder
12
-
13
-
14
-Download the latest GNU ARM Embedded Toolchain:
15
-
16
-https://developer.arm.com/open-source/gnu-toolchain/gnu-rm/downloads
17
-
18
-(The one in Arduino doesn't support STM32F7).
19
-
20
-Change compiler.path in platform.txt to point to the one you downloaded.
21
-
22
-# This HAL is in development.
23
-# Currently only tested on "The Borg".
24
-
25
-You will also need the latest Arduino 1.9.0-beta or newer.
26
-
27
-This HAL is a modified version of Chris Barr's Picoprint STM32F4 HAL, so shouldn't be to hard to get it to work on a F4.

+ 0
- 898
Marlin/src/HAL/STM32_F4_F7/STM32F7/TMC2660.cpp Näytä tiedosto

@@ -1,898 +0,0 @@
1
-/**
2
- * TMC26XStepper.cpp - - TMC26X Stepper library for Wiring/Arduino
3
- *
4
- * based on the stepper library by Tom Igoe, et. al.
5
- *
6
- * Copyright (c) 2011, Interactive Matter, Marcus Nowotny
7
- *
8
- * Permission is hereby granted, free of charge, to any person obtaining a copy
9
- * of this software and associated documentation files (the "Software"), to deal
10
- * in the Software without restriction, including without limitation the rights
11
- * to use, copy, modify, merge, publish, distribute, sublicense, and/or sell
12
- * copies of the Software, and to permit persons to whom the Software is
13
- * furnished to do so, subject to the following conditions:
14
- *
15
- * The above copyright notice and this permission notice shall be included in
16
- * all copies or substantial portions of the Software.
17
- *
18
- * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
19
- * IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
20
- * FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
21
- * AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
22
- * LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM,
23
- * OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN
24
- * THE SOFTWARE.
25
- */
26
-
27
-#if defined(STM32GENERIC) && defined(STM32F7)
28
-
29
-#include "../../../inc/MarlinConfigPre.h"
30
-
31
-#if HAS_DRIVER(TMC2660)
32
-
33
-#include <stdbool.h>
34
-#include <SPI.h>
35
-#include "TMC2660.h"
36
-
37
-#include "../../../inc/MarlinConfig.h"
38
-#include "../../../MarlinCore.h"
39
-#include "../../../module/stepper/indirection.h"
40
-#include "../../../module/printcounter.h"
41
-#include "../../../libs/duration_t.h"
42
-#include "../../../libs/hex_print.h"
43
-
44
-//some default values used in initialization
45
-#define DEFAULT_MICROSTEPPING_VALUE 32
46
-
47
-//TMC26X register definitions
48
-#define DRIVER_CONTROL_REGISTER 0x0UL
49
-#define CHOPPER_CONFIG_REGISTER 0x80000UL
50
-#define COOL_STEP_REGISTER  0xA0000ul
51
-#define STALL_GUARD2_LOAD_MEASURE_REGISTER 0xC0000ul
52
-#define DRIVER_CONFIG_REGISTER 0xE0000ul
53
-
54
-#define REGISTER_BIT_PATTERN 0xFFFFFul
55
-
56
-//definitions for the driver control register
57
-#define MICROSTEPPING_PATTERN 0xFul
58
-#define STEP_INTERPOLATION 0x200UL
59
-#define DOUBLE_EDGE_STEP 0x100UL
60
-#define VSENSE 0x40UL
61
-#define READ_MICROSTEP_POSTION 0x0UL
62
-#define READ_STALL_GUARD_READING 0x10UL
63
-#define READ_STALL_GUARD_AND_COOL_STEP 0x20UL
64
-#define READ_SELECTION_PATTERN 0x30UL
65
-
66
-//definitions for the chopper config register
67
-#define CHOPPER_MODE_STANDARD 0x0UL
68
-#define CHOPPER_MODE_T_OFF_FAST_DECAY 0x4000UL
69
-#define T_OFF_PATTERN 0xFul
70
-#define RANDOM_TOFF_TIME 0x2000UL
71
-#define BLANK_TIMING_PATTERN 0x18000UL
72
-#define BLANK_TIMING_SHIFT 15
73
-#define HYSTERESIS_DECREMENT_PATTERN 0x1800UL
74
-#define HYSTERESIS_DECREMENT_SHIFT 11
75
-#define HYSTERESIS_LOW_VALUE_PATTERN 0x780UL
76
-#define HYSTERESIS_LOW_SHIFT 7
77
-#define HYSTERESIS_START_VALUE_PATTERN 0x78UL
78
-#define HYSTERESIS_START_VALUE_SHIFT 4
79
-#define T_OFF_TIMING_PATERN 0xFul
80
-
81
-//definitions for cool step register
82
-#define MINIMUM_CURRENT_FOURTH 0x8000UL
83
-#define CURRENT_DOWN_STEP_SPEED_PATTERN 0x6000UL
84
-#define SE_MAX_PATTERN 0xF00ul
85
-#define SE_CURRENT_STEP_WIDTH_PATTERN 0x60UL
86
-#define SE_MIN_PATTERN 0xFul
87
-
88
-//definitions for StallGuard2 current register
89
-#define STALL_GUARD_FILTER_ENABLED 0x10000UL
90
-#define STALL_GUARD_TRESHHOLD_VALUE_PATTERN 0x17F00ul
91
-#define CURRENT_SCALING_PATTERN 0x1Ful
92
-#define STALL_GUARD_CONFIG_PATTERN 0x17F00ul
93
-#define STALL_GUARD_VALUE_PATTERN 0x7F00ul
94
-
95
-//definitions for the input from the TMC2660
96
-#define STATUS_STALL_GUARD_STATUS 0x1UL
97
-#define STATUS_OVER_TEMPERATURE_SHUTDOWN 0x2UL
98
-#define STATUS_OVER_TEMPERATURE_WARNING 0x4UL
99
-#define STATUS_SHORT_TO_GROUND_A 0x8UL
100
-#define STATUS_SHORT_TO_GROUND_B 0x10UL
101
-#define STATUS_OPEN_LOAD_A 0x20UL
102
-#define STATUS_OPEN_LOAD_B 0x40UL
103
-#define STATUS_STAND_STILL 0x80UL
104
-#define READOUT_VALUE_PATTERN 0xFFC00ul
105
-
106
-#define CPU_32_BIT
107
-
108
-//default values
109
-#define INITIAL_MICROSTEPPING 0x3UL //32th microstepping
110
-
111
-SPIClass SPI_6(SPI6, SPI6_MOSI_PIN, SPI6_MISO_PIN, SPI6_SCK_PIN);
112
-
113
-#define STEPPER_SPI SPI_6
114
-
115
-//debuging output
116
-
117
-//#define TMC_DEBUG1
118
-
119
-uint8_t current_scaling = 0;
120
-
121
-/**
122
- * Constructor
123
- * number_of_steps - the steps per rotation
124
- * cs_pin - the SPI client select pin
125
- * dir_pin - the pin where the direction pin is connected
126
- * step_pin - the pin where the step pin is connected
127
- */
128
-TMC26XStepper::TMC26XStepper(const int16_t in_steps, int16_t cs_pin, int16_t dir_pin, int16_t step_pin, uint16_t current, uint16_t resistor) {
129
-  // We are not started yet
130
-  started = false;
131
-
132
-  // By default cool step is not enabled
133
-  cool_step_enabled = false;
134
-
135
-  // Save the pins for later use
136
-  this->cs_pin = cs_pin;
137
-  this->dir_pin = dir_pin;
138
-  this->step_pin = step_pin;
139
-
140
-  // Store the current sense resistor value for later use
141
-  this->resistor = resistor;
142
-
143
-  // Initizalize our status values
144
-  this->steps_left = 0;
145
-  this->direction = 0;
146
-
147
-  // Initialize register values
148
-  driver_control_register_value = DRIVER_CONTROL_REGISTER | INITIAL_MICROSTEPPING;
149
-  chopper_config_register = CHOPPER_CONFIG_REGISTER;
150
-
151
-  // Setting the default register values
152
-  driver_control_register_value = DRIVER_CONTROL_REGISTER|INITIAL_MICROSTEPPING;
153
-  microsteps = _BV(INITIAL_MICROSTEPPING);
154
-  chopper_config_register = CHOPPER_CONFIG_REGISTER;
155
-  cool_step_register_value = COOL_STEP_REGISTER;
156
-  stallguard2_current_register_value = STALL_GUARD2_LOAD_MEASURE_REGISTER;
157
-  driver_configuration_register_value = DRIVER_CONFIG_REGISTER | READ_STALL_GUARD_READING;
158
-
159
-  // Set the current
160
-  setCurrent(current);
161
-  // Set to a conservative start value
162
-  setConstantOffTimeChopper(7, 54, 13,12,1);
163
-  // Set a nice microstepping value
164
-  setMicrosteps(DEFAULT_MICROSTEPPING_VALUE);
165
-  // Save the number of steps
166
-  number_of_steps = in_steps;
167
-}
168
-
169
-
170
-/**
171
- * start & configure the stepper driver
172
- * just must be called.
173
- */
174
-void TMC26XStepper::start() {
175
-
176
-  #ifdef TMC_DEBUG1
177
-    SERIAL_ECHOLNPGM("\n  TMC26X stepper library");
178
-    SERIAL_ECHOPAIR("\n  CS pin: ", cs_pin);
179
-    SERIAL_ECHOPAIR("\n  DIR pin: ", dir_pin);
180
-    SERIAL_ECHOPAIR("\n  STEP pin: ", step_pin);
181
-    SERIAL_PRINTF("\n  current scaling: %d", current_scaling);
182
-    SERIAL_PRINTF("\n  Resistor: %d", resistor);
183
-    //SERIAL_PRINTF("\n  current: %d", current);
184
-    SERIAL_ECHOPAIR("\n  Microstepping: ", microsteps);
185
-  #endif
186
-
187
-  //set the pins as output & its initial value
188
-  pinMode(step_pin, OUTPUT);
189
-  pinMode(dir_pin, OUTPUT);
190
-  pinMode(cs_pin, OUTPUT);
191
-  extDigitalWrite(step_pin, LOW);
192
-  extDigitalWrite(dir_pin, LOW);
193
-  extDigitalWrite(cs_pin, HIGH);
194
-
195
-  STEPPER_SPI.begin();
196
-  STEPPER_SPI.beginTransaction(SPISettings(4000000, MSBFIRST, SPI_MODE3));
197
-
198
-  //set the initial values
199
-  send262(driver_control_register_value);
200
-  send262(chopper_config_register);
201
-  send262(cool_step_register_value);
202
-  send262(stallguard2_current_register_value);
203
-  send262(driver_configuration_register_value);
204
-
205
-  //save that we are in running mode
206
-  started = true;
207
-}
208
-
209
-/**
210
- * Mark the driver as unstarted to be able to start it again
211
- */
212
-void TMC26XStepper::un_start() { started = false; }
213
-
214
-
215
-/**
216
- * Sets the speed in revs per minute
217
- */
218
-void TMC26XStepper::setSpeed(uint16_t whatSpeed) {
219
-  this->speed = whatSpeed;
220
-  this->step_delay = 60UL * sq(1000UL) / ((uint32_t)this->number_of_steps * (uint32_t)whatSpeed * (uint32_t)this->microsteps);
221
-  #ifdef TMC_DEBUG0 // crashes
222
-    SERIAL_ECHOPAIR("\nStep delay in micros: ", this->step_delay);
223
-  #endif
224
-  // Update the next step time
225
-  this->next_step_time = this->last_step_time + this->step_delay;
226
-}
227
-
228
-uint16_t TMC26XStepper::getSpeed() { return this->speed; }
229
-
230
-/**
231
- * Moves the motor steps_to_move steps.
232
- * Negative indicates the reverse direction.
233
- */
234
-char TMC26XStepper::step(int16_t steps_to_move) {
235
-  if (this->steps_left == 0) {
236
-    this->steps_left = ABS(steps_to_move);  // how many steps to take
237
-
238
-    // determine direction based on whether steps_to_move is + or -:
239
-    if (steps_to_move > 0)
240
-      this->direction = 1;
241
-    else if (steps_to_move < 0)
242
-      this->direction = 0;
243
-    return 0;
244
-  }
245
-  return -1;
246
-}
247
-
248
-char TMC26XStepper::move() {
249
-  // decrement the number of steps, moving one step each time:
250
-  if (this->steps_left > 0) {
251
-    uint32_t time = micros();
252
-    // move only if the appropriate delay has passed:
253
-
254
-    // rem if (time >= this->next_step_time) {
255
-
256
-    if (ABS(time - this->last_step_time) > this->step_delay) {
257
-      // increment or decrement the step number,
258
-      // depending on direction:
259
-      if (this->direction == 1)
260
-        extDigitalWrite(step_pin, HIGH);
261
-      else {
262
-        extDigitalWrite(dir_pin, HIGH);
263
-        extDigitalWrite(step_pin, HIGH);
264
-      }
265
-      // get the timeStamp of when you stepped:
266
-      this->last_step_time = time;
267
-      this->next_step_time = time + this->step_delay;
268
-      // decrement the steps left:
269
-      steps_left--;
270
-      //disable the step & dir pins
271
-      extDigitalWrite(step_pin, LOW);
272
-      extDigitalWrite(dir_pin, LOW);
273
-    }
274
-    return -1;
275
-  }
276
-  return 0;
277
-}
278
-
279
-char TMC26XStepper::isMoving() { return this->steps_left > 0; }
280
-
281
-uint16_t TMC26XStepper::getStepsLeft() { return this->steps_left; }
282
-
283
-char TMC26XStepper::stop() {
284
-  //note to self if the motor is currently moving
285
-  char state = isMoving();
286
-  //stop the motor
287
-  this->steps_left = 0;
288
-  this->direction = 0;
289
-  //return if it was moving
290
-  return state;
291
-}
292
-
293
-void TMC26XStepper::setCurrent(uint16_t current) {
294
-  uint8_t current_scaling = 0;
295
-  //calculate the current scaling from the max current setting (in mA)
296
-  float mASetting = (float)current,
297
-         resistor_value = (float)this->resistor;
298
-  // remove vsense flag
299
-  this->driver_configuration_register_value &= ~(VSENSE);
300
-  // Derived from I = (cs + 1) / 32 * (Vsense / Rsense)
301
-  //   leading to cs = 32 * R * I / V (with V = 0,31V oder 0,165V and I = 1000 * current)
302
-  // with Rsense = 0,15
303
-  // for vsense = 0,310V (VSENSE not set)
304
-  // or vsense = 0,165V (VSENSE set)
305
-  current_scaling = (byte)((resistor_value * mASetting * 32.0 / (0.31 * sq(1000.0))) - 0.5); //theoretically - 1.0 for better rounding it is 0.5
306
-
307
-  // Check if the current scalingis too low
308
-  if (current_scaling < 16) {
309
-    // Set the csense bit to get a use half the sense voltage (to support lower motor currents)
310
-    this->driver_configuration_register_value |= VSENSE;
311
-    // and recalculate the current setting
312
-    current_scaling = (byte)((resistor_value * mASetting * 32.0 / (0.165 * sq(1000.0))) - 0.5); //theoretically - 1.0 for better rounding it is 0.5
313
-    #ifdef TMC_DEBUG0 // crashes
314
-        SERIAL_ECHOPAIR("\nCS (Vsense=1): ",current_scaling);
315
-    #endif
316
-  }
317
-  #ifdef TMC_DEBUG0 // crashes
318
-    else
319
-      SERIAL_ECHOPAIR("\nCS: ", current_scaling);
320
-  #endif
321
-
322
-  // do some sanity checks
323
-  NOMORE(current_scaling, 31);
324
-
325
-  // delete the old value
326
-  stallguard2_current_register_value &= ~(CURRENT_SCALING_PATTERN);
327
-  // set the new current scaling
328
-  stallguard2_current_register_value |= current_scaling;
329
-  // if started we directly send it to the motor
330
-  if (started) {
331
-    send262(driver_configuration_register_value);
332
-    send262(stallguard2_current_register_value);
333
-  }
334
-}
335
-
336
-uint16_t TMC26XStepper::getCurrent() {
337
-  // Calculate the current according to the datasheet to be on the safe side.
338
-  // This is not the fastest but the most accurate and illustrative way.
339
-  float result = (float)(stallguard2_current_register_value & CURRENT_SCALING_PATTERN),
340
-         resistor_value = (float)this->resistor,
341
-         voltage = (driver_configuration_register_value & VSENSE) ? 0.165 : 0.31;
342
-  result = (result + 1.0) / 32.0 * voltage / resistor_value * sq(1000.0);
343
-  return (uint16_t)result;
344
-}
345
-
346
-void TMC26XStepper::setStallGuardThreshold(char stallguard_threshold, char stallguard_filter_enabled) {
347
-  // We just have 5 bits
348
-  LIMIT(stallguard_threshold, -64, 63);
349
-
350
-  // Add trim down to 7 bits
351
-  stallguard_threshold &= 0x7F;
352
-  // Delete old StallGuard settings
353
-  stallguard2_current_register_value &= ~(STALL_GUARD_CONFIG_PATTERN);
354
-  if (stallguard_filter_enabled)
355
-    stallguard2_current_register_value |= STALL_GUARD_FILTER_ENABLED;
356
-
357
-  // Set the new StallGuard threshold
358
-  stallguard2_current_register_value |= (((uint32_t)stallguard_threshold << 8) & STALL_GUARD_CONFIG_PATTERN);
359
-  // If started we directly send it to the motor
360
-  if (started) send262(stallguard2_current_register_value);
361
-}
362
-
363
-char TMC26XStepper::getStallGuardThreshold() {
364
-  uint32_t stallguard_threshold = stallguard2_current_register_value & STALL_GUARD_VALUE_PATTERN;
365
-  //shift it down to bit 0
366
-  stallguard_threshold >>= 8;
367
-  //convert the value to an int16_t to correctly handle the negative numbers
368
-  char result = stallguard_threshold;
369
-  //check if it is negative and fill it up with leading 1 for proper negative number representation
370
-  //rem if (result & _BV(6)) {
371
-
372
-  if (TEST(result, 6)) result |= 0xC0;
373
-  return result;
374
-}
375
-
376
-char TMC26XStepper::getStallGuardFilter() {
377
-  if (stallguard2_current_register_value & STALL_GUARD_FILTER_ENABLED)
378
-    return -1;
379
-  return 0;
380
-}
381
-
382
-/**
383
- * Set the number of microsteps per step.
384
- * 0,2,4,8,16,32,64,128,256 is supported
385
- * any value in between will be mapped to the next smaller value
386
- * 0 and 1 set the motor in full step mode
387
- */
388
-void TMC26XStepper::setMicrosteps(const int16_t in_steps) {
389
-  uint16_t setting_pattern;
390
-
391
-       if (in_steps >= 256) setting_pattern = 0;
392
-  else if (in_steps >= 128) setting_pattern = 1;
393
-  else if (in_steps >=  64) setting_pattern = 2;
394
-  else if (in_steps >=  32) setting_pattern = 3;
395
-  else if (in_steps >=  16) setting_pattern = 4;
396
-  else if (in_steps >=   8) setting_pattern = 5;
397
-  else if (in_steps >=   4) setting_pattern = 6;
398
-  else if (in_steps >=   2) setting_pattern = 7;
399
-  else if (in_steps <=   1) setting_pattern = 8; // 1 and 0 lead to full step
400
-
401
-  microsteps = _BV(8 - setting_pattern);
402
-
403
-  #ifdef TMC_DEBUG0 // crashes
404
-    SERIAL_ECHOPAIR("\n Microstepping: ", microsteps);
405
-  #endif
406
-
407
-  // Delete the old value
408
-  this->driver_control_register_value &= 0x000FFFF0UL;
409
-
410
-  // Set the new value
411
-  this->driver_control_register_value |= setting_pattern;
412
-
413
-  // If started we directly send it to the motor
414
-  if (started) send262(driver_control_register_value);
415
-
416
-  // Recalculate the stepping delay by simply setting the speed again
417
-  this->setSpeed(this->speed);
418
-}
419
-
420
-/**
421
- * returns the effective number of microsteps at the moment
422
- */
423
-int16_t TMC26XStepper::getMicrosteps() { return microsteps; }
424
-
425
-/**
426
- * constant_off_time: The off time setting controls the minimum chopper frequency.
427
- * For most applications an off time within the range of 5μs to 20μs will fit.
428
- *    2...15: off time setting
429
- *
430
- * blank_time: Selects the comparator blank time. This time needs to safely cover the switching event and the
431
- * duration of the ringing on the sense resistor. For
432
- *    0: min. setting 3: max. setting
433
- *
434
- * fast_decay_time_setting: Fast decay time setting. With CHM=1, these bits control the portion of fast decay for each chopper cycle.
435
- *    0: slow decay only
436
- *    1...15: duration of fast decay phase
437
- *
438
- * sine_wave_offset: Sine wave offset. With CHM=1, these bits control the sine wave offset.
439
- * A positive offset corrects for zero crossing error.
440
- *    -3..-1: negative offset 0: no offset 1...12: positive offset
441
- *
442
- * use_current_comparator: Selects usage of the current comparator for termination of the fast decay cycle.
443
- * If current comparator is enabled, it terminates the fast decay cycle in case the current
444
- * reaches a higher negative value than the actual positive value.
445
- *    1: enable comparator termination of fast decay cycle
446
- *    0: end by time only
447
- */
448
-void TMC26XStepper::setConstantOffTimeChopper(char constant_off_time, char blank_time, char fast_decay_time_setting, char sine_wave_offset, uint8_t use_current_comparator) {
449
-  // Perform some sanity checks
450
-  LIMIT(constant_off_time, 2, 15);
451
-
452
-  // Save the constant off time
453
-  this->constant_off_time = constant_off_time;
454
-
455
-  // Calculate the value acc to the clock cycles
456
-  const char blank_value = blank_time >= 54 ? 3 :
457
-                           blank_time >= 36 ? 2 :
458
-                           blank_time >= 24 ? 1 : 0;
459
-
460
-  LIMIT(fast_decay_time_setting, 0, 15);
461
-  LIMIT(sine_wave_offset, -3, 12);
462
-
463
-  // Shift the sine_wave_offset
464
-  sine_wave_offset += 3;
465
-
466
-  // Calculate the register setting
467
-  // First of all delete all the values for this
468
-  chopper_config_register &= ~(_BV(12) | BLANK_TIMING_PATTERN | HYSTERESIS_DECREMENT_PATTERN | HYSTERESIS_LOW_VALUE_PATTERN | HYSTERESIS_START_VALUE_PATTERN | T_OFF_TIMING_PATERN);
469
-  // Set the constant off pattern
470
-  chopper_config_register |= CHOPPER_MODE_T_OFF_FAST_DECAY;
471
-  // Set the blank timing value
472
-  chopper_config_register |= ((uint32_t)blank_value) << BLANK_TIMING_SHIFT;
473
-  // Setting the constant off time
474
-  chopper_config_register |= constant_off_time;
475
-  // Set the fast decay time
476
-  // Set msb
477
-  chopper_config_register |= (((uint32_t)(fast_decay_time_setting & 0x8)) << HYSTERESIS_DECREMENT_SHIFT);
478
-  // Other bits
479
-  chopper_config_register |= (((uint32_t)(fast_decay_time_setting & 0x7)) << HYSTERESIS_START_VALUE_SHIFT);
480
-  // Set the sine wave offset
481
-  chopper_config_register |= (uint32_t)sine_wave_offset << HYSTERESIS_LOW_SHIFT;
482
-  // Using the current comparator?
483
-  if (!use_current_comparator)
484
-    chopper_config_register |= _BV(12);
485
-
486
-  // If started we directly send it to the motor
487
-  if (started) {
488
-    // rem send262(driver_control_register_value);
489
-    send262(chopper_config_register);
490
-  }
491
-}
492
-
493
-/**
494
- * constant_off_time: The off time setting controls the minimum chopper frequency.
495
- * For most applications an off time within the range of 5μs to 20μs will fit.
496
- *    2...15: off time setting
497
- *
498
- * blank_time: Selects the comparator blank time. This time needs to safely cover the switching event and the
499
- * duration of the ringing on the sense resistor. For
500
- *    0: min. setting 3: max. setting
501
- *
502
- * hysteresis_start: Hysteresis start setting. Please remark, that this value is an offset to the hysteresis end value HEND.
503
- *    1...8
504
- *
505
- * hysteresis_end: Hysteresis end setting. Sets the hysteresis end value after a number of decrements. Decrement interval time is controlled by HDEC.
506
- * The sum HSTRT+HEND must be <16. At a current setting CS of max. 30 (amplitude reduced to 240), the sum is not limited.
507
- *    -3..-1: negative HEND 0: zero HEND 1...12: positive HEND
508
- *
509
- * hysteresis_decrement: Hysteresis decrement setting. This setting determines the slope of the hysteresis during on time and during fast decay time.
510
- *    0: fast decrement 3: very slow decrement
511
- */
512
-
513
-void TMC26XStepper::setSpreadCycleChopper(char constant_off_time, char blank_time, char hysteresis_start, char hysteresis_end, char hysteresis_decrement) {
514
-  // Perform some sanity checks
515
-  LIMIT(constant_off_time, 2, 15);
516
-
517
-  // Save the constant off time
518
-  this->constant_off_time = constant_off_time;
519
-
520
-  // Calculate the value acc to the clock cycles
521
-  const char blank_value = blank_time >= 54 ? 3 :
522
-                           blank_time >= 36 ? 2 :
523
-                           blank_time >= 24 ? 1 : 0;
524
-
525
-  LIMIT(hysteresis_start, 1, 8);
526
-  hysteresis_start--;
527
-
528
-  LIMIT(hysteresis_start, -3, 12);
529
-
530
-  // Shift the hysteresis_end
531
-  hysteresis_end += 3;
532
-
533
-  LIMIT(hysteresis_decrement, 0, 3);
534
-
535
-  //first of all delete all the values for this
536
-  chopper_config_register &= ~(CHOPPER_MODE_T_OFF_FAST_DECAY | BLANK_TIMING_PATTERN | HYSTERESIS_DECREMENT_PATTERN | HYSTERESIS_LOW_VALUE_PATTERN | HYSTERESIS_START_VALUE_PATTERN | T_OFF_TIMING_PATERN);
537
-
538
-  //set the blank timing value
539
-  chopper_config_register |= ((uint32_t)blank_value) << BLANK_TIMING_SHIFT;
540
-  //setting the constant off time
541
-  chopper_config_register |= constant_off_time;
542
-  //set the hysteresis_start
543
-  chopper_config_register |= ((uint32_t)hysteresis_start) << HYSTERESIS_START_VALUE_SHIFT;
544
-  //set the hysteresis end
545
-  chopper_config_register |= ((uint32_t)hysteresis_end) << HYSTERESIS_LOW_SHIFT;
546
-  //set the hystereis decrement
547
-  chopper_config_register |= ((uint32_t)blank_value) << BLANK_TIMING_SHIFT;
548
-  //if started we directly send it to the motor
549
-  if (started) {
550
-    //rem send262(driver_control_register_value);
551
-    send262(chopper_config_register);
552
-  }
553
-}
554
-
555
-/**
556
- * In a constant off time chopper scheme both coil choppers run freely, i.e. are not synchronized.
557
- * The frequency of each chopper mainly depends on the coil current and the position dependant motor coil inductivity, thus it depends on the microstep position.
558
- * With some motors a slightly audible beat can occur between the chopper frequencies, especially when they are near to each other. This typically occurs at a
559
- * few microstep positions within each quarter wave. This effect normally is not audible when compared to mechanical noise generated by ball bearings, etc.
560
- * Further factors which can cause a similar effect are a poor layout of sense resistor GND connection.
561
- * Hint: A common factor, which can cause motor noise, is a bad PCB layout causing coupling of both sense resistor voltages
562
- * (please refer to sense resistor layout hint in chapter 8.1).
563
- * In order to minimize the effect of a beat between both chopper frequencies, an internal random generator is provided.
564
- * It modulates the slow decay time setting when switched on by the RNDTF bit. The RNDTF feature further spreads the chopper spectrum,
565
- * reducing electromagnetic emission on single frequencies.
566
- */
567
-void TMC26XStepper::setRandomOffTime(char value) {
568
-  if (value)
569
-    chopper_config_register |= RANDOM_TOFF_TIME;
570
-  else
571
-    chopper_config_register &= ~(RANDOM_TOFF_TIME);
572
-  //if started we directly send it to the motor
573
-  if (started) {
574
-    //rem send262(driver_control_register_value);
575
-    send262(chopper_config_register);
576
-  }
577
-}
578
-
579
-void TMC26XStepper::setCoolStepConfiguration(
580
-  uint16_t lower_SG_threshold,
581
-  uint16_t SG_hysteresis,
582
-  uint8_t current_decrement_step_size,
583
-  uint8_t current_increment_step_size,
584
-  uint8_t lower_current_limit
585
-) {
586
-  // Sanitize the input values
587
-  NOMORE(lower_SG_threshold, 480);
588
-  // Divide by 32
589
-  lower_SG_threshold >>= 5;
590
-  NOMORE(SG_hysteresis, 480);
591
-  // Divide by 32
592
-  SG_hysteresis >>= 5;
593
-  NOMORE(current_decrement_step_size, 3);
594
-  NOMORE(current_increment_step_size, 3);
595
-  NOMORE(lower_current_limit, 1);
596
-
597
-  // Store the lower level in order to enable/disable the cool step
598
-  this->cool_step_lower_threshold=lower_SG_threshold;
599
-  // If cool step is not enabled we delete the lower value to keep it disabled
600
-  if (!this->cool_step_enabled) lower_SG_threshold = 0;
601
-  // The good news is that we can start with a complete new cool step register value
602
-  // And simply set the values in the register
603
-  cool_step_register_value = ((uint32_t)lower_SG_threshold)
604
-                          | (((uint32_t)SG_hysteresis) << 8)
605
-                          | (((uint32_t)current_decrement_step_size) << 5)
606
-                          | (((uint32_t)current_increment_step_size) << 13)
607
-                          | (((uint32_t)lower_current_limit) << 15)
608
-                          | COOL_STEP_REGISTER; // Register signature
609
-
610
-  if (started) send262(cool_step_register_value);
611
-}
612
-
613
-void TMC26XStepper::setCoolStepEnabled(boolean enabled) {
614
-  // Simply delete the lower limit to disable the cool step
615
-  cool_step_register_value &= ~SE_MIN_PATTERN;
616
-  // And set it to the proper value if cool step is to be enabled
617
-  if (enabled)
618
-    cool_step_register_value |= this->cool_step_lower_threshold;
619
-  // And save the enabled status
620
-  this->cool_step_enabled = enabled;
621
-  // Save the register value
622
-  if (started) send262(cool_step_register_value);
623
-}
624
-
625
-boolean TMC26XStepper::isCoolStepEnabled() { return this->cool_step_enabled; }
626
-
627
-uint16_t TMC26XStepper::getCoolStepLowerSgThreshold() {
628
-  // We return our internally stored value - in order to provide the correct setting even if cool step is not enabled
629
-  return this->cool_step_lower_threshold<<5;
630
-}
631
-
632
-uint16_t TMC26XStepper::getCoolStepUpperSgThreshold() {
633
-  return uint8_t((cool_step_register_value & SE_MAX_PATTERN) >> 8) << 5;
634
-}
635
-
636
-uint8_t TMC26XStepper::getCoolStepCurrentIncrementSize() {
637
-  return uint8_t((cool_step_register_value & CURRENT_DOWN_STEP_SPEED_PATTERN) >> 13);
638
-}
639
-
640
-uint8_t TMC26XStepper::getCoolStepNumberOfSGReadings() {
641
-  return uint8_t((cool_step_register_value & SE_CURRENT_STEP_WIDTH_PATTERN) >> 5);
642
-}
643
-
644
-uint8_t TMC26XStepper::getCoolStepLowerCurrentLimit() {
645
-  return uint8_t((cool_step_register_value & MINIMUM_CURRENT_FOURTH) >> 15);
646
-}
647
-
648
-void TMC26XStepper::setEnabled(boolean enabled) {
649
-  //delete the t_off in the chopper config to get sure
650
-  chopper_config_register &= ~(T_OFF_PATTERN);
651
-  if (enabled) {
652
-    //and set the t_off time
653
-    chopper_config_register |= this->constant_off_time;
654
-  }
655
-  //if not enabled we don't have to do anything since we already delete t_off from the register
656
-  if (started) send262(chopper_config_register);
657
-}
658
-
659
-boolean TMC26XStepper::isEnabled() { return !!(chopper_config_register & T_OFF_PATTERN); }
660
-
661
-/**
662
- * reads a value from the TMC26X status register. The value is not obtained directly but can then
663
- * be read by the various status routines.
664
- */
665
-void TMC26XStepper::readStatus(char read_value) {
666
-  uint32_t old_driver_configuration_register_value = driver_configuration_register_value;
667
-  //reset the readout configuration
668
-  driver_configuration_register_value &= ~(READ_SELECTION_PATTERN);
669
-  //this now equals TMC26X_READOUT_POSITION - so we just have to check the other two options
670
-  if (read_value == TMC26X_READOUT_STALLGUARD)
671
-    driver_configuration_register_value |= READ_STALL_GUARD_READING;
672
-  else if (read_value == TMC26X_READOUT_CURRENT)
673
-    driver_configuration_register_value |= READ_STALL_GUARD_AND_COOL_STEP;
674
-
675
-  //all other cases are ignored to prevent funny values
676
-  //check if the readout is configured for the value we are interested in
677
-  if (driver_configuration_register_value != old_driver_configuration_register_value) {
678
-    //because then we need to write the value twice - one time for configuring, second time to get the value, see below
679
-    send262(driver_configuration_register_value);
680
-  }
681
-  //write the configuration to get the last status
682
-  send262(driver_configuration_register_value);
683
-}
684
-
685
-int16_t TMC26XStepper::getMotorPosition() {
686
-  //we read it out even if we are not started yet - perhaps it is useful information for somebody
687
-  readStatus(TMC26X_READOUT_POSITION);
688
-  return getReadoutValue();
689
-}
690
-
691
-//reads the StallGuard setting from last status
692
-//returns -1 if StallGuard information is not present
693
-int16_t TMC26XStepper::getCurrentStallGuardReading() {
694
-  //if we don't yet started there cannot be a StallGuard value
695
-  if (!started) return -1;
696
-  //not time optimal, but solution optiomal:
697
-  //first read out the StallGuard value
698
-  readStatus(TMC26X_READOUT_STALLGUARD);
699
-  return getReadoutValue();
700
-}
701
-
702
-uint8_t TMC26XStepper::getCurrentCSReading() {
703
-  //if we don't yet started there cannot be a StallGuard value
704
-  if (!started) return 0;
705
-  //not time optimal, but solution optiomal:
706
-  //first read out the StallGuard value
707
-  readStatus(TMC26X_READOUT_CURRENT);
708
-  return (getReadoutValue() & 0x1F);
709
-}
710
-
711
-uint16_t TMC26XStepper::getCurrentCurrent() {
712
-    float result = (float)getCurrentCSReading(),
713
-           resistor_value = (float)this->resistor,
714
-           voltage = (driver_configuration_register_value & VSENSE)? 0.165 : 0.31;
715
-    result = (result + 1.0) / 32.0 * voltage / resistor_value * sq(1000.0);
716
-    return (uint16_t)result;
717
-}
718
-
719
-/**
720
- * Return true if the StallGuard threshold has been reached
721
- */
722
-boolean TMC26XStepper::isStallGuardOverThreshold() {
723
-  if (!this->started) return false;
724
-  return (driver_status_result & STATUS_STALL_GUARD_STATUS);
725
-}
726
-
727
-/**
728
- * returns if there is any over temperature condition:
729
- * OVER_TEMPERATURE_PREWARING if pre warning level has been reached
730
- * OVER_TEMPERATURE_SHUTDOWN if the temperature is so hot that the driver is shut down
731
- * Any of those levels are not too good.
732
- */
733
-char TMC26XStepper::getOverTemperature() {
734
-  if (!this->started) return 0;
735
-
736
-  if (driver_status_result & STATUS_OVER_TEMPERATURE_SHUTDOWN)
737
-    return TMC26X_OVERTEMPERATURE_SHUTDOWN;
738
-
739
-  if (driver_status_result & STATUS_OVER_TEMPERATURE_WARNING)
740
-    return TMC26X_OVERTEMPERATURE_PREWARING;
741
-
742
-  return 0;
743
-}
744
-
745
-// Is motor channel A shorted to ground
746
-boolean TMC26XStepper::isShortToGroundA() {
747
-  if (!this->started) return false;
748
-  return (driver_status_result & STATUS_SHORT_TO_GROUND_A);
749
-}
750
-
751
-// Is motor channel B shorted to ground
752
-boolean TMC26XStepper::isShortToGroundB() {
753
-  if (!this->started) return false;
754
-  return (driver_status_result & STATUS_SHORT_TO_GROUND_B);
755
-}
756
-
757
-// Is motor channel A connected
758
-boolean TMC26XStepper::isOpenLoadA() {
759
-  if (!this->started) return false;
760
-  return (driver_status_result & STATUS_OPEN_LOAD_A);
761
-}
762
-
763
-// Is motor channel B connected
764
-boolean TMC26XStepper::isOpenLoadB() {
765
-  if (!this->started) return false;
766
-  return (driver_status_result & STATUS_OPEN_LOAD_B);
767
-}
768
-
769
-// Is chopper inactive since 2^20 clock cycles - defaults to ~0,08s
770
-boolean TMC26XStepper::isStandStill() {
771
-  if (!this->started) return false;
772
-  return (driver_status_result & STATUS_STAND_STILL);
773
-}
774
-
775
-//is chopper inactive since 2^20 clock cycles - defaults to ~0,08s
776
-boolean TMC26XStepper::isStallGuardReached() {
777
-  if (!this->started) return false;
778
-  return (driver_status_result & STATUS_STALL_GUARD_STATUS);
779
-}
780
-
781
-//reads the StallGuard setting from last status
782
-//returns -1 if StallGuard information is not present
783
-int16_t TMC26XStepper::getReadoutValue() {
784
-  return (int)(driver_status_result >> 10);
785
-}
786
-
787
-int16_t TMC26XStepper::getResistor() { return this->resistor; }
788
-
789
-boolean TMC26XStepper::isCurrentScalingHalfed() {
790
-  return !!(this->driver_configuration_register_value & VSENSE);
791
-}
792
-/**
793
- * version() returns the version of the library:
794
- */
795
-int16_t TMC26XStepper::version() { return 1; }
796
-
797
-void TMC26XStepper::debugLastStatus() {
798
-  #ifdef TMC_DEBUG1
799
-    if (this->started) {
800
-      if (this->getOverTemperature()&TMC26X_OVERTEMPERATURE_PREWARING)
801
-        SERIAL_ECHOLNPGM("\n  WARNING: Overtemperature Prewarning!");
802
-      else if (this->getOverTemperature()&TMC26X_OVERTEMPERATURE_SHUTDOWN)
803
-        SERIAL_ECHOLNPGM("\n  ERROR: Overtemperature Shutdown!");
804
-
805
-      if (this->isShortToGroundA())
806
-        SERIAL_ECHOLNPGM("\n  ERROR: SHORT to ground on channel A!");
807
-
808
-      if (this->isShortToGroundB())
809
-        SERIAL_ECHOLNPGM("\n  ERROR: SHORT to ground on channel B!");
810
-
811
-      if (this->isOpenLoadA())
812
-        SERIAL_ECHOLNPGM("\n  ERROR: Channel A seems to be unconnected!");
813
-
814
-      if (this->isOpenLoadB())
815
-        SERIAL_ECHOLNPGM("\n  ERROR: Channel B seems to be unconnected!");
816
-
817
-      if (this->isStallGuardReached())
818
-        SERIAL_ECHOLNPGM("\n  INFO: Stall Guard level reached!");
819
-
820
-      if (this->isStandStill())
821
-        SERIAL_ECHOLNPGM("\n  INFO: Motor is standing still.");
822
-
823
-      uint32_t readout_config = driver_configuration_register_value & READ_SELECTION_PATTERN;
824
-      const int16_t value = getReadoutValue();
825
-      if (readout_config == READ_MICROSTEP_POSTION) {
826
-        SERIAL_ECHOPAIR("\n  Microstep position phase A: ", value);
827
-      }
828
-      else if (readout_config == READ_STALL_GUARD_READING) {
829
-        SERIAL_ECHOPAIR("\n  Stall Guard value:", value);
830
-      }
831
-      else if (readout_config == READ_STALL_GUARD_AND_COOL_STEP) {
832
-        SERIAL_ECHOPAIR("\n  Approx Stall Guard: ", value & 0xF);
833
-        SERIAL_ECHOPAIR("\n  Current level", value & 0x1F0);
834
-      }
835
-    }
836
-  #endif
837
-}
838
-
839
-/**
840
- * send register settings to the stepper driver via SPI
841
- * returns the current status
842
- */
843
-inline void TMC26XStepper::send262(uint32_t datagram) {
844
-  uint32_t i_datagram;
845
-
846
-  //preserver the previous spi mode
847
-  //uint8_t oldMode =  SPCR & SPI_MODE_MASK;
848
-
849
-  //if the mode is not correct set it to mode 3
850
-  //if (oldMode != SPI_MODE3) {
851
-  //  SPI.setDataMode(SPI_MODE3);
852
-  //}
853
-
854
-  //select the TMC driver
855
-  extDigitalWrite(cs_pin, LOW);
856
-
857
-  //ensure that only valid bist are set (0-19)
858
-  //datagram &=REGISTER_BIT_PATTERN;
859
-
860
-  #ifdef TMC_DEBUG1
861
-    //SERIAL_PRINTF("Sending ");
862
-    //SERIAL_PRINTF("Sending ", datagram,HEX);
863
-    //SERIAL_ECHOPAIR("\n\nSending \n", print_hex_long(datagram));
864
-    SERIAL_PRINTF("\n\nSending %x", datagram);
865
-  #endif
866
-
867
-  //write/read the values
868
-  i_datagram = STEPPER_SPI.transfer((datagram >> 16) & 0xFF);
869
-  i_datagram <<= 8;
870
-  i_datagram |= STEPPER_SPI.transfer((datagram >>  8) & 0xFF);
871
-  i_datagram <<= 8;
872
-  i_datagram |= STEPPER_SPI.transfer((datagram) & 0xFF);
873
-  i_datagram >>= 4;
874
-
875
-  #ifdef TMC_DEBUG1
876
-    //SERIAL_PRINTF("Received ");
877
-    //SERIAL_PRINTF("Received ", i_datagram,HEX);
878
-    //SERIAL_ECHOPAIR("\n\nReceived \n", i_datagram);
879
-    SERIAL_PRINTF("\n\nReceived %x", i_datagram);
880
-    debugLastStatus();
881
-  #endif
882
-
883
-  //deselect the TMC chip
884
-  extDigitalWrite(cs_pin, HIGH);
885
-
886
-  //restore the previous SPI mode if neccessary
887
-  //if the mode is not correct set it to mode 3
888
-  //if (oldMode != SPI_MODE3) {
889
-  //  SPI.setDataMode(oldMode);
890
-  //}
891
-
892
-  //store the datagram as status result
893
-  driver_status_result = i_datagram;
894
-}
895
-
896
-#endif // HAS_DRIVER(TMC2660)
897
-
898
-#endif // STM32GENERIC && STM32F7

+ 0
- 593
Marlin/src/HAL/STM32_F4_F7/STM32F7/TMC2660.h Näytä tiedosto

@@ -1,593 +0,0 @@
1
-/**
2
- * TMC26XStepper.h - - TMC26X Stepper library for Wiring/Arduino
3
- *
4
- * based on the stepper library by Tom Igoe, et. al.
5
- *
6
- * Copyright (c) 2011, Interactive Matter, Marcus Nowotny
7
- *
8
- * Permission is hereby granted, free of charge, to any person obtaining a copy
9
- * of this software and associated documentation files (the "Software"), to deal
10
- * in the Software without restriction, including without limitation the rights
11
- * to use, copy, modify, merge, publish, distribute, sublicense, and/or sell
12
- * copies of the Software, and to permit persons to whom the Software is
13
- * furnished to do so, subject to the following conditions:
14
- *
15
- * The above copyright notice and this permission notice shall be included in
16
- * all copies or substantial portions of the Software.
17
- *
18
- * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
19
- * IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
20
- * FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
21
- * AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
22
- * LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM,
23
- * OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN
24
- * THE SOFTWARE.
25
- */
26
-#pragma once
27
-
28
-#include <stdint.h>
29
-
30
-//! return value for TMC26XStepper.getOverTemperature() if there is a overtemperature situation in the TMC chip
31
-/*!
32
- * This warning indicates that the TMC chip is too warm.
33
- * It is still working but some parameters may be inferior.
34
- * You should do something against it.
35
- */
36
-#define TMC26X_OVERTEMPERATURE_PREWARING 1
37
-//! return value for TMC26XStepper.getOverTemperature() if there is a overtemperature shutdown in the TMC chip
38
-/*!
39
- * This warning indicates that the TMC chip is too warm to operate and has shut down to prevent damage.
40
- * It will stop working until it cools down again.
41
- * If you encouter this situation you must do something against it. Like reducing the current or improving the PCB layout
42
- * and/or heat management.
43
- */
44
-#define TMC26X_OVERTEMPERATURE_SHUTDOWN 2
45
-
46
-//which values can be read out
47
-/*!
48
- * Selects to readout the microstep position from the motor.
49
- *\sa readStatus()
50
- */
51
-#define TMC26X_READOUT_POSITION 0
52
-/*!
53
- * Selects to read out the StallGuard value of the motor.
54
- *\sa readStatus()
55
- */
56
-#define TMC26X_READOUT_STALLGUARD 1
57
-/*!
58
- * Selects to read out the current current setting (acc. to CoolStep) and the upper bits of the StallGuard value from the motor.
59
- *\sa readStatus(), setCurrent()
60
- */
61
-#define TMC26X_READOUT_CURRENT 3
62
-
63
-/*!
64
- * Define to set the minimum current for CoolStep operation to 1/2 of the selected CS minium.
65
- *\sa setCoolStepConfiguration()
66
- */
67
-#define COOL_STEP_HALF_CS_LIMIT 0
68
-/*!
69
- * Define to set the minimum current for CoolStep operation to 1/4 of the selected CS minium.
70
- *\sa setCoolStepConfiguration()
71
- */
72
-#define COOL_STEP_QUARTDER_CS_LIMIT 1
73
-
74
-/*!
75
- * \class TMC26XStepper
76
- * \brief Class representing a TMC26X stepper driver
77
- *
78
- * To use one of these drivers in your code create an object of its class:
79
- * \code
80
- * TMC26XStepper tmc_stepper = TMC26XStepper(200,1,2,3,500);
81
- * \endcode
82
- * see TMC26XStepper(int16_t number_of_steps, int16_t cs_pin, int16_t dir_pin, int16_t step_pin, uint16_t rms_current)
83
- *
84
- * Keep in mind that you need to start the driver with start() in order to configure the TMC26X.
85
- *
86
- * The most important function is move(). It checks if the motor requires a step. It's important to call move() as
87
- * often as possible in loop(). I suggest using a very fast loop routine and always call move() at the beginning or end.
88
- *
89
- * To move you must set a movement speed with setSpeed(). The speed is a positive value, setting the RPM.
90
- *
91
- * To really move the motor you have to call step() to tell the driver to move the motor the given number
92
- * of steps in the given direction. Positive values move the motor in one direction, negative values in the other.
93
- *
94
- * You can check with isMoving() if the motor is still moving or stop it abruptly with stop().
95
- */
96
-class TMC26XStepper {
97
-  public:
98
-    /*!
99
-     * \brief Create a new representation of a stepper motor connected to a TMC26X stepper driver
100
-     *
101
-     * Main constructor. If in doubt use this. All parameters must be provided as described below.
102
-     *
103
-     * \param number_of_steps Number of steps the motor has per rotation.
104
-     * \param cs_pin          Arduino pin connected to the Client Select Pin (!CS) of the TMC26X for SPI.
105
-     * \param dir_pin         Arduino pin connected to the DIR input of the TMC26X.
106
-     * \param step_pin        Arduino pin connected to the STEP pin of the TMC26X.
107
-     * \param rms_current     Maximum current to provide to the motor in mA (!). A value of 200 will send up to 200mA to the motor.
108
-     * \param resistor        Current sense resistor in milli-Ohm, defaults to 0.15 Ohm (or 150 milli-Ohm) as in the TMC260 Arduino Shield.
109
-     *
110
-     * You must also call TMC26XStepper.start() to configure the stepper driver for use.
111
-     *
112
-     * By default the Constant Off Time chopper is used. See TMC26XStepper.setConstantOffTimeChopper() for details.
113
-     * This should work on most motors (YMMV). You may want to configure and use the Spread Cycle Chopper. See setSpreadCycleChopper().
114
-     *
115
-     * By default a microstepping of 1/32 is used to provide a smooth motor run while still giving a good progression per step.
116
-     * Change stepping by sending setMicrosteps() a different value.
117
-     * \sa start(), setMicrosteps()
118
-     */
119
-    TMC26XStepper(const int16_t in_steps, int16_t cs_pin, int16_t dir_pin, int16_t step_pin, uint16_t current, uint16_t resistor=100); //resistor=150
120
-
121
-    /*!
122
-     * \brief Configure and start the TMC26X stepper driver. Before this is called the stepper driver is nonfunctional.
123
-     *
124
-     * Configure the TMC26X stepper driver for the given values via SPI.
125
-     * Most member functions are non-functional if the driver has not been started,
126
-     * therefore it is best to call this in setup().
127
-     */
128
-    void start();
129
-
130
-    /*!
131
-     * \brief Reset the stepper in unconfigured mode.
132
-     *
133
-     * Allows start to be called again. It doesn't change the internal stepper
134
-     * configuration or the desired configuration. It just marks the stepper as
135
-     * not-yet-started. The stepper doesn't need to be reconfigured before
136
-     * starting again, and is not reset to any factory settings.
137
-     * It must be reset intentionally.
138
-     * (Hint: Normally you do not need this function)
139
-     */
140
-    void un_start();
141
-
142
-    /*!
143
-     * \brief Set the rotation speed in RPM.
144
-     * \param whatSpeed the desired speed in RPM.
145
-     */
146
-    void setSpeed(uint16_t whatSpeed);
147
-
148
-    /*!
149
-     * \brief Report the currently selected speed in RPM.
150
-     * \sa setSpeed()
151
-     */
152
-    uint16_t getSpeed();
153
-
154
-    /*!
155
-     * \brief Set the number of microsteps in 2^i values (rounded) up to 256
156
-     *
157
-     * This method sets the number of microsteps per step in 2^i interval.
158
-     * It accepts 1, 2, 4, 16, 32, 64, 128 or 256 as valid microsteps.
159
-     * Other values will be rounded down to the next smaller value (e.g., 3 gives a microstepping of 2).
160
-     * You can always check the current microstepping with getMicrosteps().
161
-     */
162
-    void setMicrosteps(const int16_t in_steps);
163
-
164
-    /*!
165
-     * \brief Return the effective current number of microsteps selected.
166
-     *
167
-     * Always returns the effective number of microsteps.
168
-     * This may be different from the micro-steps set in setMicrosteps() since it is rounded to 2^i.
169
-     *
170
-     * \sa setMicrosteps()
171
-     */
172
-    int16_t getMicrosteps();
173
-
174
-    /*!
175
-     * \brief Initiate a movement with the given number of steps. Positive values move in one direction, negative in the other.
176
-     *
177
-     * \param number_of_steps The number of steps to move the motor.
178
-     * \return 0 if the motor was not moving and moves now. -1 if the motor is moving and the new steps could not be set.
179
-     *
180
-     * If the previous movement is incomplete the function returns -1 and doesn't change the steps to move the motor.
181
-     * If the motor does not move it returns 0.
182
-     *
183
-     * The movement direction is determined by the sign of the steps parameter. The motor direction in machine space
184
-     * cannot be determined, as it depends on the construction of the motor and how it functions in the drive system.
185
-     *
186
-     * For safety, verify with isMoving() or even use stop() to stop the motor before giving it new step directions.
187
-     * \sa isMoving(), getStepsLeft(), stop()
188
-     */
189
-    char step(int16_t number_of_steps);
190
-
191
-    /*!
192
-     * \brief Central movement method. Must be called as often as possible in the loop function and is very fast.
193
-     *
194
-     * Check if the motor still has to move and whether the wait-to-step interval has expired, and manages the
195
-     * number of steps remaining to fulfill the current move command.
196
-     *
197
-     * This function is implemented to be as fast as possible, so call it as often as possible in your loop.
198
-     * It should be invoked with as frequently and with as much regularity as possible.
199
-     *
200
-     * This can be called even when the motor is known not to be moving. It will simply return.
201
-     *
202
-     * The frequency with which this function is called determines the top stepping speed of the motor.
203
-     * It is recommended to call this using a hardware timer to ensure regular invocation.
204
-     * \sa step()
205
-     */
206
-    char move();
207
-
208
-    /*!
209
-     * \brief Check whether the last movement command is done.
210
-     * \return 0 if the motor stops, -1 if the motor is moving.
211
-     *
212
-     * Used to determine if the motor is ready for new movements.
213
-     *\sa step(), move()
214
-     */
215
-    char isMoving();
216
-
217
-    /*!
218
-     * \brief Get the number of steps left in the current movement.
219
-     * \return The number of steps left in the movement. Always positive.
220
-     */
221
-    uint16_t getStepsLeft();
222
-
223
-    /*!
224
-     * \brief Stop the motor immediately.
225
-     * \return -1 if the motor was moving and is really stoped or 0 if it was not moving at all.
226
-     *
227
-     * This method directly and abruptly stops the motor and may be used as an emergency stop.
228
-     */
229
-    char stop();
230
-
231
-    /*!
232
-     * \brief Set and configure the classical Constant Off Timer Chopper
233
-     * \param constant_off_time       The off time setting controls the minimum chopper frequency. For most applications an off time within the range of 5μs to 20μs will fit. Setting this parameter to zero completely disables all driver transistors and the motor can free-wheel. 0: chopper off, 1:15: off time setting (1 will work with minimum blank time of 24 clocks)
234
-     * \param blank_time              Comparator blank time. This duration needs to safely cover the duration of the switching event and the ringing on the sense resistor. For most low current drivers, a setting of 1 or 2 is good. For high current applications with large MOSFETs, a setting of 2 or 3 will be required. 0 (min setting) … (3) amx setting
235
-     * \param fast_decay_time_setting Fast decay time setting. Controls the portion of fast decay for each chopper cycle. 0: slow decay only, 1…15: duration of fast decay phase
236
-     * \param sine_wave_offset        Sine wave offset. Controls the sine wave offset. A positive offset corrects for zero crossing error. -3…-1: negative offset, 0: no offset,1…12: positive offset
237
-     * \param use_curreent_comparator Selects usage of the current comparator for termination of the fast decay cycle. If current comparator is enabled, it terminates the fast decay cycle in case the current reaches a higher negative value than the actual positive value. (0 disable, -1 enable).
238
-     *
239
-     * The classic constant off time chopper uses a fixed portion of fast decay following each on phase.
240
-     * While the duration of the on time is determined by the chopper comparator, the fast decay time needs
241
-     * to be set by the user in a way, that the current decay is enough for the driver to be able to follow
242
-     * the falling slope of the sine wave, and on the other hand it should not be too long, in order to minimize
243
-     * motor current ripple and power dissipation. This best can be tuned using an oscilloscope or
244
-     * trying out motor smoothness at different velocities. A good starting value is a fast decay time setting
245
-     * similar to the slow decay time setting.
246
-     * After tuning of the fast decay time, the offset should be determined, in order to have a smooth zero transition.
247
-     * This is necessary, because the fast decay phase leads to the absolute value of the motor current being lower
248
-     * than the target current (see figure 17). If the zero offset is too low, the motor stands still for a short
249
-     * moment during current zero crossing, if it is set too high, it makes a larger microstep.
250
-     * Typically, a positive offset setting is required for optimum operation.
251
-     *
252
-     * \sa setSpreadCycleChoper() for other alternatives.
253
-     * \sa setRandomOffTime() for spreading the noise over a wider spectrum
254
-     */
255
-    void setConstantOffTimeChopper(char constant_off_time, char blank_time, char fast_decay_time_setting, char sine_wave_offset, uint8_t use_current_comparator);
256
-
257
-    /*!
258
-     * \brief Sets and configures with spread cycle chopper.
259
-     * \param constant_off_time The off time setting controls the minimum chopper frequency. For most applications an off time within the range of 5μs to 20μs will fit. Setting this parameter to zero completely disables all driver transistors and the motor can free-wheel. 0: chopper off, 1:15: off time setting (1 will work with minimum blank time of 24 clocks)
260
-     * \param blank_time Selects the comparator blank time. This time needs to safely cover the switching event and the duration of the ringing on the sense resistor. For most low current drivers, a setting of 1 or 2 is good. For high current applications with large MOSFETs, a setting of 2 or 3 will be required. 0 (min setting) … (3) amx setting
261
-     * \param hysteresis_start Hysteresis start setting. Please remark, that this value is an offset to the hysteresis end value. 1 … 8
262
-     * \param hysteresis_end Hysteresis end setting. Sets the hysteresis end value after a number of decrements. Decrement interval time is controlled by hysteresis_decrement. The sum hysteresis_start + hysteresis_end must be <16. At a current setting CS of max. 30 (amplitude reduced to 240), the sum is not limited.
263
-     * \param hysteresis_decrement Hysteresis decrement setting. This setting determines the slope of the hysteresis during on time and during fast decay time. 0 (fast decrement) … 3 (slow decrement).
264
-     *
265
-     * The spreadCycle chopper scheme (pat.fil.) is a precise and simple to use chopper principle, which automatically determines
266
-     * the optimum fast decay portion for the motor. Anyhow, a number of settings can be made in order to optimally fit the driver
267
-     * to the motor.
268
-     * Each chopper cycle is comprised of an on-phase, a slow decay phase, a fast decay phase and a second slow decay phase.
269
-     * The slow decay phases limit the maximum chopper frequency and are important for low motor and driver power dissipation.
270
-     * The hysteresis start setting limits the chopper frequency by forcing the driver to introduce a minimum amount of
271
-     * current ripple into the motor coils. The motor inductivity determines the ability to follow a changing motor current.
272
-     * The duration of the on- and fast decay phase needs to cover at least the blank time, because the current comparator is
273
-     * disabled during this time.
274
-     *
275
-     * \sa setRandomOffTime() for spreading the noise over a wider spectrum
276
-     */
277
-    void setSpreadCycleChopper(char constant_off_time, char blank_time, char hysteresis_start, char hysteresis_end, char hysteresis_decrement);
278
-
279
-    /*!
280
-     * \brief Use random off time for noise reduction (0 for off, -1 for on).
281
-     * \param value 0 for off, -1 for on
282
-     *
283
-     * In a constant off time chopper scheme both coil choppers run freely, i.e. are not synchronized.
284
-     * The frequency of each chopper mainly depends on the coil current and the position dependant motor coil inductivity,
285
-     * thus it depends on the microstep position. With some motors a slightly audible beat can occur between the chopper
286
-     * frequencies, especially when they are near to each other. This typically occurs at a few microstep positions within
287
-     * each quarter wave.
288
-     * This effect normally is not audible when compared to mechanical noise generated by ball bearings,
289
-     * etc. Further factors which can cause a similar effect are a poor layout of sense resistor GND connection.
290
-     * In order to minimize the effect of a beat between both chopper frequencies, an internal random generator is provided.
291
-     * It modulates the slow decay time setting when switched on. The random off time feature further spreads the chopper spectrum,
292
-     * reducing electromagnetic emission on single frequencies.
293
-     */
294
-    void setRandomOffTime(char value);
295
-
296
-    /*!
297
-     * \brief set the maximum motor current in mA (1000 is 1 Amp)
298
-     * Keep in mind this is the maximum peak Current. The RMS current will be 1/sqrt(2) smaller. The actual current can also be smaller
299
-     * by employing CoolStep.
300
-     * \param current the maximum motor current in mA
301
-     * \sa getCurrent(), getCurrentCurrent()
302
-     */
303
-    void setCurrent(uint16_t current);
304
-
305
-    /*!
306
-     * \brief readout the motor maximum current in mA (1000 is an Amp)
307
-     * This is the maximum current. to get the current current - which may be affected by CoolStep us getCurrentCurrent()
308
-     * \return the maximum motor current in milli amps
309
-     * \sa getCurrentCurrent()
310
-     */
311
-    uint16_t getCurrent();
312
-
313
-    /*!
314
-     * \brief set the StallGuard threshold in order to get sensible StallGuard readings.
315
-     * \param stallguard_threshold -64 … 63 the StallGuard threshold
316
-     * \param stallguard_filter_enabled 0 if the filter is disabled, -1 if it is enabled
317
-     *
318
-     * The StallGuard threshold is used to optimize the StallGuard reading to sensible values. It should be at 0 at
319
-     * the maximum allowable load on the otor (but not before). = is a good starting point (and the default)
320
-     * If you get Stall Gaurd readings of 0 without any load or with too little laod increase the value.
321
-     * If you get readings of 1023 even with load decrease the setting.
322
-     *
323
-     * If you switch on the filter the StallGuard reading is only updated each 4th full step to reduce the noise in the
324
-     * reading.
325
-     *
326
-     * \sa getCurrentStallGuardReading() to read out the current value.
327
-     */
328
-    void setStallGuardThreshold(char stallguard_threshold, char stallguard_filter_enabled);
329
-
330
-    /*!
331
-     * \brief reads out the StallGuard threshold
332
-     * \return a number between -64 and 63.
333
-     */
334
-    char getStallGuardThreshold();
335
-
336
-    /*!
337
-     * \brief returns the current setting of the StallGuard filter
338
-     * \return 0 if not set, -1 if set
339
-     */
340
-    char getStallGuardFilter();
341
-
342
-    /*!
343
-     * \brief This method configures the CoolStep smart energy operation. You must have a proper StallGuard configuration for the motor situation (current, voltage, speed) in rder to use this feature.
344
-     * \param lower_SG_threshold Sets the lower threshold for stallGuard2TM reading. Below this value, the motor current becomes increased. Allowed values are 0...480
345
-     * \param SG_hysteresis Sets the distance between the lower and the upper threshold for stallGuard2TM reading. Above the upper threshold (which is lower_SG_threshold+SG_hysteresis+1) the motor current becomes decreased. Allowed values are 0...480
346
-     * \param current_decrement_step_size Sets the current decrement steps. If the StallGuard value is above the threshold the current gets decremented by this step size. 0...32
347
-     * \param current_increment_step_size Sets the current increment step. The current becomes incremented for each measured stallGuard2TM value below the lower threshold. 0...8
348
-     * \param lower_current_limit Sets the lower motor current limit for coolStepTM operation by scaling the CS value. Values can be COOL_STEP_HALF_CS_LIMIT, COOL_STEP_QUARTER_CS_LIMIT
349
-     * The CoolStep smart energy operation automatically adjust the current sent into the motor according to the current load,
350
-     * read out by the StallGuard in order to provide the optimum torque with the minimal current consumption.
351
-     * You configure the CoolStep current regulator by defining upper and lower bounds of StallGuard readouts. If the readout is above the
352
-     * limit the current gets increased, below the limit the current gets decreased.
353
-     * You can specify the upper an lower threshold of the StallGuard readout in order to adjust the current. You can also set the number of
354
-     * StallGuard readings neccessary above or below the limit to get a more stable current adjustement.
355
-     * The current adjustement itself is configured by the number of steps the current gests in- or decreased and the absolut minimum current
356
-     * (1/2 or 1/4th otf the configured current).
357
-     * \sa COOL_STEP_HALF_CS_LIMIT, COOL_STEP_QUARTER_CS_LIMIT
358
-     */
359
-    void setCoolStepConfiguration(uint16_t lower_SG_threshold, uint16_t SG_hysteresis, uint8_t current_decrement_step_size,
360
-                                  uint8_t current_increment_step_size, uint8_t lower_current_limit);
361
-
362
-    /*!
363
-     * \brief enables or disables the CoolStep smart energy operation feature. It must be configured before enabling it.
364
-     * \param enabled true if CoolStep should be enabled, false if not.
365
-     * \sa setCoolStepConfiguration()
366
-     */
367
-    void setCoolStepEnabled(boolean enabled);
368
-
369
-
370
-    /*!
371
-     * \brief check if the CoolStep feature is enabled
372
-     * \sa setCoolStepEnabled()
373
-     */
374
-    boolean isCoolStepEnabled();
375
-
376
-    /*!
377
-     * \brief returns the lower StallGuard threshold for the CoolStep operation
378
-     * \sa setCoolStepConfiguration()
379
-     */
380
-    uint16_t getCoolStepLowerSgThreshold();
381
-
382
-    /*!
383
-     * \brief returns the upper StallGuard threshold for the CoolStep operation
384
-     * \sa setCoolStepConfiguration()
385
-     */
386
-    uint16_t getCoolStepUpperSgThreshold();
387
-
388
-    /*!
389
-     * \brief returns the number of StallGuard readings befor CoolStep adjusts the motor current.
390
-     * \sa setCoolStepConfiguration()
391
-     */
392
-    uint8_t getCoolStepNumberOfSGReadings();
393
-
394
-    /*!
395
-     * \brief returns the increment steps for the current for the CoolStep operation
396
-     * \sa setCoolStepConfiguration()
397
-     */
398
-    uint8_t getCoolStepCurrentIncrementSize();
399
-
400
-    /*!
401
-     * \brief returns the absolut minium current for the CoolStep operation
402
-     * \sa setCoolStepConfiguration()
403
-     * \sa COOL_STEP_HALF_CS_LIMIT, COOL_STEP_QUARTER_CS_LIMIT
404
-     */
405
-    uint8_t getCoolStepLowerCurrentLimit();
406
-
407
-    /*!
408
-     * \brief Get the current microstep position for phase A
409
-     * \return The current microstep position for phase A 0…255
410
-     *
411
-     * Keep in mind that this routine reads and writes a value via SPI - so this may take a bit time.
412
-     */
413
-    int16_t getMotorPosition();
414
-
415
-    /*!
416
-     * \brief Reads the current StallGuard value.
417
-     * \return The current StallGuard value, lesser values indicate higher load, 0 means stall detected.
418
-     * Keep in mind that this routine reads and writes a value via SPI - so this may take a bit time.
419
-     * \sa setStallGuardThreshold() for tuning the readout to sensible ranges.
420
-     */
421
-    int16_t getCurrentStallGuardReading();
422
-
423
-    /*!
424
-     * \brief Reads the current current setting value as fraction of the maximum current
425
-     * Returns values between 0 and 31, representing 1/32 to 32/32 (=1)
426
-     * \sa setCoolStepConfiguration()
427
-     */
428
-    uint8_t getCurrentCSReading();
429
-
430
-
431
-    /*!
432
-     *\brief a convenience method to determine if the current scaling uses 0.31V or 0.165V as reference.
433
-     *\return false if 0.13V is the reference voltage, true if 0.165V is used.
434
-     */
435
-    boolean isCurrentScalingHalfed();
436
-
437
-    /*!
438
-     * \brief Reads the current current setting value and recalculates the absolute current in mA (1A would be 1000).
439
-     * This method calculates the currently used current setting (either by setting or by CoolStep) and reconstructs
440
-     * the current in mA by usinge the VSENSE and resistor value. This method uses floating point math - so it
441
-     * may not be the fastest.
442
-     * \sa getCurrentCSReading(), getResistor(), isCurrentScalingHalfed(), getCurrent()
443
-     */
444
-    uint16_t getCurrentCurrent();
445
-
446
-    /*!
447
-     * \brief checks if there is a StallGuard warning in the last status
448
-     * \return 0 if there was no warning, -1 if there was some warning.
449
-     * Keep in mind that this method does not enforce a readout but uses the value of the last status readout.
450
-     * You may want to use getMotorPosition() or getCurrentStallGuardReading() to enforce an updated status readout.
451
-     *
452
-     * \sa setStallGuardThreshold() for tuning the readout to sensible ranges.
453
-     */
454
-    boolean isStallGuardOverThreshold();
455
-
456
-    /*!
457
-     * \brief Return over temperature status of the last status readout
458
-     * return 0 is everything is OK, TMC26X_OVERTEMPERATURE_PREWARING if status is reached, TMC26X_OVERTEMPERATURE_SHUTDOWN is the chip is shutdown, -1 if the status is unknown.
459
-     * Keep in mind that this method does not enforce a readout but uses the value of the last status readout.
460
-     * You may want to use getMotorPosition() or getCurrentStallGuardReading() to enforce an updated status readout.
461
-     */
462
-    char getOverTemperature();
463
-
464
-    /*!
465
-     * \brief Is motor channel A shorted to ground detected in the last status readout.
466
-     * \return true is yes, false if not.
467
-     * Keep in mind that this method does not enforce a readout but uses the value of the last status readout.
468
-     * You may want to use getMotorPosition() or getCurrentStallGuardReading() to enforce an updated status readout.
469
-     */
470
-
471
-    boolean isShortToGroundA();
472
-
473
-    /*!
474
-     * \brief Is motor channel B shorted to ground detected in the last status readout.
475
-     * \return true is yes, false if not.
476
-     * Keep in mind that this method does not enforce a readout but uses the value of the last status readout.
477
-     * You may want to use getMotorPosition() or getCurrentStallGuardReading() to enforce an updated status readout.
478
-     */
479
-    boolean isShortToGroundB();
480
-    /*!
481
-     * \brief iIs motor channel A connected according to the last statu readout.
482
-     * \return true is yes, false if not.
483
-     * Keep in mind that this method does not enforce a readout but uses the value of the last status readout.
484
-     * You may want to use getMotorPosition() or getCurrentStallGuardReading() to enforce an updated status readout.
485
-     */
486
-    boolean isOpenLoadA();
487
-
488
-    /*!
489
-     * \brief iIs motor channel A connected according to the last statu readout.
490
-     * \return true is yes, false if not.
491
-     * Keep in mind that this method does not enforce a readout but uses the value of the last status readout.
492
-     * You may want to use getMotorPosition() or getCurrentStallGuardReading() to enforce an updated status readout.
493
-     */
494
-    boolean isOpenLoadB();
495
-
496
-    /*!
497
-     * \brief Is chopper inactive since 2^20 clock cycles - defaults to ~0,08s
498
-     * \return true is yes, false if not.
499
-     * Keep in mind that this method does not enforce a readout but uses the value of the last status readout.
500
-     * You may want to use getMotorPosition() or getCurrentStallGuardReading() to enforce an updated status readout.
501
-     */
502
-    boolean isStandStill();
503
-
504
-    /*!
505
-     * \brief checks if there is a StallGuard warning in the last status
506
-     * \return 0 if there was no warning, -1 if there was some warning.
507
-     * Keep in mind that this method does not enforce a readout but uses the value of the last status readout.
508
-     * You may want to use getMotorPosition() or getCurrentStallGuardReading() to enforce an updated status readout.
509
-     *
510
-     * \sa isStallGuardOverThreshold()
511
-     * TODO why?
512
-     *
513
-     * \sa setStallGuardThreshold() for tuning the readout to sensible ranges.
514
-     */
515
-    boolean isStallGuardReached();
516
-
517
-    /*!
518
-     *\brief enables or disables the motor driver bridges. If disabled the motor can run freely. If enabled not.
519
-     *\param enabled a boolean value true if the motor should be enabled, false otherwise.
520
-     */
521
-    void setEnabled(boolean enabled);
522
-
523
-    /*!
524
-     *\brief checks if the output bridges are enabled. If the bridges are not enabled the motor can run freely
525
-     *\return true if the bridges and by that the motor driver are enabled, false if not.
526
-     *\sa setEnabled()
527
-     */
528
-    boolean isEnabled();
529
-
530
-    /*!
531
-     * \brief Manually read out the status register
532
-     * This function sends a byte to the motor driver in order to get the current readout. The parameter read_value
533
-     * seletcs which value will get returned. If the read_vlaue changes in respect to the previous readout this method
534
-     * automatically send two bytes to the motor: one to set the redout and one to get the actual readout. So this method
535
-     * may take time to send and read one or two bits - depending on the previous readout.
536
-     * \param read_value selects which value to read out (0..3). You can use the defines TMC26X_READOUT_POSITION, TMC_262_READOUT_STALLGUARD, or TMC_262_READOUT_CURRENT
537
-     * \sa TMC26X_READOUT_POSITION, TMC_262_READOUT_STALLGUARD, TMC_262_READOUT_CURRENT
538
-     */
539
-    void readStatus(char read_value);
540
-
541
-    /*!
542
-     * \brief Returns the current sense resistor value in milliohm.
543
-     * The default value of ,15 Ohm will return 150.
544
-     */
545
-    int16_t getResistor();
546
-
547
-    /*!
548
-     * \brief Prints out all the information that can be found in the last status read out - it does not force a status readout.
549
-     * The result is printed via Serial
550
-     */
551
-    void debugLastStatus();
552
-
553
-    /*!
554
-     * \brief library version
555
-     * \return the version number as int.
556
-     */
557
-    int16_t version();
558
-
559
-  private:
560
-    uint16_t steps_left;      // The steps the motor has to do to complete the movement
561
-    int16_t direction;        // Direction of rotation
562
-    uint32_t step_delay;      // Delay between steps, in ms, based on speed
563
-    int16_t number_of_steps;  // Total number of steps this motor can take
564
-    uint16_t speed;           // Store the current speed in order to change the speed after changing microstepping
565
-    uint16_t resistor;        // Current sense resitor value in milliohm
566
-
567
-    uint32_t last_step_time,  // Timestamp (ms) of the last step
568
-             next_step_time;  // Timestamp (ms) of the next step
569
-
570
-    // Driver control register copies to easily set & modify the registers
571
-    uint32_t driver_control_register_value,
572
-             chopper_config_register,
573
-             cool_step_register_value,
574
-             stallguard2_current_register_value,
575
-             driver_configuration_register_value,
576
-             driver_status_result; // The driver status result
577
-
578
-    // Helper routione to get the top 10 bit of the readout
579
-    inline int16_t getReadoutValue();
580
-
581
-    // The pins for the stepper driver
582
-    uint8_t cs_pin, step_pin, dir_pin;
583
-
584
-    // Status values
585
-    boolean started; // If the stepper has been started yet
586
-    int16_t microsteps; // The current number of micro steps
587
-    char constant_off_time; // We need to remember this value in order to enable and disable the motor
588
-    uint8_t cool_step_lower_threshold; //  we need to remember the threshold to enable and disable the CoolStep feature
589
-    boolean cool_step_enabled; // We need to remember this to configure the coolstep if it si enabled
590
-
591
-    // SPI sender
592
-    inline void send262(uint32_t datagram);
593
-};

+ 0
- 127
Marlin/src/HAL/STM32_F4_F7/STM32F7/timers.cpp Näytä tiedosto

@@ -1,127 +0,0 @@
1
-/**
2
- * Marlin 3D Printer Firmware
3
- *
4
- * Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
5
- * Copyright (c) 2016 Bob Cousins bobcousins42@googlemail.com
6
- * Copyright (c) 2015-2016 Nico Tonnhofer wurstnase.reprap@gmail.com
7
- *
8
- * This program is free software: you can redistribute it and/or modify
9
- * it under the terms of the GNU General Public License as published by
10
- * the Free Software Foundation, either version 3 of the License, or
11
- * (at your option) any later version.
12
- *
13
- * This program is distributed in the hope that it will be useful,
14
- * but WITHOUT ANY WARRANTY; without even the implied warranty of
15
- * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the
16
- * GNU General Public License for more details.
17
- *
18
- * You should have received a copy of the GNU General Public License
19
- * along with this program.  If not, see <https://www.gnu.org/licenses/>.
20
- *
21
- */
22
-#if defined(STM32GENERIC) && defined(STM32F7)
23
-
24
-#include "../../../inc/MarlinConfig.h"
25
-
26
-// ------------------------
27
-// Local defines
28
-// ------------------------
29
-
30
-#define NUM_HARDWARE_TIMERS 2
31
-
32
-//#define PRESCALER 1
33
-
34
-// ------------------------
35
-// Private Variables
36
-// ------------------------
37
-
38
-tTimerConfig timerConfig[NUM_HARDWARE_TIMERS];
39
-
40
-// ------------------------
41
-// Public functions
42
-// ------------------------
43
-
44
-bool timers_initialized[NUM_HARDWARE_TIMERS] = { false };
45
-
46
-void HAL_timer_start(const uint8_t timer_num, const uint32_t frequency) {
47
-
48
-  if (!timers_initialized[timer_num]) {
49
-    switch (timer_num) {
50
-      case STEP_TIMER_NUM:
51
-      //STEPPER TIMER TIM5 //use a 32bit timer
52
-      __HAL_RCC_TIM5_CLK_ENABLE();
53
-      timerConfig[0].timerdef.Instance               = TIM5;
54
-      timerConfig[0].timerdef.Init.Prescaler         = (STEPPER_TIMER_PRESCALE);
55
-      timerConfig[0].timerdef.Init.CounterMode       = TIM_COUNTERMODE_UP;
56
-      timerConfig[0].timerdef.Init.ClockDivision     = TIM_CLOCKDIVISION_DIV1;
57
-      timerConfig[0].IRQ_Id = TIM5_IRQn;
58
-      timerConfig[0].callback = (uint32_t)TC5_Handler;
59
-      HAL_NVIC_SetPriority(timerConfig[0].IRQ_Id, 1, 0);
60
-      #if PIN_EXISTS(STEPPER_ENABLE)
61
-        OUT_WRITE(STEPPER_ENABLE_PIN, HIGH);
62
-      #endif
63
-      break;
64
-    case TEMP_TIMER_NUM:
65
-      //TEMP TIMER TIM7 // any available 16bit Timer (1 already used for PWM)
66
-      __HAL_RCC_TIM7_CLK_ENABLE();
67
-      timerConfig[1].timerdef.Instance               = TIM7;
68
-      timerConfig[1].timerdef.Init.Prescaler         = (TEMP_TIMER_PRESCALE);
69
-      timerConfig[1].timerdef.Init.CounterMode       = TIM_COUNTERMODE_UP;
70
-      timerConfig[1].timerdef.Init.ClockDivision     = TIM_CLOCKDIVISION_DIV1;
71
-      timerConfig[1].IRQ_Id = TIM7_IRQn;
72
-      timerConfig[1].callback = (uint32_t)TC7_Handler;
73
-      HAL_NVIC_SetPriority(timerConfig[1].IRQ_Id, 2, 0);
74
-      break;
75
-    }
76
-    timers_initialized[timer_num] = true;
77
-  }
78
-
79
-  timerConfig[timer_num].timerdef.Init.Period = (((HAL_TIMER_RATE) / timerConfig[timer_num].timerdef.Init.Prescaler) / frequency) - 1;
80
-
81
-  if (HAL_TIM_Base_Init(&timerConfig[timer_num].timerdef) == HAL_OK)
82
-    HAL_TIM_Base_Start_IT(&timerConfig[timer_num].timerdef);
83
-}
84
-
85
-//forward the interrupt
86
-extern "C" {
87
-  void TIM5_IRQHandler() { ((void(*)())timerConfig[0].callback)(); }
88
-  void TIM7_IRQHandler() { ((void(*)())timerConfig[1].callback)(); }
89
-}
90
-
91
-void HAL_timer_set_compare(const uint8_t timer_num, const uint32_t compare) {
92
-  __HAL_TIM_SetAutoreload(&timerConfig[timer_num].timerdef, compare);
93
-}
94
-
95
-void HAL_timer_enable_interrupt(const uint8_t timer_num) {
96
-  HAL_NVIC_EnableIRQ(timerConfig[timer_num].IRQ_Id);
97
-}
98
-
99
-void HAL_timer_disable_interrupt(const uint8_t timer_num) {
100
-  HAL_NVIC_DisableIRQ(timerConfig[timer_num].IRQ_Id);
101
-
102
-  // We NEED memory barriers to ensure Interrupts are actually disabled!
103
-  // ( https://dzone.com/articles/nvic-disabling-interrupts-on-arm-cortex-m-and-the )
104
-  __DSB();
105
-  __ISB();
106
-}
107
-
108
-hal_timer_t HAL_timer_get_compare(const uint8_t timer_num) {
109
-  return __HAL_TIM_GetAutoreload(&timerConfig[timer_num].timerdef);
110
-}
111
-
112
-uint32_t HAL_timer_get_count(const uint8_t timer_num) {
113
-  return __HAL_TIM_GetCounter(&timerConfig[timer_num].timerdef);
114
-}
115
-
116
-void HAL_timer_isr_prologue(const uint8_t timer_num) {
117
-  if (__HAL_TIM_GET_FLAG(&timerConfig[timer_num].timerdef, TIM_FLAG_UPDATE) == SET) {
118
-    __HAL_TIM_CLEAR_FLAG(&timerConfig[timer_num].timerdef, TIM_FLAG_UPDATE);
119
-  }
120
-}
121
-
122
-bool HAL_timer_interrupt_enabled(const uint8_t timer_num) {
123
-  const uint32_t IRQ_Id = uint32_t(timerConfig[timer_num].IRQ_Id);
124
-  return NVIC->ISER[IRQ_Id >> 5] & _BV32(IRQ_Id & 0x1F);
125
-}
126
-
127
-#endif // STM32GENERIC && STM32F7

+ 0
- 107
Marlin/src/HAL/STM32_F4_F7/STM32F7/timers.h Näytä tiedosto

@@ -1,107 +0,0 @@
1
-/**
2
- * Marlin 3D Printer Firmware
3
- *
4
- * Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
5
- * Copyright (c) 2016 Bob Cousins bobcousins42@googlemail.com
6
- * Copyright (c) 2017 Victor Perez
7
- *
8
- * This program is free software: you can redistribute it and/or modify
9
- * it under the terms of the GNU General Public License as published by
10
- * the Free Software Foundation, either version 3 of the License, or
11
- * (at your option) any later version.
12
- *
13
- * This program is distributed in the hope that it will be useful,
14
- * but WITHOUT ANY WARRANTY; without even the implied warranty of
15
- * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the
16
- * GNU General Public License for more details.
17
- *
18
- * You should have received a copy of the GNU General Public License
19
- * along with this program.  If not, see <https://www.gnu.org/licenses/>.
20
- *
21
- */
22
-#pragma once
23
-
24
-#include <stdint.h>
25
-
26
-// ------------------------
27
-// Defines
28
-// ------------------------
29
-
30
-#define FORCE_INLINE __attribute__((always_inline)) inline
31
-
32
-#define hal_timer_t uint32_t  // TODO: One is 16-bit, one 32-bit - does this need to be checked?
33
-#define HAL_TIMER_TYPE_MAX 0xFFFF
34
-
35
-#define HAL_TIMER_RATE         (HAL_RCC_GetSysClockFreq() / 2)  // frequency of timer peripherals
36
-
37
-#ifndef STEP_TIMER_NUM
38
-  #define STEP_TIMER_NUM        0  // Timer Index for Stepper
39
-#endif
40
-#ifndef PULSE_TIMER_NUM
41
-  #define PULSE_TIMER_NUM       STEP_TIMER_NUM
42
-#endif
43
-#ifndef TEMP_TIMER_NUM
44
-  #define TEMP_TIMER_NUM        1  // Timer Index for Temperature
45
-#endif
46
-
47
-#define TEMP_TIMER_FREQUENCY    1000 // temperature interrupt frequency
48
-#define TEMP_TIMER_PRESCALE     1000 // prescaler for setting Temp timer, 72Khz
49
-
50
-#define STEPPER_TIMER_PRESCALE 54    // was 40,prescaler for setting stepper timer, 2Mhz
51
-#define STEPPER_TIMER_RATE     (HAL_TIMER_RATE / STEPPER_TIMER_PRESCALE)   // frequency of stepper timer
52
-#define STEPPER_TIMER_TICKS_PER_US ((STEPPER_TIMER_RATE) / 1000000) // stepper timer ticks per µs
53
-
54
-#define PULSE_TIMER_RATE       STEPPER_TIMER_RATE   // frequency of pulse timer
55
-#define PULSE_TIMER_PRESCALE   STEPPER_TIMER_PRESCALE
56
-#define PULSE_TIMER_TICKS_PER_US STEPPER_TIMER_TICKS_PER_US
57
-
58
-#define ENABLE_STEPPER_DRIVER_INTERRUPT() HAL_timer_enable_interrupt(STEP_TIMER_NUM)
59
-#define DISABLE_STEPPER_DRIVER_INTERRUPT() HAL_timer_disable_interrupt(STEP_TIMER_NUM)
60
-
61
-#define ENABLE_TEMPERATURE_INTERRUPT() HAL_timer_enable_interrupt(TEMP_TIMER_NUM)
62
-#define DISABLE_TEMPERATURE_INTERRUPT() HAL_timer_disable_interrupt(TEMP_TIMER_NUM)
63
-
64
-#define STEPPER_ISR_ENABLED() HAL_timer_interrupt_enabled(STEP_TIMER_NUM)
65
-#define TEMP_ISR_ENABLED() HAL_timer_interrupt_enabled(TEMP_TIMER_NUM)
66
-
67
-// TODO change this
68
-
69
-extern void TC5_Handler();
70
-extern void TC7_Handler();
71
-#ifndef HAL_STEP_TIMER_ISR
72
-  #define HAL_STEP_TIMER_ISR()  void TC5_Handler()
73
-#endif
74
-#ifndef HAL_TEMP_TIMER_ISR
75
-  #define HAL_TEMP_TIMER_ISR()  void TC7_Handler()
76
-#endif
77
-
78
-// ------------------------
79
-// Types
80
-// ------------------------
81
-
82
-typedef struct {
83
-  TIM_HandleTypeDef timerdef;
84
-  IRQn_Type   IRQ_Id;
85
-  uint32_t callback;
86
-} tTimerConfig;
87
-
88
-// ------------------------
89
-// Public Variables
90
-// ------------------------
91
-
92
-//extern const tTimerConfig timerConfig[];
93
-
94
-// ------------------------
95
-// Public functions
96
-// ------------------------
97
-
98
-void HAL_timer_start(const uint8_t timer_num, const uint32_t frequency);
99
-void HAL_timer_enable_interrupt(const uint8_t timer_num);
100
-void HAL_timer_disable_interrupt(const uint8_t timer_num);
101
-bool HAL_timer_interrupt_enabled(const uint8_t timer_num);
102
-
103
-void HAL_timer_set_compare(const uint8_t timer_num, const uint32_t compare);
104
-hal_timer_t HAL_timer_get_compare(const uint8_t timer_num);
105
-uint32_t HAL_timer_get_count(const uint8_t timer_num);
106
-void HAL_timer_isr_prologue(const uint8_t timer_num);
107
-#define HAL_timer_isr_epilogue(TIMER_NUM)

+ 0
- 51
Marlin/src/HAL/STM32_F4_F7/Servo.cpp Näytä tiedosto

@@ -1,51 +0,0 @@
1
-/**
2
- * Marlin 3D Printer Firmware
3
- * Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
4
- *
5
- * Based on Sprinter and grbl.
6
- * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm
7
- * Copyright (c) 2017 Victor Perez
8
- *
9
- * This program is free software: you can redistribute it and/or modify
10
- * it under the terms of the GNU General Public License as published by
11
- * the Free Software Foundation, either version 3 of the License, or
12
- * (at your option) any later version.
13
- *
14
- * This program is distributed in the hope that it will be useful,
15
- * but WITHOUT ANY WARRANTY; without even the implied warranty of
16
- * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the
17
- * GNU General Public License for more details.
18
- *
19
- * You should have received a copy of the GNU General Public License
20
- * along with this program.  If not, see <https://www.gnu.org/licenses/>.
21
- *
22
- */
23
-#if defined(STM32GENERIC) && (defined(STM32F4) || defined(STM32F7))
24
-
25
-#include "../../inc/MarlinConfig.h"
26
-
27
-#if HAS_SERVOS
28
-
29
-#include "Servo.h"
30
-
31
-int8_t libServo::attach(const int pin) {
32
-  if (servoIndex >= MAX_SERVOS) return -1;
33
-  return super::attach(pin);
34
-}
35
-
36
-int8_t libServo::attach(const int pin, const int min, const int max) {
37
-  return super::attach(pin, min, max);
38
-}
39
-
40
-void libServo::move(const int value) {
41
-  constexpr uint16_t servo_delay[] = SERVO_DELAY;
42
-  static_assert(COUNT(servo_delay) == NUM_SERVOS, "SERVO_DELAY must be an array NUM_SERVOS long.");
43
-  if (attach(0) >= 0) {
44
-    write(value);
45
-    safe_delay(servo_delay[servoIndex]);
46
-    TERN_(DEACTIVATE_SERVOS_AFTER_MOVE, detach());
47
-  }
48
-}
49
-
50
-#endif // HAS_SERVOS
51
-#endif // STM32GENERIC && (STM32F4 || STM32F7)

+ 0
- 41
Marlin/src/HAL/STM32_F4_F7/Servo.h Näytä tiedosto

@@ -1,41 +0,0 @@
1
-/**
2
- * Marlin 3D Printer Firmware
3
- * Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
4
- *
5
- * Based on Sprinter and grbl.
6
- * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm
7
- * Copyright (c) 2017 Victor Perez
8
- *
9
- * This program is free software: you can redistribute it and/or modify
10
- * it under the terms of the GNU General Public License as published by
11
- * the Free Software Foundation, either version 3 of the License, or
12
- * (at your option) any later version.
13
- *
14
- * This program is distributed in the hope that it will be useful,
15
- * but WITHOUT ANY WARRANTY; without even the implied warranty of
16
- * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the
17
- * GNU General Public License for more details.
18
- *
19
- * You should have received a copy of the GNU General Public License
20
- * along with this program.  If not, see <https://www.gnu.org/licenses/>.
21
- *
22
- */
23
-#pragma once
24
-
25
-//#ifdef STM32F7
26
-//  #include <../../libraries/Servo/src/Servo.h>
27
-//#else
28
-  #include <Servo.h>
29
-//#endif
30
-
31
-// Inherit and expand on the official library
32
-class libServo : public Servo {
33
-  public:
34
-    int8_t attach(const int pin);
35
-    int8_t attach(const int pin, const int min, const int max);
36
-    void move(const int value);
37
-  private:
38
-    typedef Servo super;
39
-    uint16_t min_ticks, max_ticks;
40
-    uint8_t servoIndex;               // index into the channel data for this servo
41
-};

+ 0
- 535
Marlin/src/HAL/STM32_F4_F7/eeprom_emul.cpp Näytä tiedosto

@@ -1,535 +0,0 @@
1
-/**
2
-  ******************************************************************************
3
-  * @file    eeprom_emul.cpp
4
-  * @author  MCD Application Team
5
-  * @version V1.2.6
6
-  * @date    04-November-2016
7
-  * @brief   This file provides all the EEPROM emulation firmware functions.
8
-  ******************************************************************************
9
-  * @attention
10
-  *
11
-  * Copyright © 2016 STMicroelectronics International N.V.
12
-  * All rights reserved.
13
-  *
14
-  * Redistribution and use in source and binary forms, with or without
15
-  * modification, are permitted, provided that the following conditions are met:
16
-  *
17
-  * 1. Redistribution of source code must retain the above copyright notice,
18
-  *    this list of conditions and the following disclaimer.
19
-  * 2. Redistributions in binary form must reproduce the above copyright notice,
20
-  *    this list of conditions and the following disclaimer in the documentation
21
-  *    and/or other materials provided with the distribution.
22
-  * 3. Neither the name of STMicroelectronics nor the names of other
23
-  *    contributors to this software may be used to endorse or promote products
24
-  *    derived from this software without specific written permission.
25
-  * 4. This software, including modifications and/or derivative works of this
26
-  *    software, must execute solely and exclusively on microcontroller or
27
-  *    microprocessor devices manufactured by or for STMicroelectronics.
28
-  * 5. Redistribution and use of this software other than as permitted under
29
-  *    this license is void and will automatically terminate your rights under
30
-  *    this license.
31
-  *
32
-  * THIS SOFTWARE IS PROVIDED BY STMICROELECTRONICS AND CONTRIBUTORS "AS IS"
33
-  * AND ANY EXPRESS, IMPLIED OR STATUTORY WARRANTIES, INCLUDING, BUT NOT
34
-  * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY, FITNESS FOR A
35
-  * PARTICULAR PURPOSE AND NON-INFRINGEMENT OF THIRD PARTY INTELLECTUAL PROPERTY
36
-  * RIGHTS ARE DISCLAIMED TO THE FULLEST EXTENT PERMITTED BY LAW. IN NO EVENT
37
-  * SHALL STMICROELECTRONICS OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
38
-  * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT
39
-  * LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA,
40
-  * OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF
41
-  * LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING
42
-  * NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE,
43
-  * EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
44
-  *
45
-  ******************************************************************************
46
-  */
47
-/** @addtogroup EEPROM_Emulation
48
-  * @{
49
-  */
50
-#if defined(STM32GENERIC) && (defined(STM32F4) || defined(STM32F7))
51
-
52
-#include "../../inc/MarlinConfig.h"
53
-
54
-#if ENABLED(FLASH_EEPROM_EMULATION)
55
-
56
-/* Includes ------------------------------------------------------------------*/
57
-#include "eeprom_emul.h"
58
-
59
-/* Private variables ---------------------------------------------------------*/
60
-
61
-/* Global variable used to store variable value in read sequence */
62
-uint16_t DataVar = 0;
63
-
64
-/* Virtual address defined by the user: 0xFFFF value is prohibited */
65
-uint16_t VirtAddVarTab[NB_OF_VAR];
66
-
67
-/* Private function prototypes -----------------------------------------------*/
68
-
69
-static HAL_StatusTypeDef EE_Format();
70
-static uint16_t EE_FindValidPage(uint8_t Operation);
71
-static uint16_t EE_VerifyPageFullWriteVariable(uint16_t VirtAddress, uint16_t Data);
72
-static uint16_t EE_PageTransfer(uint16_t VirtAddress, uint16_t Data);
73
-static uint16_t EE_VerifyPageFullyErased(uint32_t Address);
74
-
75
- /**
76
-  * @brief  Restore the pages to a known good state in case of page's status
77
-  *   corruption after a power loss.
78
-  * @param  None.
79
-  * @retval - Flash error code: on write Flash error
80
-  *         - FLASH_COMPLETE: on success
81
-  */
82
-
83
-/* Private functions ---------------------------------------------------------*/
84
-
85
-uint16_t EE_Initialize() {
86
-  /* Get Page0 and Page1 status */
87
-  uint16_t PageStatus0 = (*(__IO uint16_t*)PAGE0_BASE_ADDRESS),
88
-           PageStatus1 = (*(__IO uint16_t*)PAGE1_BASE_ADDRESS);
89
-
90
-  FLASH_EraseInitTypeDef pEraseInit;
91
-  pEraseInit.TypeErase = TYPEERASE_SECTORS;
92
-  pEraseInit.Sector = PAGE0_ID;
93
-  pEraseInit.NbSectors = 1;
94
-  pEraseInit.VoltageRange = VOLTAGE_RANGE;
95
-
96
-  HAL_StatusTypeDef FlashStatus; // = HAL_OK
97
-
98
-  /* Check for invalid header states and repair if necessary */
99
-  uint32_t SectorError;
100
-  switch (PageStatus0) {
101
-    case ERASED:
102
-      if (PageStatus1 == VALID_PAGE) { /* Page0 erased, Page1 valid */
103
-        /* Erase Page0 */
104
-        if (!EE_VerifyPageFullyErased(PAGE0_BASE_ADDRESS)) {
105
-          /* As the last operation, simply return the result */
106
-          return HAL_FLASHEx_Erase(&pEraseInit, &SectorError);
107
-        }
108
-      }
109
-      else if (PageStatus1 == RECEIVE_DATA) { /* Page0 erased, Page1 receive */
110
-        /* Erase Page0 */
111
-        if (!EE_VerifyPageFullyErased(PAGE0_BASE_ADDRESS)) {
112
-          HAL_StatusTypeDef fStat = HAL_FLASHEx_Erase(&pEraseInit, &SectorError);
113
-          /* If erase operation was failed, a Flash error code is returned */
114
-          if (fStat != HAL_OK) return fStat;
115
-        }
116
-        /* Mark Page1 as valid */
117
-        /* As the last operation, simply return the result */
118
-        return HAL_FLASH_Program(TYPEPROGRAM_HALFWORD, PAGE1_BASE_ADDRESS, VALID_PAGE);
119
-      }
120
-      else { /* First EEPROM access (Page0&1 are erased) or invalid state -> format EEPROM */
121
-        /* Erase both Page0 and Page1 and set Page0 as valid page */
122
-        /* As the last operation, simply return the result */
123
-        return EE_Format();
124
-      }
125
-      break;
126
-
127
-    case RECEIVE_DATA:
128
-      if (PageStatus1 == VALID_PAGE) { /* Page0 receive, Page1 valid */
129
-        /* Transfer data from Page1 to Page0 */
130
-        int16_t x = -1;
131
-        for (uint16_t VarIdx = 0; VarIdx < NB_OF_VAR; VarIdx++) {
132
-          if (( *(__IO uint16_t*)(PAGE0_BASE_ADDRESS + 6)) == VirtAddVarTab[VarIdx])
133
-            x = VarIdx;
134
-          if (VarIdx != x) {
135
-            /* Read the last variables' updates */
136
-            uint16_t ReadStatus = EE_ReadVariable(VirtAddVarTab[VarIdx], &DataVar);
137
-            /* In case variable corresponding to the virtual address was found */
138
-            if (ReadStatus != 0x1) {
139
-              /* Transfer the variable to the Page0 */
140
-              uint16_t EepromStatus = EE_VerifyPageFullWriteVariable(VirtAddVarTab[VarIdx], DataVar);
141
-              /* If program operation was failed, a Flash error code is returned */
142
-              if (EepromStatus != HAL_OK) return EepromStatus;
143
-            }
144
-          }
145
-        }
146
-        /* Mark Page0 as valid */
147
-        FlashStatus = HAL_FLASH_Program(TYPEPROGRAM_HALFWORD, PAGE0_BASE_ADDRESS, VALID_PAGE);
148
-        /* If program operation was failed, a Flash error code is returned */
149
-        if (FlashStatus != HAL_OK) return FlashStatus;
150
-        pEraseInit.Sector = PAGE1_ID;
151
-        pEraseInit.NbSectors = 1;
152
-        pEraseInit.VoltageRange = VOLTAGE_RANGE;
153
-        /* Erase Page1 */
154
-        if (!EE_VerifyPageFullyErased(PAGE1_BASE_ADDRESS)) {
155
-          /* As the last operation, simply return the result */
156
-          return HAL_FLASHEx_Erase(&pEraseInit, &SectorError);
157
-        }
158
-      }
159
-      else if (PageStatus1 == ERASED) { /* Page0 receive, Page1 erased */
160
-        pEraseInit.Sector = PAGE1_ID;
161
-        pEraseInit.NbSectors = 1;
162
-        pEraseInit.VoltageRange = VOLTAGE_RANGE;
163
-        /* Erase Page1 */
164
-        if (!EE_VerifyPageFullyErased(PAGE1_BASE_ADDRESS)) {
165
-          HAL_StatusTypeDef fStat = HAL_FLASHEx_Erase(&pEraseInit, &SectorError);
166
-          /* If erase operation was failed, a Flash error code is returned */
167
-          if (fStat != HAL_OK) return fStat;
168
-        }
169
-        /* Mark Page0 as valid */
170
-        /* As the last operation, simply return the result */
171
-        return HAL_FLASH_Program(TYPEPROGRAM_HALFWORD, PAGE0_BASE_ADDRESS, VALID_PAGE);
172
-      }
173
-      else { /* Invalid state -> format eeprom */
174
-        /* Erase both Page0 and Page1 and set Page0 as valid page */
175
-        /* As the last operation, simply return the result */
176
-        return EE_Format();
177
-      }
178
-      break;
179
-
180
-    case VALID_PAGE:
181
-      if (PageStatus1 == VALID_PAGE) { /* Invalid state -> format eeprom */
182
-        /* Erase both Page0 and Page1 and set Page0 as valid page */
183
-        FlashStatus = EE_Format();
184
-        /* If erase/program operation was failed, a Flash error code is returned */
185
-        if (FlashStatus != HAL_OK) return FlashStatus;
186
-      }
187
-      else if (PageStatus1 == ERASED) { /* Page0 valid, Page1 erased */
188
-        pEraseInit.Sector = PAGE1_ID;
189
-        pEraseInit.NbSectors = 1;
190
-        pEraseInit.VoltageRange = VOLTAGE_RANGE;
191
-        /* Erase Page1 */
192
-        if (!EE_VerifyPageFullyErased(PAGE1_BASE_ADDRESS)) {
193
-          FlashStatus = HAL_FLASHEx_Erase(&pEraseInit, &SectorError);
194
-          /* If erase operation was failed, a Flash error code is returned */
195
-          if (FlashStatus != HAL_OK) return FlashStatus;
196
-        }
197
-      }
198
-      else { /* Page0 valid, Page1 receive */
199
-        /* Transfer data from Page0 to Page1 */
200
-        int16_t x = -1;
201
-        for (uint16_t VarIdx = 0; VarIdx < NB_OF_VAR; VarIdx++) {
202
-          if ((*(__IO uint16_t*)(PAGE1_BASE_ADDRESS + 6)) == VirtAddVarTab[VarIdx])
203
-            x = VarIdx;
204
-
205
-          if (VarIdx != x) {
206
-            /* Read the last variables' updates */
207
-            uint16_t ReadStatus = EE_ReadVariable(VirtAddVarTab[VarIdx], &DataVar);
208
-            /* In case variable corresponding to the virtual address was found */
209
-            if (ReadStatus != 0x1) {
210
-              /* Transfer the variable to the Page1 */
211
-              uint16_t EepromStatus = EE_VerifyPageFullWriteVariable(VirtAddVarTab[VarIdx], DataVar);
212
-              /* If program operation was failed, a Flash error code is returned */
213
-              if (EepromStatus != HAL_OK) return EepromStatus;
214
-            }
215
-          }
216
-        }
217
-        /* Mark Page1 as valid */
218
-        FlashStatus = HAL_FLASH_Program(TYPEPROGRAM_HALFWORD, PAGE1_BASE_ADDRESS, VALID_PAGE);
219
-        /* If program operation was failed, a Flash error code is returned */
220
-        if (FlashStatus != HAL_OK) return FlashStatus;
221
-        pEraseInit.Sector = PAGE0_ID;
222
-        pEraseInit.NbSectors = 1;
223
-        pEraseInit.VoltageRange = VOLTAGE_RANGE;
224
-        /* Erase Page0 */
225
-        if (!EE_VerifyPageFullyErased(PAGE0_BASE_ADDRESS)) {
226
-          /* As the last operation, simply return the result */
227
-          return HAL_FLASHEx_Erase(&pEraseInit, &SectorError);
228
-        }
229
-      }
230
-      break;
231
-
232
-    default:  /* Any other state -> format eeprom */
233
-      /* Erase both Page0 and Page1 and set Page0 as valid page */
234
-      /* As the last operation, simply return the result */
235
-      return EE_Format();
236
-  }
237
-
238
-  return HAL_OK;
239
-}
240
-
241
-/**
242
- * @brief  Verify if specified page is fully erased.
243
- * @param  Address: page address
244
- *   This parameter can be one of the following values:
245
- *     @arg PAGE0_BASE_ADDRESS: Page0 base address
246
- *     @arg PAGE1_BASE_ADDRESS: Page1 base address
247
- * @retval page fully erased status:
248
- *           - 0: if Page not erased
249
- *           - 1: if Page erased
250
- */
251
-uint16_t EE_VerifyPageFullyErased(uint32_t Address) {
252
-  uint32_t ReadStatus = 1;
253
-  /* Check each active page address starting from end */
254
-  while (Address <= PAGE0_END_ADDRESS) {
255
-    /* Get the current location content to be compared with virtual address */
256
-    uint16_t AddressValue = (*(__IO uint16_t*)Address);
257
-    /* Compare the read address with the virtual address */
258
-    if (AddressValue != ERASED) {
259
-      /* In case variable value is read, reset ReadStatus flag */
260
-      ReadStatus = 0;
261
-      break;
262
-    }
263
-    /* Next address location */
264
-    Address += 4;
265
-  }
266
-  /* Return ReadStatus value: (0: Page not erased, 1: Sector erased) */
267
-  return ReadStatus;
268
-}
269
-
270
-/**
271
- * @brief  Returns the last stored variable data, if found, which correspond to
272
- *   the passed virtual address
273
- * @param  VirtAddress: Variable virtual address
274
- * @param  Data: Global variable contains the read variable value
275
- * @retval Success or error status:
276
- *           - 0: if variable was found
277
- *           - 1: if the variable was not found
278
- *           - NO_VALID_PAGE: if no valid page was found.
279
- */
280
-uint16_t EE_ReadVariable(uint16_t VirtAddress, uint16_t* Data) {
281
-  uint16_t ReadStatus = 1;
282
-
283
-  /* Get active Page for read operation */
284
-  uint16_t ValidPage = EE_FindValidPage(READ_FROM_VALID_PAGE);
285
-
286
-  /* Check if there is no valid page */
287
-  if (ValidPage == NO_VALID_PAGE) return NO_VALID_PAGE;
288
-
289
-  /* Get the valid Page start and end Addresses */
290
-  uint32_t PageStartAddress = uint32_t(EEPROM_START_ADDRESS) + uint32_t(ValidPage * (PAGE_SIZE)),
291
-           Address = PageStartAddress + PAGE_SIZE - 2;
292
-
293
-  /* Check each active page address starting from end */
294
-  while (Address > PageStartAddress + 2) {
295
-    /* Get the current location content to be compared with virtual address */
296
-    uint16_t AddressValue = (*(__IO uint16_t*)Address);
297
-
298
-    /* Compare the read address with the virtual address */
299
-    if (AddressValue == VirtAddress) {
300
-      /* Get content of Address-2 which is variable value */
301
-      *Data = (*(__IO uint16_t*)(Address - 2));
302
-      /* In case variable value is read, reset ReadStatus flag */
303
-      ReadStatus = 0;
304
-      break;
305
-    }
306
-    else /* Next address location */
307
-      Address -= 4;
308
-  }
309
-  /* Return ReadStatus value: (0: variable exist, 1: variable doesn't exist) */
310
-  return ReadStatus;
311
-}
312
-
313
-/**
314
- * @brief  Writes/upadtes variable data in EEPROM.
315
- * @param  VirtAddress: Variable virtual address
316
- * @param  Data: 16 bit data to be written
317
- * @retval Success or error status:
318
- *           - FLASH_COMPLETE: on success
319
- *           - PAGE_FULL: if valid page is full
320
- *           - NO_VALID_PAGE: if no valid page was found
321
- *           - Flash error code: on write Flash error
322
- */
323
-uint16_t EE_WriteVariable(uint16_t VirtAddress, uint16_t Data) {
324
-  /* Write the variable virtual address and value in the EEPROM */
325
-  uint16_t Status = EE_VerifyPageFullWriteVariable(VirtAddress, Data);
326
-
327
-  /* In case the EEPROM active page is full */
328
-  if (Status == PAGE_FULL) /* Perform Page transfer */
329
-    Status = EE_PageTransfer(VirtAddress, Data);
330
-
331
-  /* Return last operation status */
332
-  return Status;
333
-}
334
-
335
-/**
336
- * @brief  Erases PAGE and PAGE1 and writes VALID_PAGE header to PAGE
337
- * @param  None
338
- * @retval Status of the last operation (Flash write or erase) done during
339
- *         EEPROM formatting
340
- */
341
-static HAL_StatusTypeDef EE_Format() {
342
-  FLASH_EraseInitTypeDef pEraseInit;
343
-  pEraseInit.TypeErase = FLASH_TYPEERASE_SECTORS;
344
-  pEraseInit.Sector = PAGE0_ID;
345
-  pEraseInit.NbSectors = 1;
346
-  pEraseInit.VoltageRange = VOLTAGE_RANGE;
347
-
348
-  HAL_StatusTypeDef FlashStatus; // = HAL_OK
349
-
350
-  /* Erase Page0 */
351
-  if (!EE_VerifyPageFullyErased(PAGE0_BASE_ADDRESS)) {
352
-    uint32_t SectorError;
353
-    FlashStatus = HAL_FLASHEx_Erase(&pEraseInit, &SectorError);
354
-    /* If erase operation was failed, a Flash error code is returned */
355
-    if (FlashStatus != HAL_OK) return FlashStatus;
356
-  }
357
-  /* Set Page0 as valid page: Write VALID_PAGE at Page0 base address */
358
-  FlashStatus = HAL_FLASH_Program(TYPEPROGRAM_HALFWORD, PAGE0_BASE_ADDRESS, VALID_PAGE);
359
-  /* If program operation was failed, a Flash error code is returned */
360
-  if (FlashStatus != HAL_OK) return FlashStatus;
361
-
362
-  pEraseInit.Sector = PAGE1_ID;
363
-  /* Erase Page1 */
364
-  if (!EE_VerifyPageFullyErased(PAGE1_BASE_ADDRESS)) {
365
-    /* As the last operation, just return the result code */
366
-    uint32_t SectorError;
367
-    return HAL_FLASHEx_Erase(&pEraseInit, &SectorError);
368
-  }
369
-
370
-  return HAL_OK;
371
-}
372
-
373
-/**
374
- * @brief  Find valid Page for write or read operation
375
- * @param  Operation: operation to achieve on the valid page.
376
- *   This parameter can be one of the following values:
377
- *     @arg READ_FROM_VALID_PAGE: read operation from valid page
378
- *     @arg WRITE_IN_VALID_PAGE: write operation from valid page
379
- * @retval Valid page number (PAGE or PAGE1) or NO_VALID_PAGE in case
380
- *   of no valid page was found
381
- */
382
-static uint16_t EE_FindValidPage(uint8_t Operation) {
383
-  /* Get Page0 and Page1 actual status */
384
-  uint16_t PageStatus0 = (*(__IO uint16_t*)PAGE0_BASE_ADDRESS),
385
-           PageStatus1 = (*(__IO uint16_t*)PAGE1_BASE_ADDRESS);
386
-
387
-  /* Write or read operation */
388
-  switch (Operation) {
389
-    case WRITE_IN_VALID_PAGE:   /* ---- Write operation ---- */
390
-      if (PageStatus1 == VALID_PAGE) {
391
-        /* Page0 receiving data */
392
-        return (PageStatus0 == RECEIVE_DATA) ? PAGE0 : PAGE1;
393
-      }
394
-      else if (PageStatus0 == VALID_PAGE) {
395
-        /* Page1 receiving data */
396
-        return (PageStatus1 == RECEIVE_DATA) ? PAGE1 : PAGE0;
397
-      }
398
-      else
399
-        return NO_VALID_PAGE;   /* No valid Page */
400
-
401
-    case READ_FROM_VALID_PAGE:  /* ---- Read operation ---- */
402
-      if (PageStatus0 == VALID_PAGE)
403
-        return PAGE0;           /* Page0 valid */
404
-      else if (PageStatus1 == VALID_PAGE)
405
-        return PAGE1;           /* Page1 valid */
406
-      else
407
-        return NO_VALID_PAGE;   /* No valid Page */
408
-
409
-    default:
410
-      return PAGE0;             /* Page0 valid */
411
-  }
412
-}
413
-
414
-/**
415
- * @brief  Verify if active page is full and Writes variable in EEPROM.
416
- * @param  VirtAddress: 16 bit virtual address of the variable
417
- * @param  Data: 16 bit data to be written as variable value
418
- * @retval Success or error status:
419
- *           - FLASH_COMPLETE: on success
420
- *           - PAGE_FULL: if valid page is full
421
- *           - NO_VALID_PAGE: if no valid page was found
422
- *           - Flash error code: on write Flash error
423
- */
424
-static uint16_t EE_VerifyPageFullWriteVariable(uint16_t VirtAddress, uint16_t Data) {
425
-  /* Get valid Page for write operation */
426
-  uint16_t ValidPage = EE_FindValidPage(WRITE_IN_VALID_PAGE);
427
-
428
-  /* Check if there is no valid page */
429
-  if (ValidPage == NO_VALID_PAGE) return NO_VALID_PAGE;
430
-
431
-  /* Get the valid Page start and end Addresses */
432
-  uint32_t Address = uint32_t(EEPROM_START_ADDRESS) + uint32_t(ValidPage * (PAGE_SIZE)),
433
-           PageEndAddress = Address + PAGE_SIZE - 1;
434
-
435
-  /* Check each active page address starting from begining */
436
-  while (Address < PageEndAddress) {
437
-    /* Verify if Address and Address+2 contents are 0xFFFFFFFF */
438
-    if ((*(__IO uint32_t*)Address) == 0xFFFFFFFF) {
439
-      /* Set variable data */
440
-      HAL_StatusTypeDef FlashStatus = HAL_FLASH_Program(TYPEPROGRAM_HALFWORD, Address, Data);
441
-      /* If program operation was failed, a Flash error code is returned */
442
-      if (FlashStatus != HAL_OK) return FlashStatus;
443
-      /* Set variable virtual address, return status */
444
-      return HAL_FLASH_Program(TYPEPROGRAM_HALFWORD, Address + 2, VirtAddress);
445
-    }
446
-    else /* Next address location */
447
-      Address += 4;
448
-  }
449
-
450
-  /* Return PAGE_FULL in case the valid page is full */
451
-  return PAGE_FULL;
452
-}
453
-
454
-/**
455
- * @brief  Transfers last updated variables data from the full Page to
456
- *   an empty one.
457
- * @param  VirtAddress: 16 bit virtual address of the variable
458
- * @param  Data: 16 bit data to be written as variable value
459
- * @retval Success or error status:
460
- *           - FLASH_COMPLETE: on success
461
- *           - PAGE_FULL: if valid page is full
462
- *           - NO_VALID_PAGE: if no valid page was found
463
- *           - Flash error code: on write Flash error
464
- */
465
-static uint16_t EE_PageTransfer(uint16_t VirtAddress, uint16_t Data) {
466
-  /* Get active Page for read operation */
467
-  uint16_t ValidPage = EE_FindValidPage(READ_FROM_VALID_PAGE);
468
-  uint32_t NewPageAddress = EEPROM_START_ADDRESS;
469
-  uint16_t OldPageId = 0;
470
-
471
-  if (ValidPage == PAGE1) {     /* Page1 valid */
472
-    /* New page address where variable will be moved to */
473
-    NewPageAddress = PAGE0_BASE_ADDRESS;
474
-    /* Old page ID where variable will be taken from */
475
-    OldPageId = PAGE1_ID;
476
-  }
477
-  else if (ValidPage == PAGE0) { /* Page0 valid */
478
-    /* New page address  where variable will be moved to */
479
-    NewPageAddress = PAGE1_BASE_ADDRESS;
480
-    /* Old page ID where variable will be taken from */
481
-    OldPageId = PAGE0_ID;
482
-  }
483
-  else
484
-    return NO_VALID_PAGE;       /* No valid Page */
485
-
486
-  /* Set the new Page status to RECEIVE_DATA status */
487
-  HAL_StatusTypeDef FlashStatus = HAL_FLASH_Program(TYPEPROGRAM_HALFWORD, NewPageAddress, RECEIVE_DATA);
488
-  /* If program operation was failed, a Flash error code is returned */
489
-  if (FlashStatus != HAL_OK) return FlashStatus;
490
-
491
-  /* Write the variable passed as parameter in the new active page */
492
-  uint16_t EepromStatus = EE_VerifyPageFullWriteVariable(VirtAddress, Data);
493
-  /* If program operation was failed, a Flash error code is returned */
494
-  if (EepromStatus != HAL_OK) return EepromStatus;
495
-
496
-  /* Transfer process: transfer variables from old to the new active page */
497
-  for (uint16_t VarIdx = 0; VarIdx < NB_OF_VAR; VarIdx++) {
498
-    if (VirtAddVarTab[VarIdx] != VirtAddress) { /* Check each variable except the one passed as parameter */
499
-      /* Read the other last variable updates */
500
-      uint16_t ReadStatus = EE_ReadVariable(VirtAddVarTab[VarIdx], &DataVar);
501
-      /* In case variable corresponding to the virtual address was found */
502
-      if (ReadStatus != 0x1) {
503
-        /* Transfer the variable to the new active page */
504
-        EepromStatus = EE_VerifyPageFullWriteVariable(VirtAddVarTab[VarIdx], DataVar);
505
-        /* If program operation was failed, a Flash error code is returned */
506
-        if (EepromStatus != HAL_OK) return EepromStatus;
507
-      }
508
-    }
509
-  }
510
-
511
-  FLASH_EraseInitTypeDef pEraseInit;
512
-  pEraseInit.TypeErase = TYPEERASE_SECTORS;
513
-  pEraseInit.Sector = OldPageId;
514
-  pEraseInit.NbSectors = 1;
515
-  pEraseInit.VoltageRange = VOLTAGE_RANGE;
516
-
517
-  /* Erase the old Page: Set old Page status to ERASED status */
518
-  uint32_t SectorError;
519
-  FlashStatus = HAL_FLASHEx_Erase(&pEraseInit, &SectorError);
520
-  /* If erase operation was failed, a Flash error code is returned */
521
-  if (FlashStatus != HAL_OK) return FlashStatus;
522
-
523
-  /* Set new Page status to VALID_PAGE status */
524
-  /* As the last operation, just return the result code */
525
-  return HAL_FLASH_Program(TYPEPROGRAM_HALFWORD, NewPageAddress, VALID_PAGE);
526
-}
527
-
528
-#endif // FLASH_EEPROM_EMULATION
529
-#endif // STM32GENERIC && (STM32F4 || STM32F7)
530
-
531
-/**
532
- * @}
533
- */
534
-
535
-/******************* (C) COPYRIGHT 2011 STMicroelectronics *****END OF FILE****/

+ 0
- 114
Marlin/src/HAL/STM32_F4_F7/eeprom_emul.h Näytä tiedosto

@@ -1,114 +0,0 @@
1
-/******************************************************************************
2
- * @file    eeprom_emul.h
3
- * @author  MCD Application Team
4
- * @version V1.2.6
5
- * @date    04-November-2016
6
- * @brief   This file contains all the functions prototypes for the EEPROM
7
- *          emulation firmware library.
8
- ******************************************************************************
9
- * @attention
10
- *
11
- * Copyright © 2016 STMicroelectronics International N.V.
12
- * All rights reserved.</center></h2>
13
- *
14
- * Redistribution and use in source and binary forms, with or without
15
- * modification, are permitted, provided that the following conditions are met:
16
- *
17
- * 1. Redistribution of source code must retain the above copyright notice,
18
- *    this list of conditions and the following disclaimer.
19
- * 2. Redistributions in binary form must reproduce the above copyright notice,
20
- *    this list of conditions and the following disclaimer in the documentation
21
- *    and/or other materials provided with the distribution.
22
- * 3. Neither the name of STMicroelectronics nor the names of other
23
- *    contributors to this software may be used to endorse or promote products
24
- *    derived from this software without specific written permission.
25
- * 4. This software, including modifications and/or derivative works of this
26
- *    software, must execute solely and exclusively on microcontroller or
27
- *    microprocessor devices manufactured by or for STMicroelectronics.
28
- * 5. Redistribution and use of this software other than as permitted under
29
- *    this license is void and will automatically terminate your rights under
30
- *    this license.
31
- *
32
- * THIS SOFTWARE IS PROVIDED BY STMICROELECTRONICS AND CONTRIBUTORS "AS IS"
33
- * AND ANY EXPRESS, IMPLIED OR STATUTORY WARRANTIES, INCLUDING, BUT NOT
34
- * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY, FITNESS FOR A
35
- * PARTICULAR PURPOSE AND NON-INFRINGEMENT OF THIRD PARTY INTELLECTUAL PROPERTY
36
- * RIGHTS ARE DISCLAIMED TO THE FULLEST EXTENT PERMITTED BY LAW. IN NO EVENT
37
- * SHALL STMICROELECTRONICS OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
38
- * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT
39
- * LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA,
40
- * OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF
41
- * LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING
42
- * NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE,
43
- * EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
44
- *
45
- ******************************************************************************/
46
-#pragma once
47
-
48
-// ------------------------
49
-// Includes
50
-// ------------------------
51
-
52
-#include "../../inc/MarlinConfig.h"
53
-
54
-/* Exported constants --------------------------------------------------------*/
55
-/* EEPROM emulation firmware error codes */
56
-#define EE_OK      uint32_t(HAL_OK)
57
-#define EE_ERROR   uint32_t(HAL_ERROR)
58
-#define EE_BUSY    uint32_t(HAL_BUSY)
59
-#define EE_TIMEOUT uint32_t(HAL_TIMEOUT)
60
-
61
-/* Define the size of the sectors to be used */
62
-#define PAGE_SIZE             uint32_t(0x4000)  /* Page size = 16KByte */
63
-
64
-/* Device voltage range supposed to be [2.7V to 3.6V], the operation will
65
-   be done by word  */
66
-#define VOLTAGE_RANGE         uint8_t(VOLTAGE_RANGE_3)
67
-
68
-/* EEPROM start address in Flash */
69
-#ifdef STM32F7
70
-  #define EEPROM_START_ADDRESS  uint32_t(0x08100000) /* EEPROM emulation start address:
71
-                                                        from sector2 : after 16KByte of used
72
-                                                        Flash memory */
73
-#else
74
-  #define EEPROM_START_ADDRESS  uint32_t(0x08078000) /* EEPROM emulation start address:
75
-                                                        after 480KByte of used Flash memory */
76
-#endif
77
-
78
-/* Pages 0 and 1 base and end addresses */
79
-#define PAGE0_BASE_ADDRESS    uint32_t(EEPROM_START_ADDRESS + 0x0000)
80
-#define PAGE0_END_ADDRESS     uint32_t(EEPROM_START_ADDRESS + PAGE_SIZE - 1)
81
-#define PAGE0_ID              FLASH_SECTOR_1
82
-
83
-#define PAGE1_BASE_ADDRESS    uint32_t(EEPROM_START_ADDRESS + 0x4000)
84
-#define PAGE1_END_ADDRESS     uint32_t(EEPROM_START_ADDRESS + 2 * (PAGE_SIZE) - 1)
85
-#define PAGE1_ID              FLASH_SECTOR_2
86
-
87
-/* Used Flash pages for EEPROM emulation */
88
-#define PAGE0                 uint16_t(0x0000)
89
-#define PAGE1                 uint16_t(0x0001) /* Page nb between PAGE0_BASE_ADDRESS & PAGE1_BASE_ADDRESS*/
90
-
91
-/* No valid page define */
92
-#define NO_VALID_PAGE         uint16_t(0x00AB)
93
-
94
-/* Page status definitions */
95
-#define ERASED                uint16_t(0xFFFF)     /* Page is empty */
96
-#define RECEIVE_DATA          uint16_t(0xEEEE)     /* Page is marked to receive data */
97
-#define VALID_PAGE            uint16_t(0x0000)     /* Page containing valid data */
98
-
99
-/* Valid pages in read and write defines */
100
-#define READ_FROM_VALID_PAGE  uint8_t(0x00)
101
-#define WRITE_IN_VALID_PAGE   uint8_t(0x01)
102
-
103
-/* Page full define */
104
-#define PAGE_FULL             uint8_t(0x80)
105
-
106
-/* Variables' number */
107
-#define NB_OF_VAR             uint16_t(4096)
108
-
109
-/* Exported functions ------------------------------------------------------- */
110
-uint16_t EE_Initialize();
111
-uint16_t EE_ReadVariable(uint16_t VirtAddress, uint16_t* Data);
112
-uint16_t EE_WriteVariable(uint16_t VirtAddress, uint16_t Data);
113
-
114
-/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/

+ 0
- 111
Marlin/src/HAL/STM32_F4_F7/eeprom_flash.cpp Näytä tiedosto

@@ -1,111 +0,0 @@
1
-/**
2
- * Marlin 3D Printer Firmware
3
- * Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
4
- *
5
- * This program is free software: you can redistribute it and/or modify
6
- * it under the terms of the GNU General Public License as published by
7
- * the Free Software Foundation, either version 3 of the License, or
8
- * (at your option) any later version.
9
- *
10
- * This program is distributed in the hope that it will be useful,
11
- * but WITHOUT ANY WARRANTY; without even the implied warranty of
12
- * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the
13
- * GNU General Public License for more details.
14
- *
15
- * You should have received a copy of the GNU General Public License
16
- * along with this program.  If not, see <https://www.gnu.org/licenses/>.
17
- *
18
- */
19
-#if defined(STM32GENERIC) && (defined(STM32F4) || defined(STM32F7))
20
-
21
-#include "../../inc/MarlinConfig.h"
22
-
23
-#if ENABLED(FLASH_EEPROM_EMULATION)
24
-
25
-#include "../shared/eeprom_api.h"
26
-#include "eeprom_emul.h"
27
-
28
-// FLASH_FLAG_PGSERR (Programming Sequence Error) was renamed to
29
-// FLASH_FLAG_ERSERR (Erasing Sequence Error) in STM32F4/7
30
-
31
-#ifdef STM32F7
32
-  #define FLASH_FLAG_PGSERR FLASH_FLAG_ERSERR
33
-#else
34
-  //#define FLASH_FLAG_PGSERR FLASH_FLAG_ERSERR
35
-#endif
36
-
37
-void ee_write_byte(uint8_t *pos, unsigned char value) {
38
-  HAL_FLASH_Unlock();
39
-  __HAL_FLASH_CLEAR_FLAG(FLASH_FLAG_EOP | FLASH_FLAG_OPERR | FLASH_FLAG_WRPERR |FLASH_FLAG_PGAERR | FLASH_FLAG_PGPERR | FLASH_FLAG_PGSERR);
40
-
41
-  const unsigned eeprom_address = (unsigned)pos;
42
-  if (EE_WriteVariable(eeprom_address, uint16_t(value)) != EE_OK)
43
-    for (;;) HAL_Delay(1); // Spin forever until watchdog reset
44
-
45
-  HAL_FLASH_Lock();
46
-}
47
-
48
-uint8_t ee_read_byte(uint8_t *pos) {
49
-  uint16_t data = 0xFF;
50
-  const unsigned eeprom_address = (unsigned)pos;
51
-  (void)EE_ReadVariable(eeprom_address, &data); // Data unchanged on error
52
-  return uint8_t(data);
53
-}
54
-
55
-#ifndef MARLIN_EEPROM_SIZE
56
-  #error "MARLIN_EEPROM_SIZE is required for Flash-based EEPROM."
57
-#endif
58
-size_t PersistentStore::capacity() { return MARLIN_EEPROM_SIZE; }
59
-
60
-bool PersistentStore::access_finish() { return true; }
61
-
62
-bool PersistentStore::access_start() {
63
-  static bool ee_initialized = false;
64
-  if (!ee_initialized) {
65
-    HAL_FLASH_Unlock();
66
-
67
-    __HAL_FLASH_CLEAR_FLAG(FLASH_FLAG_EOP | FLASH_FLAG_OPERR | FLASH_FLAG_WRPERR |FLASH_FLAG_PGAERR | FLASH_FLAG_PGPERR | FLASH_FLAG_PGSERR);
68
-
69
-    /* EEPROM Init */
70
-    if (EE_Initialize() != EE_OK)
71
-      for (;;) HAL_Delay(1); // Spin forever until watchdog reset
72
-
73
-    HAL_FLASH_Lock();
74
-    ee_initialized = true;
75
-  }
76
-  return true;
77
-}
78
-
79
-bool PersistentStore::write_data(int &pos, const uint8_t *value, size_t size, uint16_t *crc) {
80
-  while (size--) {
81
-    uint8_t * const p = (uint8_t * const)pos;
82
-    uint8_t v = *value;
83
-    // EEPROM has only ~100,000 write cycles,
84
-    // so only write bytes that have changed!
85
-    if (v != ee_read_byte(p)) {
86
-      ee_write_byte(p, v);
87
-      if (ee_read_byte(p) != v) {
88
-        SERIAL_ECHO_MSG(STR_ERR_EEPROM_WRITE);
89
-        return true;
90
-      }
91
-    }
92
-    crc16(crc, &v, 1);
93
-    pos++;
94
-    value++;
95
-  }
96
-  return false;
97
-}
98
-
99
-bool PersistentStore::read_data(int &pos, uint8_t *value, size_t size, uint16_t *crc, const bool writing/*=true*/) {
100
-  do {
101
-    uint8_t c = ee_read_byte((uint8_t*)pos);
102
-    if (writing) *value = c;
103
-    crc16(crc, &c, 1);
104
-    pos++;
105
-    value++;
106
-  } while (--size);
107
-  return false;
108
-}
109
-
110
-#endif // FLASH_EEPROM_EMULATION
111
-#endif // STM32GENERIC && (STM32F4 || STM32F7)

+ 0
- 77
Marlin/src/HAL/STM32_F4_F7/eeprom_wired.cpp Näytä tiedosto

@@ -1,77 +0,0 @@
1
-/**
2
- * Marlin 3D Printer Firmware
3
- *
4
- * Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
5
- * Copyright (c) 2016 Bob Cousins bobcousins42@googlemail.com
6
- * Copyright (c) 2015-2016 Nico Tonnhofer wurstnase.reprap@gmail.com
7
- * Copyright (c) 2016 Victor Perez victor_pv@hotmail.com
8
- *
9
- * This program is free software: you can redistribute it and/or modify
10
- * it under the terms of the GNU General Public License as published by
11
- * the Free Software Foundation, either version 3 of the License, or
12
- * (at your option) any later version.
13
- *
14
- * This program is distributed in the hope that it will be useful,
15
- * but WITHOUT ANY WARRANTY; without even the implied warranty of
16
- * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the
17
- * GNU General Public License for more details.
18
- *
19
- * You should have received a copy of the GNU General Public License
20
- * along with this program.  If not, see <https://www.gnu.org/licenses/>.
21
- *
22
- */
23
-#if defined(STM32GENERIC) && (defined(STM32F4) || defined(STM32F7))
24
-
25
-#include "../../inc/MarlinConfig.h"
26
-
27
-#if USE_WIRED_EEPROM
28
-
29
-/**
30
- * PersistentStore for Arduino-style EEPROM interface
31
- * with simple implementations supplied by Marlin.
32
- */
33
-
34
-#include "../shared/eeprom_if.h"
35
-#include "../shared/eeprom_api.h"
36
-
37
-#ifndef MARLIN_EEPROM_SIZE
38
-  #error "MARLIN_EEPROM_SIZE is required for I2C / SPI EEPROM."
39
-#endif
40
-size_t PersistentStore::capacity() { return MARLIN_EEPROM_SIZE; }
41
-
42
-bool PersistentStore::access_start()  { eeprom_init(); return true; }
43
-bool PersistentStore::access_finish() { return true; }
44
-
45
-bool PersistentStore::write_data(int &pos, const uint8_t *value, size_t size, uint16_t *crc) {
46
-  while (size--) {
47
-    uint8_t * const p = (uint8_t * const)pos;
48
-    uint8_t v = *value;
49
-    // EEPROM has only ~100,000 write cycles,
50
-    // so only write bytes that have changed!
51
-    if (v != eeprom_read_byte(p)) {
52
-      eeprom_write_byte(p, v);
53
-      if (eeprom_read_byte(p) != v) {
54
-        SERIAL_ECHO_MSG(STR_ERR_EEPROM_WRITE);
55
-        return true;
56
-      }
57
-    }
58
-    crc16(crc, &v, 1);
59
-    pos++;
60
-    value++;
61
-  }
62
-  return false;
63
-}
64
-
65
-bool PersistentStore::read_data(int &pos, uint8_t *value, size_t size, uint16_t *crc, const bool writing/*=true*/) {
66
-  do {
67
-    uint8_t c = eeprom_read_byte((uint8_t*)pos);
68
-    if (writing) *value = c;
69
-    crc16(crc, &c, 1);
70
-    pos++;
71
-    value++;
72
-  } while (--size);
73
-  return false;
74
-}
75
-
76
-#endif // USE_WIRED_EEPROM
77
-#endif // STM32GENERIC && (STM32F4 || STM32F7)

+ 0
- 49
Marlin/src/HAL/STM32_F4_F7/endstop_interrupts.h Näytä tiedosto

@@ -1,49 +0,0 @@
1
-/**
2
- * Marlin 3D Printer Firmware
3
- * Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
4
- *
5
- * Based on Sprinter and grbl.
6
- * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm
7
- * Copyright (c) 2017 Victor Perez
8
- *
9
- * This program is free software: you can redistribute it and/or modify
10
- * it under the terms of the GNU General Public License as published by
11
- * the Free Software Foundation, either version 3 of the License, or
12
- * (at your option) any later version.
13
- *
14
- * This program is distributed in the hope that it will be useful,
15
- * but WITHOUT ANY WARRANTY; without even the implied warranty of
16
- * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the
17
- * GNU General Public License for more details.
18
- *
19
- * You should have received a copy of the GNU General Public License
20
- * along with this program.  If not, see <https://www.gnu.org/licenses/>.
21
- *
22
- */
23
-#pragma once
24
-
25
-#include "../../module/endstops.h"
26
-
27
-// One ISR for all EXT-Interrupts
28
-void endstop_ISR() { endstops.update(); }
29
-
30
-void setup_endstop_interrupts() {
31
-  #define _ATTACH(P) attachInterrupt(P, endstop_ISR, CHANGE)
32
-  TERN_(HAS_X_MAX, _ATTACH(X_MAX_PIN));
33
-  TERN_(HAS_X_MIN, _ATTACH(X_MIN_PIN));
34
-  TERN_(HAS_Y_MAX, _ATTACH(Y_MAX_PIN));
35
-  TERN_(HAS_Y_MIN, _ATTACH(Y_MIN_PIN));
36
-  TERN_(HAS_Z_MAX, _ATTACH(Z_MAX_PIN));
37
-  TERN_(HAS_Z_MIN, _ATTACH(Z_MIN_PIN));
38
-  TERN_(HAS_X2_MAX, _ATTACH(X2_MAX_PIN));
39
-  TERN_(HAS_X2_MIN, _ATTACH(X2_MIN_PIN));
40
-  TERN_(HAS_Y2_MAX, _ATTACH(Y2_MAX_PIN));
41
-  TERN_(HAS_Y2_MIN, _ATTACH(Y2_MIN_PIN));
42
-  TERN_(HAS_Z2_MAX, _ATTACH(Z2_MAX_PIN));
43
-  TERN_(HAS_Z2_MIN, _ATTACH(Z2_MIN_PIN));
44
-  TERN_(HAS_Z3_MAX, _ATTACH(Z3_MAX_PIN));
45
-  TERN_(HAS_Z3_MIN, _ATTACH(Z3_MIN_PIN));
46
-  TERN_(HAS_Z4_MAX, _ATTACH(Z4_MAX_PIN));
47
-  TERN_(HAS_Z4_MIN, _ATTACH(Z4_MIN_PIN));
48
-  TERN_(HAS_Z_MIN_PROBE_PIN, _ATTACH(Z_MIN_PROBE_PIN));
49
-}

+ 0
- 310
Marlin/src/HAL/STM32_F4_F7/fastio.h Näytä tiedosto

@@ -1,310 +0,0 @@
1
-/**
2
- * Marlin 3D Printer Firmware
3
- * Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
4
- *
5
- * Based on Sprinter and grbl.
6
- * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm
7
- * Copyright (c) 2017 Victor Perez
8
- *
9
- * This program is free software: you can redistribute it and/or modify
10
- * it under the terms of the GNU General Public License as published by
11
- * the Free Software Foundation, either version 3 of the License, or
12
- * (at your option) any later version.
13
- *
14
- * This program is distributed in the hope that it will be useful,
15
- * but WITHOUT ANY WARRANTY; without even the implied warranty of
16
- * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the
17
- * GNU General Public License for more details.
18
- *
19
- * You should have received a copy of the GNU General Public License
20
- * along with this program.  If not, see <https://www.gnu.org/licenses/>.
21
- *
22
- */
23
-#pragma once
24
-
25
-/**
26
- * Fast I/O interfaces for STM32F4/7
27
- * These use GPIO functions instead of Direct Port Manipulation, as on AVR.
28
- */
29
-
30
-#ifndef PWM
31
-  #define PWM OUTPUT
32
-#endif
33
-
34
-#define READ(IO)                digitalRead(IO)
35
-#define WRITE(IO,V)             digitalWrite(IO,V)
36
-
37
-#define _GET_MODE(IO)
38
-#define _SET_MODE(IO,M)         pinMode(IO, M)
39
-#define _SET_OUTPUT(IO)         pinMode(IO, OUTPUT)                               /*!< Output Push Pull Mode & GPIO_NOPULL   */
40
-
41
-#define OUT_WRITE(IO,V)         do{ _SET_OUTPUT(IO); WRITE(IO,V); }while(0)
42
-
43
-#define SET_INPUT(IO)           _SET_MODE(IO, INPUT)                              /*!< Input Floating Mode                   */
44
-#define SET_INPUT_PULLUP(IO)    _SET_MODE(IO, INPUT_PULLUP)                       /*!< Input with Pull-up activation         */
45
-#define SET_INPUT_PULLDOWN(IO)  _SET_MODE(IO, INPUT_PULLDOWN)                     /*!< Input with Pull-down activation       */
46
-#define SET_OUTPUT(IO)          OUT_WRITE(IO, LOW)
47
-#define SET_PWM(IO)             _SET_MODE(IO, PWM)
48
-
49
-#define TOGGLE(IO)              OUT_WRITE(IO, !READ(IO))
50
-
51
-#define IS_INPUT(IO)
52
-#define IS_OUTPUT(IO)
53
-
54
-#define PWM_PIN(P)              true
55
-
56
-// digitalRead/Write wrappers
57
-#define extDigitalRead(IO)    digitalRead(IO)
58
-#define extDigitalWrite(IO,V) digitalWrite(IO,V)
59
-
60
-//
61
-// Pins Definitions
62
-//
63
-#define PORTA 0
64
-#define PORTB 1
65
-#define PORTC 2
66
-#define PORTD 3
67
-#define PORTE 4
68
-#define PORTF 5
69
-#define PORTG 6
70
-
71
-#define _STM32_PIN(P,PN) ((PORT##P * 16) + PN)
72
-
73
-#undef PA0
74
-#define PA0  _STM32_PIN(A,  0)
75
-#undef PA1
76
-#define PA1  _STM32_PIN(A,  1)
77
-#undef PA2
78
-#define PA2  _STM32_PIN(A,  2)
79
-#undef PA3
80
-#define PA3  _STM32_PIN(A,  3)
81
-#undef PA4
82
-#define PA4  _STM32_PIN(A,  4)
83
-#undef PA5
84
-#define PA5  _STM32_PIN(A,  5)
85
-#undef PA6
86
-#define PA6  _STM32_PIN(A,  6)
87
-#undef PA7
88
-#define PA7  _STM32_PIN(A,  7)
89
-#undef PA8
90
-#define PA8  _STM32_PIN(A,  8)
91
-#undef PA9
92
-#define PA9  _STM32_PIN(A,  9)
93
-#undef PA10
94
-#define PA10 _STM32_PIN(A, 10)
95
-#undef PA11
96
-#define PA11 _STM32_PIN(A, 11)
97
-#undef PA12
98
-#define PA12 _STM32_PIN(A, 12)
99
-#undef PA13
100
-#define PA13 _STM32_PIN(A, 13)
101
-#undef PA14
102
-#define PA14 _STM32_PIN(A, 14)
103
-#undef PA15
104
-#define PA15 _STM32_PIN(A, 15)
105
-
106
-#undef PB0
107
-#define PB0  _STM32_PIN(B,  0)
108
-#undef PB1
109
-#define PB1  _STM32_PIN(B,  1)
110
-#undef PB2
111
-#define PB2  _STM32_PIN(B,  2)
112
-#undef PB3
113
-#define PB3  _STM32_PIN(B,  3)
114
-#undef PB4
115
-#define PB4  _STM32_PIN(B,  4)
116
-#undef PB5
117
-#define PB5  _STM32_PIN(B,  5)
118
-#undef PB6
119
-#define PB6  _STM32_PIN(B,  6)
120
-#undef PB7
121
-#define PB7  _STM32_PIN(B,  7)
122
-#undef PB8
123
-#define PB8  _STM32_PIN(B,  8)
124
-#undef PB9
125
-#define PB9  _STM32_PIN(B,  9)
126
-#undef PB10
127
-#define PB10 _STM32_PIN(B, 10)
128
-#undef PB11
129
-#define PB11 _STM32_PIN(B, 11)
130
-#undef PB12
131
-#define PB12 _STM32_PIN(B, 12)
132
-#undef PB13
133
-#define PB13 _STM32_PIN(B, 13)
134
-#undef PB14
135
-#define PB14 _STM32_PIN(B, 14)
136
-#undef PB15
137
-#define PB15 _STM32_PIN(B, 15)
138
-
139
-#undef PC0
140
-#define PC0  _STM32_PIN(C,  0)
141
-#undef PC1
142
-#define PC1  _STM32_PIN(C,  1)
143
-#undef PC2
144
-#define PC2  _STM32_PIN(C,  2)
145
-#undef PC3
146
-#define PC3  _STM32_PIN(C,  3)
147
-#undef PC4
148
-#define PC4  _STM32_PIN(C,  4)
149
-#undef PC5
150
-#define PC5  _STM32_PIN(C,  5)
151
-#undef PC6
152
-#define PC6  _STM32_PIN(C,  6)
153
-#undef PC7
154
-#define PC7  _STM32_PIN(C,  7)
155
-#undef PC8
156
-#define PC8  _STM32_PIN(C,  8)
157
-#undef PC9
158
-#define PC9  _STM32_PIN(C,  9)
159
-#undef PC10
160
-#define PC10 _STM32_PIN(C, 10)
161
-#undef PC11
162
-#define PC11 _STM32_PIN(C, 11)
163
-#undef PC12
164
-#define PC12 _STM32_PIN(C, 12)
165
-#undef PC13
166
-#define PC13 _STM32_PIN(C, 13)
167
-#undef PC14
168
-#define PC14 _STM32_PIN(C, 14)
169
-#undef PC15
170
-#define PC15 _STM32_PIN(C, 15)
171
-
172
-#undef PD0
173
-#define PD0  _STM32_PIN(D,  0)
174
-#undef PD1
175
-#define PD1  _STM32_PIN(D,  1)
176
-#undef PD2
177
-#define PD2  _STM32_PIN(D,  2)
178
-#undef PD3
179
-#define PD3  _STM32_PIN(D,  3)
180
-#undef PD4
181
-#define PD4  _STM32_PIN(D,  4)
182
-#undef PD5
183
-#define PD5  _STM32_PIN(D,  5)
184
-#undef PD6
185
-#define PD6  _STM32_PIN(D,  6)
186
-#undef PD7
187
-#define PD7  _STM32_PIN(D,  7)
188
-#undef PD8
189
-#define PD8  _STM32_PIN(D,  8)
190
-#undef PD9
191
-#define PD9  _STM32_PIN(D,  9)
192
-#undef PD10
193
-#define PD10 _STM32_PIN(D, 10)
194
-#undef PD11
195
-#define PD11 _STM32_PIN(D, 11)
196
-#undef PD12
197
-#define PD12 _STM32_PIN(D, 12)
198
-#undef PD13
199
-#define PD13 _STM32_PIN(D, 13)
200
-#undef PD14
201
-#define PD14 _STM32_PIN(D, 14)
202
-#undef PD15
203
-#define PD15 _STM32_PIN(D, 15)
204
-
205
-#undef PE0
206
-#define PE0  _STM32_PIN(E,  0)
207
-#undef PE1
208
-#define PE1  _STM32_PIN(E,  1)
209
-#undef PE2
210
-#define PE2  _STM32_PIN(E,  2)
211
-#undef PE3
212
-#define PE3  _STM32_PIN(E,  3)
213
-#undef PE4
214
-#define PE4  _STM32_PIN(E,  4)
215
-#undef PE5
216
-#define PE5  _STM32_PIN(E,  5)
217
-#undef PE6
218
-#define PE6  _STM32_PIN(E,  6)
219
-#undef PE7
220
-#define PE7  _STM32_PIN(E,  7)
221
-#undef PE8
222
-#define PE8  _STM32_PIN(E,  8)
223
-#undef PE9
224
-#define PE9  _STM32_PIN(E,  9)
225
-#undef PE10
226
-#define PE10 _STM32_PIN(E, 10)
227
-#undef PE11
228
-#define PE11 _STM32_PIN(E, 11)
229
-#undef PE12
230
-#define PE12 _STM32_PIN(E, 12)
231
-#undef PE13
232
-#define PE13 _STM32_PIN(E, 13)
233
-#undef PE14
234
-#define PE14 _STM32_PIN(E, 14)
235
-#undef PE15
236
-#define PE15 _STM32_PIN(E, 15)
237
-
238
-#ifdef STM32F7
239
-
240
-  #undef PORTF
241
-  #define PORTF 5
242
-  #undef PF0
243
-  #define PF0  _STM32_PIN(F,  0)
244
-  #undef PF1
245
-  #define PF1  _STM32_PIN(F,  1)
246
-  #undef PF2
247
-  #define PF2  _STM32_PIN(F,  2)
248
-  #undef PF3
249
-  #define PF3  _STM32_PIN(F,  3)
250
-  #undef PF4
251
-  #define PF4  _STM32_PIN(F,  4)
252
-  #undef PF5
253
-  #define PF5  _STM32_PIN(F,  5)
254
-  #undef PF6
255
-  #define PF6  _STM32_PIN(F,  6)
256
-  #undef PF7
257
-  #define PF7  _STM32_PIN(F,  7)
258
-  #undef PF8
259
-  #define PF8  _STM32_PIN(F,  8)
260
-  #undef PF9
261
-  #define PF9  _STM32_PIN(F,  9)
262
-  #undef PF10
263
-  #define PF10 _STM32_PIN(F, 10)
264
-  #undef PF11
265
-  #define PF11 _STM32_PIN(F, 11)
266
-  #undef PF12
267
-  #define PF12 _STM32_PIN(F, 12)
268
-  #undef PF13
269
-  #define PF13 _STM32_PIN(F, 13)
270
-  #undef PF14
271
-  #define PF14 _STM32_PIN(F, 14)
272
-  #undef PF15
273
-  #define PF15 _STM32_PIN(F, 15)
274
-
275
-  #undef PORTG
276
-  #define PORTG 6
277
-  #undef PG0
278
-  #define PG0  _STM32_PIN(G,  0)
279
-  #undef PG1
280
-  #define PG1  _STM32_PIN(G,  1)
281
-  #undef PG2
282
-  #define PG2  _STM32_PIN(G,  2)
283
-  #undef PG3
284
-  #define PG3  _STM32_PIN(G,  3)
285
-  #undef PG4
286
-  #define PG4  _STM32_PIN(G,  4)
287
-  #undef PG5
288
-  #define PG5  _STM32_PIN(G,  5)
289
-  #undef PG6
290
-  #define PG6  _STM32_PIN(G,  6)
291
-  #undef PG7
292
-  #define PG7  _STM32_PIN(G,  7)
293
-  #undef PG8
294
-  #define PG8  _STM32_PIN(G,  8)
295
-  #undef PG9
296
-  #define PG9  _STM32_PIN(G,  9)
297
-  #undef PG10
298
-  #define PG10 _STM32_PIN(G, 10)
299
-  #undef PG11
300
-  #define PG11 _STM32_PIN(G, 11)
301
-  #undef PG12
302
-  #define PG12 _STM32_PIN(G, 12)
303
-  #undef PG13
304
-  #define PG13 _STM32_PIN(G, 13)
305
-  #undef PG14
306
-  #define PG14 _STM32_PIN(G, 14)
307
-  #undef PG15
308
-  #define PG15 _STM32_PIN(G, 15)
309
-
310
-#endif // STM32GENERIC && STM32F7

+ 0
- 26
Marlin/src/HAL/STM32_F4_F7/inc/Conditionals_LCD.h Näytä tiedosto

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

+ 0
- 22
Marlin/src/HAL/STM32_F4_F7/inc/Conditionals_adv.h Näytä tiedosto

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

+ 0
- 29
Marlin/src/HAL/STM32_F4_F7/inc/Conditionals_post.h Näytä tiedosto

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

+ 0
- 41
Marlin/src/HAL/STM32_F4_F7/inc/SanityCheck.h Näytä tiedosto

@@ -1,41 +0,0 @@
1
-/**
2
- * Marlin 3D Printer Firmware
3
- * Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
4
- *
5
- * Based on Sprinter and grbl.
6
- * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm
7
- *
8
- * This program is free software: you can redistribute it and/or modify
9
- * it under the terms of the GNU General Public License as published by
10
- * the Free Software Foundation, either version 3 of the License, or
11
- * (at your option) any later version.
12
- *
13
- * This program is distributed in the hope that it will be useful,
14
- * but WITHOUT ANY WARRANTY; without even the implied warranty of
15
- * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the
16
- * GNU General Public License for more details.
17
- *
18
- * You should have received a copy of the GNU General Public License
19
- * along with this program.  If not, see <https://www.gnu.org/licenses/>.
20
- *
21
- */
22
-#pragma once
23
-
24
-/**
25
- * Test STM32F4/7-specific configuration values for errors at compile-time.
26
- */
27
-//#if ENABLED(SPINDLE_LASER_PWM) && !(SPINDLE_LASER_PWM_PIN == 4 || SPINDLE_LASER_PWM_PIN == 6 || SPINDLE_LASER_PWM_PIN == 11)
28
-//  #error "SPINDLE_LASER_PWM_PIN must use SERVO0, SERVO1 or SERVO3 connector"
29
-//#endif
30
-
31
-#if ENABLED(EMERGENCY_PARSER)
32
-  #error "EMERGENCY_PARSER is not yet implemented for STM32F4/7. Disable EMERGENCY_PARSER to continue."
33
-#endif
34
-
35
-#if ENABLED(FAST_PWM_FAN) || SPINDLE_LASER_FREQUENCY
36
-  #error "Features requiring Hardware PWM (FAST_PWM_FAN, SPINDLE_LASER_FREQUENCY) are not yet supported on STM32F4/F7."
37
-#endif
38
-
39
-#if HAS_TMC_SW_SERIAL
40
-  #error "TMC220x Software Serial is not supported on this platform."
41
-#endif

+ 0
- 27
Marlin/src/HAL/STM32_F4_F7/pinsDebug.h Näytä tiedosto

@@ -1,27 +0,0 @@
1
-/**
2
- * Marlin 3D Printer Firmware
3
- * Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
4
- *
5
- * This program is free software: you can redistribute it and/or modify
6
- * it under the terms of the GNU General Public License as published by
7
- * the Free Software Foundation, either version 3 of the License, or
8
- * (at your option) any later version.
9
- *
10
- * This program is distributed in the hope that it will be useful,
11
- * but WITHOUT ANY WARRANTY; without even the implied warranty of
12
- * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the
13
- * GNU General Public License for more details.
14
- *
15
- * You should have received a copy of the GNU General Public License
16
- * along with this program.  If not, see <https://www.gnu.org/licenses/>.
17
- *
18
- */
19
-#pragma once
20
-
21
-#ifdef NUM_DIGITAL_PINS             // Only in ST's Arduino core (STM32duino, STM32Core)
22
-  #include "../STM32/pinsDebug_STM32duino.h"
23
-#elif defined(BOARD_NR_GPIO_PINS)   // Only in STM32GENERIC (Maple)
24
-  #include "../STM32/pinsDebug_STM32GENERIC.h"
25
-#else
26
-  #error "M43 Pins Debugging not supported for this board."
27
-#endif

+ 0
- 35
Marlin/src/HAL/STM32_F4_F7/spi_pins.h Näytä tiedosto

@@ -1,35 +0,0 @@
1
-/**
2
- * Marlin 3D Printer Firmware
3
- * Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
4
- *
5
- * This program is free software: you can redistribute it and/or modify
6
- * it under the terms of the GNU General Public License as published by
7
- * the Free Software Foundation, either version 3 of the License, or
8
- * (at your option) any later version.
9
- *
10
- * This program is distributed in the hope that it will be useful,
11
- * but WITHOUT ANY WARRANTY; without even the implied warranty of
12
- * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the
13
- * GNU General Public License for more details.
14
- *
15
- * You should have received a copy of the GNU General Public License
16
- * along with this program.  If not, see <https://www.gnu.org/licenses/>.
17
- *
18
- */
19
-#pragma once
20
-
21
-/**
22
- * Define SPI Pins: SCK, MISO, MOSI, SS
23
- */
24
-#ifndef SCK_PIN
25
-  #define SCK_PIN   PA5
26
-#endif
27
-#ifndef MISO_PIN
28
-  #define MISO_PIN  PA6
29
-#endif
30
-#ifndef MOSI_PIN
31
-  #define MOSI_PIN  PA7
32
-#endif
33
-#ifndef SS_PIN
34
-  #define SS_PIN    PA8
35
-#endif

+ 0
- 28
Marlin/src/HAL/STM32_F4_F7/timers.h Näytä tiedosto

@@ -1,28 +0,0 @@
1
-/**
2
- * Marlin 3D Printer Firmware
3
- *
4
- * Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
5
- * Copyright (c) 2016 Bob Cousins bobcousins42@googlemail.com
6
- * Copyright (c) 2017 Victor Perez
7
- *
8
- * This program is free software: you can redistribute it and/or modify
9
- * it under the terms of the GNU General Public License as published by
10
- * the Free Software Foundation, either version 3 of the License, or
11
- * (at your option) any later version.
12
- *
13
- * This program is distributed in the hope that it will be useful,
14
- * but WITHOUT ANY WARRANTY; without even the implied warranty of
15
- * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the
16
- * GNU General Public License for more details.
17
- *
18
- * You should have received a copy of the GNU General Public License
19
- * along with this program.  If not, see <https://www.gnu.org/licenses/>.
20
- *
21
- */
22
-#pragma once
23
-
24
-#ifdef STM32F4
25
-  #include "STM32F4/timers.h"
26
-#else
27
-  #include "STM32F7/timers.h"
28
-#endif

+ 0
- 57
Marlin/src/HAL/STM32_F4_F7/watchdog.cpp Näytä tiedosto

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

+ 0
- 27
Marlin/src/HAL/STM32_F4_F7/watchdog.h Näytä tiedosto

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

+ 0
- 2
Marlin/src/HAL/platforms.h Näytä tiedosto

@@ -37,8 +37,6 @@
37 37
   #define HAL_PATH(PATH, NAME) XSTR(PATH/LPC1768/NAME)
38 38
 #elif defined(__STM32F1__) || defined(TARGET_STM32F1)
39 39
   #define HAL_PATH(PATH, NAME) XSTR(PATH/STM32F1/NAME)
40
-#elif defined(STM32GENERIC) && (defined(STM32F4) || defined(STM32F7))
41
-  #define HAL_PATH(PATH, NAME) XSTR(PATH/STM32_F4_F7/NAME)
42 40
 #elif defined(ARDUINO_ARCH_STM32)
43 41
   #define HAL_PATH(PATH, NAME) XSTR(PATH/STM32/NAME)
44 42
 #elif defined(ARDUINO_ARCH_ESP32)

+ 0
- 11
Marlin/src/HAL/shared/backtrace/unwmemaccess.cpp Näytä tiedosto

@@ -74,17 +74,6 @@
74 74
   #define START_FLASH_ADDR  0x08000000
75 75
   #define END_FLASH_ADDR    0x08080000
76 76
 
77
-#elif MB(THE_BORG)
78
-
79
-  // For STM32F765 in BORG
80
-  //  SRAM  (0x20000000 - 0x20080000) (512kb)
81
-  //  FLASH (0x08000000 - 0x08100000) (1024kb)
82
-  //
83
-  #define START_SRAM_ADDR   0x20000000
84
-  #define END_SRAM_ADDR     0x20080000
85
-  #define START_FLASH_ADDR  0x08000000
86
-  #define END_FLASH_ADDR    0x08100000
87
-
88 77
 #elif MB(REMRAM_V1, NUCLEO_F767ZI)
89 78
 
90 79
   // For STM32F765VI in RemRam v1

+ 0
- 2
Marlin/src/HAL/shared/servo.h Näytä tiedosto

@@ -76,8 +76,6 @@
76 76
   #include "../LPC1768/Servo.h"
77 77
 #elif defined(__STM32F1__) || defined(TARGET_STM32F1)
78 78
   #include "../STM32F1/Servo.h"
79
-#elif defined(STM32GENERIC) && defined(STM32F4)
80
-  #include "../STM32_F4_F7/Servo.h"
81 79
 #elif defined(ARDUINO_ARCH_STM32)
82 80
   #include "../STM32/Servo.h"
83 81
 #elif defined(ARDUINO_ARCH_ESP32)

+ 24
- 26
Marlin/src/core/boards.h Näytä tiedosto

@@ -329,6 +329,7 @@
329 329
 #define BOARD_TRIGORILLA_PRO          4037  // Trigorilla Pro (STM32F103ZET6)
330 330
 #define BOARD_FLY_MINI                4038  // FLY MINI (STM32F103RCT6)
331 331
 #define BOARD_FLSUN_HISPEED           4039  // FLSUN HiSpeedV1 (STM32F103VET6)
332
+#define BOARD_BEAST                   4040  // STM32F103RET6 Libmaple-based controller
332 333
 
333 334
 //
334 335
 // ARM Cortex-M4F
@@ -341,37 +342,34 @@
341 342
 // STM32 ARM Cortex-M4F
342 343
 //
343 344
 
344
-#define BOARD_BEAST                   4200  // STM32F4xxVxT6 Libmaple-based STM32F4 controller
345
-#define BOARD_GENERIC_STM32F4         4201  // STM32 STM32GENERIC-based STM32F4 controller
346
-#define BOARD_ARMED                   4202  // Arm'ed STM32F4-based controller
347
-#define BOARD_RUMBA32_V1_0            4203  // RUMBA32 STM32F446VET6 based controller from Aus3D
348
-#define BOARD_RUMBA32_V1_1            4204  // RUMBA32 STM32F446VET6 based controller from Aus3D
349
-#define BOARD_RUMBA32_MKS             4205  // RUMBA32 STM32F446VET6 based controller from Makerbase
350
-#define BOARD_BLACK_STM32F407VE       4206  // BLACK_STM32F407VE
351
-#define BOARD_BLACK_STM32F407ZE       4207  // BLACK_STM32F407ZE
352
-#define BOARD_STEVAL_3DP001V1         4208  // STEVAL-3DP001V1 3D PRINTER BOARD
353
-#define BOARD_BTT_SKR_PRO_V1_1        4209  // BigTreeTech SKR Pro v1.1 (STM32F407ZG)
354
-#define BOARD_BTT_SKR_PRO_V1_2        4210  // BigTreeTech SKR Pro v1.2 (STM32F407ZG)
355
-#define BOARD_BTT_BTT002_V1_0         4211  // BigTreeTech BTT002 v1.0 (STM32F407VG)
356
-#define BOARD_BTT_GTR_V1_0            4212  // BigTreeTech GTR v1.0 (STM32F407IGT)
357
-#define BOARD_LERDGE_K                4213  // Lerdge K (STM32F407ZG)
358
-#define BOARD_LERDGE_S                4214  // Lerdge S (STM32F407VE)
359
-#define BOARD_LERDGE_X                4215  // Lerdge X (STM32F407VE)
360
-#define BOARD_VAKE403D                4216  // VAkE 403D (STM32F446VET6)
361
-#define BOARD_FYSETC_S6               4217  // FYSETC S6 board
362
-#define BOARD_FYSETC_S6_V2_0          4218  // FYSETC S6 v2.0 board
363
-#define BOARD_FLYF407ZG               4219  // FLYF407ZG board (STM32F407ZG)
364
-#define BOARD_MKS_ROBIN2              4220  // MKS_ROBIN2 (STM32F407ZE)
345
+#define BOARD_ARMED                   4200  // Arm'ed STM32F4-based controller
346
+#define BOARD_RUMBA32_V1_0            4201  // RUMBA32 STM32F446VET6 based controller from Aus3D
347
+#define BOARD_RUMBA32_V1_1            4202  // RUMBA32 STM32F446VET6 based controller from Aus3D
348
+#define BOARD_RUMBA32_MKS             4203  // RUMBA32 STM32F446VET6 based controller from Makerbase
349
+#define BOARD_BLACK_STM32F407VE       4204  // BLACK_STM32F407VE
350
+#define BOARD_BLACK_STM32F407ZE       4205  // BLACK_STM32F407ZE
351
+#define BOARD_STEVAL_3DP001V1         4206  // STEVAL-3DP001V1 3D PRINTER BOARD
352
+#define BOARD_BTT_SKR_PRO_V1_1        4207  // BigTreeTech SKR Pro v1.1 (STM32F407ZG)
353
+#define BOARD_BTT_SKR_PRO_V1_2        4208  // BigTreeTech SKR Pro v1.2 (STM32F407ZG)
354
+#define BOARD_BTT_BTT002_V1_0         4209  // BigTreeTech BTT002 v1.0 (STM32F407VG)
355
+#define BOARD_BTT_GTR_V1_0            4210  // BigTreeTech GTR v1.0 (STM32F407IGT)
356
+#define BOARD_LERDGE_K                4211  // Lerdge K (STM32F407ZG)
357
+#define BOARD_LERDGE_S                4212  // Lerdge S (STM32F407VE)
358
+#define BOARD_LERDGE_X                4213  // Lerdge X (STM32F407VE)
359
+#define BOARD_VAKE403D                4214  // VAkE 403D (STM32F446VET6)
360
+#define BOARD_FYSETC_S6               4215  // FYSETC S6 board
361
+#define BOARD_FYSETC_S6_V2_0          4216  // FYSETC S6 v2.0 board
362
+#define BOARD_FLYF407ZG               4217  // FLYF407ZG board (STM32F407ZG)
363
+#define BOARD_MKS_ROBIN2              4218  // MKS_ROBIN2 (STM32F407ZE)
365 364
 
366 365
 //
367 366
 // ARM Cortex M7
368 367
 //
369 368
 
370
-#define BOARD_THE_BORG                5000  // THE-BORG (Power outputs: Hotend0, Hotend1, Bed, Fan)
371
-#define BOARD_REMRAM_V1               5001  // RemRam v1
372
-#define BOARD_TEENSY41                5002  // Teensy 4.1
373
-#define BOARD_T41U5XBB                5003  // T41U5XBB Teensy 4.1 breakout board
374
-#define BOARD_NUCLEO_F767ZI           5004  // ST NUCLEO-F767ZI Dev Board
369
+#define BOARD_REMRAM_V1               5000  // RemRam v1
370
+#define BOARD_TEENSY41                5001  // Teensy 4.1
371
+#define BOARD_T41U5XBB                5002  // T41U5XBB Teensy 4.1 breakout board
372
+#define BOARD_NUCLEO_F767ZI           5003  // ST NUCLEO-F767ZI Dev Board
375 373
 
376 374
 //
377 375
 // Espressif ESP32 WiFi

+ 1
- 5
Marlin/src/core/macros.h Näytä tiedosto

@@ -61,11 +61,7 @@
61 61
 #define _O3          __attribute__((optimize("O3")))
62 62
 
63 63
 #ifndef UNUSED
64
-  #if defined(ARDUINO_ARCH_STM32) && !defined(STM32GENERIC)
65
-    #define UNUSED(X) (void)X
66
-  #else
67
-    #define UNUSED(x) ((void)(x))
68
-  #endif
64
+  #define UNUSED(x) ((void)(x))
69 65
 #endif
70 66
 
71 67
 // Clock speed factors

+ 1
- 5
Marlin/src/module/stepper/TMC26X.h Näytä tiedosto

@@ -31,11 +31,7 @@
31 31
 // TMC26X drivers have STEP/DIR on normal pins, but ENABLE via SPI
32 32
 
33 33
 #include <SPI.h>
34
-#if defined(STM32GENERIC) && defined(STM32F7)
35
-  #include "../../HAL/STM32_F4_F7/STM32F7/TMC2660.h"
36
-#else
37
-  #include <TMC26XStepper.h>
38
-#endif
34
+#include <TMC26XStepper.h>
39 35
 
40 36
 void tmc26x_init_to_defaults();
41 37
 

+ 7
- 11
Marlin/src/pins/pins.h Näytä tiedosto

@@ -594,6 +594,8 @@
594 594
   #include "stm32f1/pins_FLY_MINI.h"            // STM32F1                                env:FLY_MINI
595 595
 #elif MB(FLSUN_HISPEED)
596 596
   #include "stm32f1/pins_FLSUN_HISPEED.h"       // STM32F1                                env:flsun_hispeed
597
+#elif MB(BEAST)
598
+  #include "stm32f1/pins_BEAST.h"               // STM32F1                                env:STM32F103RE
597 599
 
598 600
 //
599 601
 // ARM Cortex-M4F
@@ -608,10 +610,6 @@
608 610
 // STM32 ARM Cortex-M4F
609 611
 //
610 612
 
611
-#elif MB(BEAST)
612
-  #include "stm32f4/pins_BEAST.h"               // STM32F4                                env:STM32F4
613
-#elif MB(GENERIC_STM32F4)
614
-  #include "stm32f4/pins_GENERIC_STM32F4.h"     // STM32F4                                env:STM32F4
615 613
 #elif MB(ARMED)
616 614
   #include "stm32f4/pins_ARMED.h"               // STM32F4                                env:ARMED
617 615
 #elif MB(RUMBA32_V1_0)
@@ -633,13 +631,13 @@
633 631
 #elif MB(BTT_BTT002_V1_0)
634 632
   #include "stm32f4/pins_BTT_BTT002_V1_0.h"     // STM32F4                                env:BIGTREE_BTT002
635 633
 #elif MB(LERDGE_K)
636
-  #include "stm32f4/pins_LERDGE_K.h"            // STM32F4                                env:STM32F4
634
+  #include "stm32f4/pins_LERDGE_K.h"            // STM32F4                                env:LERDGEK
637 635
 #elif MB(LERDGE_S)
638
-  #include "stm32f4/pins_LERDGE_S.h"            // STM32F4                                env:LERDGE_S
636
+  #include "stm32f4/pins_LERDGE_S.h"            // STM32F4                                env:LERDGES
639 637
 #elif MB(LERDGE_X)
640
-  #include "stm32f4/pins_LERDGE_X.h"            // STM32F4                                env:LERDGE_X
638
+  #include "stm32f4/pins_LERDGE_X.h"            // STM32F4                                env:LERDGEX
641 639
 #elif MB(VAKE403D)
642
-  #include "stm32f4/pins_VAKE403D.h"            // STM32F4                                env:STM32F4
640
+  #include "stm32f4/pins_VAKE403D.h"            // STM32F4
643 641
 #elif MB(FYSETC_S6)
644 642
   #include "stm32f4/pins_FYSETC_S6.h"           // STM32F4                                env:FYSETC_S6
645 643
 #elif MB(FLYF407ZG)
@@ -653,10 +651,8 @@
653 651
 // ARM Cortex M7
654 652
 //
655 653
 
656
-#elif MB(THE_BORG)
657
-  #include "stm32f7/pins_THE_BORG.h"            // STM32F7                                env:STM32F7
658 654
 #elif MB(REMRAM_V1)
659
-  #include "stm32f7/pins_REMRAM_V1.h"           // STM32F7                                env:STM32F7
655
+  #include "stm32f7/pins_REMRAM_V1.h"           // STM32F7                                env:REMRAM_V1
660 656
 #elif MB(NUCLEO_F767ZI)
661 657
   #include "stm32f7/pins_NUCLEO_F767ZI.h"       // STM32F7                                env:NUCLEO_F767ZI
662 658
 #elif MB(TEENSY41)

Marlin/src/pins/stm32f4/pins_BEAST.h → Marlin/src/pins/stm32f1/pins_BEAST.h Näytä tiedosto

@@ -21,8 +21,8 @@
21 21
  */
22 22
 #pragma once
23 23
 
24
-#if NOT_TARGET(__STM32F1__, __STM32F4__)
25
-  #error "Oops! Select an STM32F1/4 board in 'Tools > Board.'"
24
+#if NOT_TARGET(__STM32F1__)
25
+  #error "Oops! Select an STM32F1 board in 'Tools > Board.'"
26 26
 #endif
27 27
 
28 28
 /**

+ 0
- 197
Marlin/src/pins/stm32f4/pins_GENERIC_STM32F4.h Näytä tiedosto

@@ -1,197 +0,0 @@
1
-/**
2
- * Marlin 3D Printer Firmware
3
- * Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
4
- *
5
- * Based on Sprinter and grbl.
6
- * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm
7
- *
8
- * This program is free software: you can redistribute it and/or modify
9
- * it under the terms of the GNU General Public License as published by
10
- * the Free Software Foundation, either version 3 of the License, or
11
- * (at your option) any later version.
12
- *
13
- * This program is distributed in the hope that it will be useful,
14
- * but WITHOUT ANY WARRANTY; without even the implied warranty of
15
- * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the
16
- * GNU General Public License for more details.
17
- *
18
- * You should have received a copy of the GNU General Public License
19
- * along with this program.  If not, see <https://www.gnu.org/licenses/>.
20
- *
21
- */
22
-#pragma once
23
-
24
-/**
25
- * To build with Arduino IDE use "Discovery F407VG"
26
- * To build with PlatformIO use environment "STM32F4"
27
- */
28
-#if NOT_TARGET(STM32F4, STM32F4xx)
29
-  #error "Oops! Select an STM32F4 board in 'Tools > Board.'"
30
-#elif HOTENDS > 2 || E_STEPPERS > 2
31
-  #error "STM32F4 supports up to 2 hotends / E-steppers."
32
-#endif
33
-
34
-#define BOARD_INFO_NAME      "Misc. STM32F4"
35
-#define DEFAULT_MACHINE_NAME "STM32F407VET6"
36
-
37
-//#define I2C_EEPROM
38
-
39
-#ifndef MARLIN_EEPROM_SIZE
40
-  #define MARLIN_EEPROM_SIZE              0x1000  // 4KB
41
-#endif
42
-
43
-// Ignore temp readings during development.
44
-//#define BOGUS_TEMPERATURE_GRACE_PERIOD    2000
45
-
46
-//
47
-// Limit Switches
48
-//
49
-#define X_MIN_PIN                           PE0
50
-#define X_MAX_PIN                           -1
51
-#define Y_MIN_PIN                           PE1
52
-#define Y_MAX_PIN                           -1
53
-#define Z_MIN_PIN                           PE14
54
-#define Z_MAX_PIN                           -1
55
-
56
-//
57
-// Z Probe (when not Z_MIN_PIN)
58
-//
59
-
60
-//#ifndef Z_MIN_PROBE_PIN
61
-//  #define Z_MIN_PROBE_PIN  PA4
62
-//#endif
63
-
64
-//
65
-// Steppers
66
-//
67
-
68
-#define X_STEP_PIN                          PD3
69
-#define X_DIR_PIN                           PD2
70
-#define X_ENABLE_PIN                        PD0
71
-//#ifndef X_CS_PIN
72
-//  #define X_CS_PIN         PD1
73
-//#endif
74
-
75
-#define Y_STEP_PIN                          PE11
76
-#define Y_DIR_PIN                           PE10
77
-#define Y_ENABLE_PIN                        PE13
78
-//#ifndef Y_CS_PIN
79
-//  #define Y_CS_PIN         PE12
80
-//#endif
81
-
82
-#define Z_STEP_PIN                          PD6
83
-#define Z_DIR_PIN                           PD7
84
-#define Z_ENABLE_PIN                        PD4
85
-//#ifndef Z_CS_PIN
86
-//  #define Z_CS_PIN         PD5
87
-//#endif
88
-
89
-#define E0_STEP_PIN                         PB5
90
-#define E0_DIR_PIN                          PB6
91
-#define E0_ENABLE_PIN                       PB3
92
-//#ifndef E0_CS_PIN
93
-//  #define E0_CS_PIN         PB4
94
-//#endif
95
-
96
-#define E1_STEP_PIN                         PE4
97
-#define E1_DIR_PIN                          PE2
98
-#define E1_ENABLE_PIN                       PE3
99
-//#ifndef E1_CS_PIN
100
-//  #define E1_CS_PIN         PE5
101
-//#endif
102
-
103
-#define SCK_PIN                             PA5
104
-#define MISO_PIN                            PA6
105
-#define MOSI_PIN                            PA7
106
-
107
-//
108
-// Temperature Sensors
109
-//
110
-
111
-#define TEMP_0_PIN                          PC0   // Analog Input
112
-#define TEMP_1_PIN                          PC1   // Analog Input
113
-#define TEMP_BED_PIN                        PC2   // Analog Input
114
-
115
-//
116
-// Heaters / Fans
117
-//
118
-
119
-#define HEATER_0_PIN                        PA1
120
-#define HEATER_1_PIN                        PA2
121
-#define HEATER_BED_PIN                      PA0
122
-
123
-#ifndef FAN_PIN
124
-  #define FAN_PIN                           PC6
125
-#endif
126
-#define FAN1_PIN                            PC7
127
-#define FAN2_PIN                            PC8
128
-
129
-#ifndef E0_AUTO_FAN_PIN
130
-  #define E0_AUTO_FAN_PIN                   PC7
131
-#endif
132
-
133
-//
134
-// Misc. Functions
135
-//
136
-
137
-//#define CASE_LIGHT_PIN_CI                 PF13
138
-//#define CASE_LIGHT_PIN_DO                 PF14
139
-//#define NEOPIXEL_PIN                      PF13
140
-
141
-//
142
-// Průša i3 MK2 Multi Material Multiplexer Support
143
-//
144
-
145
-//#define E_MUX0_PIN                        PG3
146
-//#define E_MUX1_PIN                        PG4
147
-
148
-//
149
-// Servos
150
-//
151
-
152
-//#define SERVO0_PIN                        PE13
153
-//#define SERVO1_PIN                        PE14
154
-
155
-#define SDSS                                PE7
156
-#define SS_PIN                              PE7
157
-#define LED_PIN                             PB7   //Alive
158
-#define PS_ON_PIN                           PA10
159
-#define KILL_PIN                            PA8
160
-#define PWR_LOSS                            PA4   //Power loss / nAC_FAULT
161
-
162
-//
163
-// LCD / Controller
164
-//
165
-
166
-#define SD_DETECT_PIN                       PA15
167
-#define BEEPER_PIN                          PC9
168
-#define LCD_PINS_RS                         PE9
169
-#define LCD_PINS_ENABLE                     PE8
170
-#define LCD_PINS_D4                         PB12
171
-#define LCD_PINS_D5                         PB13
172
-#define LCD_PINS_D6                         PB14
173
-#define LCD_PINS_D7                         PB15
174
-#define BTN_EN1                             PC4
175
-#define BTN_EN2                             PC5
176
-#define BTN_ENC                             PC3
177
-
178
-//
179
-// Filament runout
180
-//
181
-
182
-#define FIL_RUNOUT_PIN                      PA3
183
-
184
-//
185
-// ST7920 Delays
186
-//
187
-#if HAS_MARLINUI_U8GLIB
188
-  #ifndef BOARD_ST7920_DELAY_1
189
-    #define BOARD_ST7920_DELAY_1  DELAY_NS(96)
190
-  #endif
191
-  #ifndef BOARD_ST7920_DELAY_2
192
-    #define BOARD_ST7920_DELAY_2  DELAY_NS(48)
193
-  #endif
194
-  #ifndef BOARD_ST7920_DELAY_3
195
-    #define BOARD_ST7920_DELAY_3 DELAY_NS(715)
196
-  #endif
197
-#endif

+ 0
- 183
Marlin/src/pins/stm32f7/pins_THE_BORG.h Näytä tiedosto

@@ -1,183 +0,0 @@
1
-/**
2
- * Marlin 3D Printer Firmware
3
- * Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
4
- *
5
- * Based on Sprinter and grbl.
6
- * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm
7
- *
8
- * This program is free software: you can redistribute it and/or modify
9
- * it under the terms of the GNU General Public License as published by
10
- * the Free Software Foundation, either version 3 of the License, or
11
- * (at your option) any later version.
12
- *
13
- * This program is distributed in the hope that it will be useful,
14
- * but WITHOUT ANY WARRANTY; without even the implied warranty of
15
- * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the
16
- * GNU General Public License for more details.
17
- *
18
- * You should have received a copy of the GNU General Public License
19
- * along with this program.  If not, see <https://www.gnu.org/licenses/>.
20
- *
21
- */
22
-#pragma once
23
-
24
-#if NOT_TARGET(STM32F7)
25
-  #error "Oops! Select an STM32F7 board in 'Tools > Board.'"
26
-#elif HOTENDS > 3 || E_STEPPERS > 3
27
-  #error "The-Borg supports up to 3 hotends / E-steppers."
28
-#endif
29
-
30
-#define BOARD_INFO_NAME      "The-Borge"
31
-#define DEFAULT_MACHINE_NAME BOARD_INFO_NAME
32
-
33
-#ifndef MARLIN_EEPROM_SIZE
34
-  #define MARLIN_EEPROM_SIZE              0x1000
35
-#endif
36
-
37
-// Ignore temp readings during development.
38
-//#define BOGUS_TEMPERATURE_GRACE_PERIOD    2000
39
-
40
-//
41
-// Limit Switches
42
-//
43
-#define X_MIN_PIN                           PE9
44
-#define X_MAX_PIN                           PE10
45
-#define Y_MIN_PIN                           PE7
46
-#define Y_MAX_PIN                           PE8
47
-#define Z_MIN_PIN                           PF15
48
-#define Z_MAX_PIN                           PG0
49
-#define E_MIN_PIN                           PE2
50
-#define E_MAX_PIN                           PE3
51
-
52
-//
53
-// Z Probe (when not Z_MIN_PIN)
54
-//
55
-#ifndef Z_MIN_PROBE_PIN
56
-  #define Z_MIN_PROBE_PIN                   PA4
57
-#endif
58
-
59
-//
60
-// Steppers
61
-//
62
-#define STEPPER_ENABLE_PIN                  PE0
63
-
64
-#define X_STEP_PIN                          PC6   // 96, 39 in Arduino
65
-#define X_DIR_PIN                           PC7
66
-#define X_ENABLE_PIN                        PC8
67
-
68
-#define Y_STEP_PIN                          PD9
69
-#define Y_DIR_PIN                           PD10
70
-#define Y_ENABLE_PIN                        PD11
71
-
72
-#define Z_STEP_PIN                          PE15
73
-#define Z_DIR_PIN                           PG1
74
-#define Z_ENABLE_PIN                        PD8
75
-
76
-#define E0_STEP_PIN                         PB1
77
-#define E0_DIR_PIN                          PB2
78
-#define E0_ENABLE_PIN                       PE11
79
-
80
-#define E1_STEP_PIN                         PC4
81
-#define E1_DIR_PIN                          PC5
82
-#define E1_ENABLE_PIN                       PB0
83
-
84
-#define E2_STEP_PIN                         PC13
85
-#define E2_DIR_PIN                          PC14
86
-#define E2_ENABLE_PIN                       PC15
87
-
88
-#define Z2_STEP_PIN                         PC13
89
-#define Z2_DIR_PIN                          PC14
90
-#define Z2_ENABLE_PIN                       PC15
91
-
92
-#define SCK_PIN                             PA5
93
-#define MISO_PIN                            PA6
94
-#define MOSI_PIN                            PA7
95
-
96
-#define SPI1_SCK_PIN                        PA5
97
-#define SPI1_MISO_PIN                       PA6
98
-#define SPI1_MOSI_PIN                       PA7
99
-
100
-#define SPI6_SCK_PIN                        PG13
101
-#define SPI6_MISO_PIN                       PG12
102
-#define SPI6_MOSI_PIN                       PG14
103
-
104
-//
105
-// Temperature Sensors
106
-//
107
-
108
-#define TEMP_0_PIN                          PC3   // Analog Input
109
-#define TEMP_1_PIN                          PC2   // Analog Input
110
-#define TEMP_2_PIN                          PC1   // Analog Input
111
-#define TEMP_3_PIN                          PC0   // Analog Input
112
-
113
-#define TEMP_BED_PIN                        PF10  // Analog Input
114
-
115
-#define TEMP_5_PIN                          PE12  // Analog Input, Probe temp
116
-
117
-//
118
-// Heaters / Fans
119
-//
120
-#define HEATER_0_PIN                        PD15
121
-#define HEATER_1_PIN                        PD14
122
-#define HEATER_BED_PIN                      PF6
123
-
124
-#ifndef FAN_PIN
125
-  #define FAN_PIN                           PD13
126
-#endif
127
-#define FAN1_PIN                            PA0
128
-#define FAN2_PIN                            PA1
129
-
130
-#ifndef E0_AUTO_FAN_PIN
131
-  #define E0_AUTO_FAN_PIN                   PA1
132
-#endif
133
-
134
-//
135
-// Misc. Functions
136
-//
137
-
138
-//#define CASE_LIGHT_PIN_CI                 PF13
139
-//#define CASE_LIGHT_PIN_DO                 PF14
140
-//#define NEOPIXEL_PIN                      PF13
141
-
142
-//
143
-// Průša i3 MK2 Multi Material Multiplexer Support
144
-//
145
-
146
-#define E_MUX0_PIN                          PG3
147
-#define E_MUX1_PIN                          PG4
148
-
149
-//
150
-// Servos
151
-//
152
-
153
-#define SERVO0_PIN                          PE13
154
-#define SERVO1_PIN                          PE14
155
-
156
-#define SDSS                                PA8
157
-#define SS_PIN                              PA8
158
-#define LED_PIN                             PA2   // Alive
159
-#define PS_ON_PIN                           PA3
160
-#define KILL_PIN                            -1    //PD5   // EXP2-10
161
-#define PWR_LOSS                            PG5   // Power loss / nAC_FAULT
162
-
163
-//
164
-// MAX7219_DEBUG
165
-//
166
-#define MAX7219_CLK_PIN                     PG10  // EXP1-1
167
-#define MAX7219_DIN_PIN                     PD7   // EXP1-3
168
-#define MAX7219_LOAD_PIN                    PD1   // EXP1-5
169
-
170
-//
171
-// LCD / Controller
172
-//
173
-//#define SD_DETECT_PIN                     -1    //PB6)     // EXP2-4
174
-#define BEEPER_PIN                          PG10  // EXP1-1
175
-#define LCD_PINS_RS                         PG9   // EXP1-4
176
-#define LCD_PINS_ENABLE                     PD7   // EXP1-3
177
-#define LCD_PINS_D4                         PD1   // EXP1-5
178
-#define LCD_PINS_D5                         PF0   // EXP1-6
179
-#define LCD_PINS_D6                         PD3   // EXP1-7
180
-#define LCD_PINS_D7                         PD4   // EXP1-8
181
-#define BTN_EN1                             PD6   // EXP2-5
182
-#define BTN_EN2                             PD0   // EXP2-3
183
-#define BTN_ENC                             PG11  // EXP1-2

+ 1
- 1
buildroot/tests/BIGTREE_SKR_PRO-tests Näytä tiedosto

@@ -25,7 +25,7 @@ opt_set E1_AUTO_FAN_PIN PC11
25 25
 opt_set E2_AUTO_FAN_PIN PC12
26 26
 opt_set X_DRIVER_TYPE TMC2209
27 27
 opt_set Y_DRIVER_TYPE TMC2130
28
-opt_enable BLTOUCH EEPROM_SETTINGS AUTO_BED_LEVELING_3POINT Z_SAFE_HOMING
28
+opt_enable BLTOUCH EEPROM_SETTINGS AUTO_BED_LEVELING_3POINT Z_SAFE_HOMING PINS_DEBUGGING
29 29
 exec_test $1 $2 "BigTreeTech SKR Pro 3 Extruders, Auto-Fan, BLTOUCH, mixed TMC drivers" "$3"
30 30
 
31 31
 # clean up

buildroot/tests/STM32F7-tests → buildroot/tests/REMRAM_V1-tests Näytä tiedosto

@@ -1,6 +1,6 @@
1 1
 #!/usr/bin/env bash
2 2
 #
3
-# Build tests for STM32F7
3
+# Build tests for REMRAM_V1
4 4
 #
5 5
 
6 6
 # exit on first failure

+ 1
- 0
buildroot/tests/STM32F103RC_btt-tests Näytä tiedosto

@@ -21,6 +21,7 @@ opt_set X_SLAVE_ADDRESS 0
21 21
 opt_set Y_SLAVE_ADDRESS 1
22 22
 opt_set Z_SLAVE_ADDRESS 2
23 23
 opt_set E0_SLAVE_ADDRESS 3
24
+opt_enable PINS_DEBUGGING
24 25
 
25 26
 exec_test $1 $2 "BigTreeTech SKR Mini E3 1.0 - Basic Config with TMC2209 HW Serial" "$3"
26 27
 

+ 0
- 16
buildroot/tests/STM32F4-tests Näytä tiedosto

@@ -1,16 +0,0 @@
1
-#!/usr/bin/env bash
2
-#
3
-# Build tests for STM32F4 disco_f407vg
4
-#
5
-
6
-# exit on first failure
7
-set -e
8
-
9
-#
10
-# Build with the default configurations
11
-#
12
-use_example_configs STM32/STM32F4
13
-exec_test $1 $2 "STM32F4 Default Configuration" "$3"
14
-
15
-# clean up
16
-restore_configs

+ 4
- 13
platformio.ini Näytä tiedosto

@@ -863,22 +863,13 @@ lib_deps          = ${common_stm32f1.lib_deps}
863 863
   USBComposite for STM32F1@0.91
864 864
 
865 865
 #
866
-# STM32F4 with STM32GENERIC
866
+# REMRAM_V1
867 867
 #
868
-[env:STM32F4]
869
-platform      = ${common_stm32.platform}
870
-board         = disco_f407vg
871
-build_flags   = ${common.build_flags} -DUSE_STM32GENERIC -DSTM32GENERIC -DSTM32F4 -DMENU_USB_SERIAL -DMENU_SERIAL=SerialUSB -DHAL_IWDG_MODULE_ENABLED
872
-src_filter    = ${common.default_src_filter} +<src/HAL/STM32_F4_F7> -<src/HAL/STM32_F4_F7/STM32F7>
873
-
874
-#
875
-# STM32F7 with STM32GENERIC
876
-#
877
-[env:STM32F7]
868
+[env:REMRAM_V1]
878 869
 platform      = ${common_stm32.platform}
870
+extends       = common_stm32
879 871
 board         = remram_v1
880
-build_flags   = ${common.build_flags} -DUSE_STM32GENERIC -DSTM32GENERIC -DSTM32F7 -DMENU_USB_SERIAL -DMENU_SERIAL=SerialUSB -DHAL_IWDG_MODULE_ENABLED
881
-src_filter    = ${common.default_src_filter} +<src/HAL/STM32_F4_F7> -<src/HAL/STM32_F4_F7/STM32F4>
872
+build_flags   = ${common_stm32.build_flags}
882 873
 
883 874
 #
884 875
 # ST NUCLEO-F767ZI Development Board

Loading…
Peruuta
Tallenna