Quellcode durchsuchen

New HardwareTimer for STM32 5.7.0 (#15655)

Lino Barreca vor 5 Jahren
Ursprung
Commit
ac71cdc265
31 geänderte Dateien mit 1289 neuen und 519 gelöschten Zeilen
  1. 9
    10
      .travis.yml
  2. 2
    2
      Marlin/src/HAL/HAL_ESP32/timers.h
  3. 1
    1
      Marlin/src/HAL/HAL_SAMD51/timers.cpp
  4. 14
    0
      Marlin/src/HAL/HAL_STM32/HAL.cpp
  5. 391
    0
      Marlin/src/HAL/HAL_STM32/SoftwareSerial.cpp
  6. 119
    0
      Marlin/src/HAL/HAL_STM32/SoftwareSerial.h
  7. 74
    28
      Marlin/src/HAL/HAL_STM32/timers.cpp
  8. 32
    37
      Marlin/src/HAL/HAL_STM32/timers.h
  9. 2
    2
      Marlin/src/HAL/HAL_STM32F1/timers.cpp
  10. 3
    4
      Marlin/src/HAL/HAL_STM32_F4_F7/HAL.h
  11. 2
    2
      Marlin/src/HAL/HAL_TEENSY31_32/timers.cpp
  12. 2
    2
      Marlin/src/HAL/HAL_TEENSY35_36/timers.cpp
  13. 1
    1
      Marlin/src/module/stepper.cpp
  14. 12
    2
      Marlin/src/module/temperature.cpp
  15. 3
    5
      Marlin/src/module/temperature.h
  16. 2
    4
      buildroot/share/PlatformIO/boards/BigTree_Btt002.json
  17. 2
    4
      buildroot/share/PlatformIO/boards/BigTree_SKR_Pro.json
  18. 0
    29
      buildroot/share/PlatformIO/scripts/black_stm32f407vet6.py
  19. 0
    2
      buildroot/share/PlatformIO/scripts/generic_create_variant.py
  20. 88
    185
      buildroot/share/PlatformIO/variants/BIGTREE_SKR_PRO_1v1/PeripheralPins.c
  21. 0
    0
      buildroot/share/PlatformIO/variants/BIGTREE_SKR_PRO_1v1/PinNamesVar.h
  22. 52
    0
      buildroot/share/PlatformIO/variants/BIGTREE_SKR_PRO_1v1/hal_conf_extra.h
  23. 0
    3
      buildroot/share/PlatformIO/variants/BIGTREE_SKR_PRO_1v1/ldscript.ld
  24. 0
    0
      buildroot/share/PlatformIO/variants/BIGTREE_SKR_PRO_1v1/variant.cpp
  25. 10
    6
      buildroot/share/PlatformIO/variants/BIGTREE_SKR_PRO_1v1/variant.h
  26. 112
    92
      buildroot/share/PlatformIO/variants/MARLIN_F407VE/PeripheralPins.c
  27. 62
    47
      buildroot/share/PlatformIO/variants/MARLIN_F407VE/hal_conf_custom.h
  28. 36
    16
      buildroot/share/PlatformIO/variants/MARLIN_F407VE/ldscript.ld
  29. 80
    4
      buildroot/share/PlatformIO/variants/MARLIN_F407VE/variant.cpp
  30. 144
    6
      buildroot/share/PlatformIO/variants/MARLIN_F407VE/variant.h
  31. 34
    25
      platformio.ini

+ 9
- 10
.travis.yml Datei anzeigen

@@ -25,23 +25,27 @@ env:
25 25
   - TEST_PLATFORM="sanguino_atmega1284p"
26 26
   - TEST_PLATFORM="sanguino_atmega644p"
27 27
 
28
-  # Broken Extended STM32 Environments
29
-  #- TEST_PLATFORM="ARMED"
30
-  #- TEST_PLATFORM="BIGTREE_BTT002"
31
-  #- TEST_PLATFORM="BIGTREE_SKR_PRO"
32
-
33 28
   # Extended STM32 Environments
34 29
   - TEST_PLATFORM="STM32F103RC_bigtree"
30
+  - TEST_PLATFORM="STM32F103RC_bigtree_USB"
31
+  - TEST_PLATFORM="STM32F103RC_fysetc"
35 32
   - TEST_PLATFORM="jgaurora_a5s_a1"
36 33
   - TEST_PLATFORM="STM32F103VE_longer"
37 34
   - TEST_PLATFORM="STM32F407VE_black"
35
+  - TEST_PLATFORM="BIGTREE_SKR_PRO"
38 36
   - TEST_PLATFORM="mks_robin"
37
+  - TEST_PLATFORM="ARMED"
38
+
39
+  # STM32 with non-STM framework. both broken for now. they should use HAL_STM32 which is working.
40
+  #- TEST_PLATFORM="STM32F4"
41
+  #- TEST_PLATFORM="STM32F7"
39 42
 
40 43
   # Put lengthy tests last
41 44
   - TEST_PLATFORM="LPC1768"
42 45
   - TEST_PLATFORM="LPC1769"
43 46
 
44 47
   # Non-working environment tests
48
+  #- TEST_PLATFORM="BIGTREE_BTT002" this board isn't released yet. we need pinout to be sure about what we do
45 49
   #- TEST_PLATFORM="at90usb1286_cdc"
46 50
   #- TEST_PLATFORM="at90usb1286_dfu"
47 51
   #- TEST_PLATFORM="STM32F103CB_malyan"
@@ -49,11 +53,6 @@ env:
49 53
   #- TEST_PLATFORM="mks_robin_mini"
50 54
   #- TEST_PLATFORM="mks_robin_nano"
51 55
   #- TEST_PLATFORM="SAMD51_grandcentral_m4"
52
-  #- TEST_PLATFORM="STM32F103RC_bigtree"
53
-  #- TEST_PLATFORM="STM32F103RC_bigtree_USB"
54
-  #- TEST_PLATFORM="STM32F103RC_fysetc"
55
-  #- TEST_PLATFORM="STM32F4"
56
-  #- TEST_PLATFORM="STM32F7"
57 56
 
58 57
 before_install:
59 58
   #

+ 2
- 2
Marlin/src/HAL/HAL_ESP32/timers.h Datei anzeigen

@@ -51,8 +51,8 @@ typedef uint64_t hal_timer_t;
51 51
   #define STEPPER_TIMER_TICKS_PER_US ((STEPPER_TIMER_RATE) / 1000000) // stepper timer ticks per µs // wrong would be 0.25
52 52
 #else
53 53
   #define STEPPER_TIMER_PRESCALE     40
54
-  #define STEPPER_TIMER_RATE         (HAL_TIMER_RATE / STEPPER_TIMER_PRESCALE) // frequency of stepper timer, 2MHz
55
-  #define STEPPER_TIMER_TICKS_PER_US ((STEPPER_TIMER_RATE) / 1000000)          // stepper timer ticks per µs
54
+  #define STEPPER_TIMER_RATE         ((HAL_TIMER_RATE) / (STEPPER_TIMER_PRESCALE)) // frequency of stepper timer, 2MHz
55
+  #define STEPPER_TIMER_TICKS_PER_US ((STEPPER_TIMER_RATE) / 1000000)              // stepper timer ticks per µs
56 56
 #endif
57 57
 
58 58
 #define STEP_TIMER_MIN_INTERVAL   8 // minimum time in µs between stepper interrupts

+ 1
- 1
Marlin/src/HAL/HAL_SAMD51/timers.cpp Datei anzeigen

@@ -99,7 +99,7 @@ void HAL_timer_start(const uint8_t timer_num, const uint32_t frequency) {
99 99
   SYNC(tc->COUNT32.SYNCBUSY.bit.CTRLB);
100 100
 
101 101
   // Set compare value
102
-  tc->COUNT32.COUNT.reg = tc->COUNT32.CC[0].reg = HAL_TIMER_RATE / frequency;
102
+  tc->COUNT32.COUNT.reg = tc->COUNT32.CC[0].reg = (HAL_TIMER_RATE) / frequency;
103 103
 
104 104
   // And start timer
105 105
   tc->COUNT32.CTRLA.bit.ENABLE = true;

+ 14
- 0
Marlin/src/HAL/HAL_STM32/HAL.cpp Datei anzeigen

@@ -28,6 +28,16 @@
28 28
 #include "../../inc/MarlinConfig.h"
29 29
 #include "../shared/Delay.h"
30 30
 
31
+#if (__cplusplus == 201703L) && defined(__has_include)
32
+  #define HAS_SWSERIAL __has_include(<SoftwareSerial.h>)
33
+#else
34
+  #define HAS_SWSERIAL HAS_TMC220x
35
+#endif
36
+
37
+#if HAS_SWSERIAL
38
+  #include "SoftwareSerial.h"
39
+#endif  
40
+
31 41
 #if ENABLED(SRAM_EEPROM_EMULATION)
32 42
   #if STM32F7xx
33 43
     #include "stm32f7xx_ll_pwr.h"
@@ -82,6 +92,10 @@ void HAL_init() {
82 92
   // Wait until backup regulator is initialized
83 93
   while (!LL_PWR_IsActiveFlag_BRR());
84 94
   #endif // EEPROM_EMULATED_SRAM
95
+
96
+  #if HAS_SWSERIAL
97
+    SoftwareSerial::setInterruptPriority(SWSERIAL_TIMER_IRQ_PRIO, 0);
98
+  #endif
85 99
 }
86 100
 
87 101
 void HAL_clear_reset_source() { __HAL_RCC_CLEAR_RESET_FLAGS(); }

+ 391
- 0
Marlin/src/HAL/HAL_STM32/SoftwareSerial.cpp Datei anzeigen

@@ -0,0 +1,391 @@
1
+/*
2
+ * SoftwareSerial.cpp (formerly NewSoftSerial.cpp)
3
+ *
4
+ * Multi-instance software serial library for Arduino/Wiring
5
+ * -- Interrupt-driven receive and other improvements by ladyada
6
+ *    (http://ladyada.net)
7
+ * -- Tuning, circular buffer, derivation from class Print/Stream,
8
+ *    multi-instance support, porting to 8MHz processors,
9
+ *    various optimizations, PROGMEM delay tables, inverse logic and
10
+ *    direct port writing by Mikal Hart (http://www.arduiniana.org)
11
+ * -- Pin change interrupt macros by Paul Stoffregen (http://www.pjrc.com)
12
+ * -- 20MHz processor support by Garrett Mace (http://www.macetech.com)
13
+ * -- ATmega1280/2560 support by Brett Hagman (http://www.roguerobotics.com/)
14
+ * -- STM32 support by Armin van der Togt
15
+ *
16
+ * This library is free software; you can redistribute it and/or
17
+ * modify it under the terms of the GNU Lesser General Public
18
+ * License as published by the Free Software Foundation; either
19
+ * version 2.1 of the License, or (at your option) any later version.
20
+ *
21
+ * This library is distributed in the hope that it will be useful,
22
+ * but WITHOUT ANY WARRANTY; without even the implied warranty of
23
+ * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the GNU
24
+ * Lesser General Public License for more details.
25
+ *
26
+ * You should have received a copy of the GNU Lesser General Public
27
+ * License along with this library; if not, write to the Free Software
28
+ * Foundation, Inc., 51 Franklin St, Fifth Floor, Boston, MA  02110-1301  USA
29
+ *
30
+ * The latest version of this library can always be found at
31
+ * http://arduiniana.org.
32
+ */
33
+
34
+//
35
+// Includes
36
+//
37
+#include "SoftwareSerial.h"
38
+#include <timer.h>
39
+
40
+#define OVERSAMPLE 3 // in RX, Timer will generate interruption OVERSAMPLE time during a bit. Thus OVERSAMPLE ticks in a bit. (interrupt not synchonized with edge).
41
+
42
+// defined in bit-periods
43
+#define HALFDUPLEX_SWITCH_DELAY 5
44
+// It's best to define TIMER_SERIAL in variant.h. If not defined, we choose one here
45
+// The order is based on (lack of) features and compare channels, we choose the simplest available
46
+// because we only need an update interrupt
47
+#if !defined(TIMER_SERIAL)
48
+#if defined (TIM18_BASE)
49
+#define TIMER_SERIAL TIM18
50
+#elif defined (TIM7_BASE)
51
+#define TIMER_SERIAL TIM7
52
+#elif defined (TIM6_BASE)
53
+#define TIMER_SERIAL TIM6
54
+#elif defined (TIM22_BASE)
55
+#define TIMER_SERIAL TIM22
56
+#elif defined (TIM21_BASE)
57
+#define TIMER_SERIAL TIM21
58
+#elif defined (TIM17_BASE)
59
+#define TIMER_SERIAL TIM17
60
+#elif defined (TIM16_BASE)
61
+#define TIMER_SERIAL TIM16
62
+#elif defined (TIM15_BASE)
63
+#define TIMER_SERIAL TIM15
64
+#elif defined (TIM14_BASE)
65
+#define TIMER_SERIAL TIM14
66
+#elif defined (TIM13_BASE)
67
+#define TIMER_SERIAL TIM13
68
+#elif defined (TIM11_BASE)
69
+#define TIMER_SERIAL TIM11
70
+#elif defined (TIM10_BASE)
71
+#define TIMER_SERIAL TIM10
72
+#elif defined (TIM12_BASE)
73
+#define TIMER_SERIAL TIM12
74
+#elif defined (TIM19_BASE)
75
+#define TIMER_SERIAL TIM19
76
+#elif defined (TIM9_BASE)
77
+#define TIMER_SERIAL TIM9
78
+#elif defined (TIM5_BASE)
79
+#define TIMER_SERIAL TIM5
80
+#elif defined (TIM4_BASE)
81
+#define TIMER_SERIAL TIM4
82
+#elif defined (TIM3_BASE)
83
+#define TIMER_SERIAL TIM3
84
+#elif defined (TIM2_BASE)
85
+#define TIMER_SERIAL TIM2
86
+#elif defined (TIM20_BASE)
87
+#define TIMER_SERIAL TIM20
88
+#elif defined (TIM8_BASE)
89
+#define TIMER_SERIAL TIM8
90
+#elif defined (TIM1_BASE)
91
+#define TIMER_SERIAL TIM1
92
+#else
93
+#error No suitable timer found for SoftwareSerial, define TIMER_SERIAL in variant.h
94
+#endif
95
+#endif
96
+//
97
+// Statics
98
+//
99
+HardwareTimer SoftwareSerial::timer(TIMER_SERIAL);
100
+const IRQn_Type SoftwareSerial::timer_interrupt_number = static_cast<IRQn_Type>(getTimerUpIrq(TIMER_SERIAL));
101
+uint32_t SoftwareSerial::timer_interrupt_priority = NVIC_EncodePriority(NVIC_GetPriorityGrouping(), TIM_IRQ_PRIO, TIM_IRQ_SUBPRIO);
102
+SoftwareSerial *SoftwareSerial::active_listener = nullptr;
103
+SoftwareSerial *volatile SoftwareSerial::active_out = nullptr;
104
+SoftwareSerial *volatile SoftwareSerial::active_in = nullptr;
105
+int32_t SoftwareSerial::tx_tick_cnt = 0; // OVERSAMPLE ticks needed for a bit
106
+int32_t volatile SoftwareSerial::rx_tick_cnt = 0;  // OVERSAMPLE ticks needed for a bit
107
+uint32_t SoftwareSerial::tx_buffer = 0;
108
+int32_t SoftwareSerial::tx_bit_cnt = 0;
109
+uint32_t SoftwareSerial::rx_buffer = 0;
110
+int32_t SoftwareSerial::rx_bit_cnt = -1; // rx_bit_cnt = -1 :  waiting for start bit
111
+uint32_t SoftwareSerial::cur_speed = 0;
112
+
113
+void SoftwareSerial::setInterruptPriority(uint32_t preemptPriority, uint32_t subPriority) {
114
+  timer_interrupt_priority = NVIC_EncodePriority(NVIC_GetPriorityGrouping(), preemptPriority, subPriority);
115
+}
116
+
117
+//
118
+// Private methods
119
+//
120
+
121
+void SoftwareSerial::setSpeed(uint32_t speed) {
122
+  if (speed != cur_speed) {
123
+    timer.pause();
124
+    if (speed != 0) {
125
+      // Disable the timer
126
+      uint32_t clock_rate, cmp_value;
127
+      // Get timer clock
128
+      clock_rate = timer.getTimerClkFreq();
129
+      int pre = 1;
130
+      // Calculate prescale an compare value
131
+      do {
132
+        cmp_value = clock_rate / (speed * OVERSAMPLE);
133
+        if (cmp_value >= UINT16_MAX) {
134
+          clock_rate /= 2;
135
+          pre *= 2;
136
+        }
137
+      } while (cmp_value >= UINT16_MAX);
138
+      timer.setPrescaleFactor(pre);
139
+      timer.setOverflow(cmp_value);
140
+      timer.setCount(0);
141
+      timer.attachInterrupt(&handleInterrupt);
142
+      timer.resume();
143
+      NVIC_SetPriority(timer_interrupt_number, timer_interrupt_priority);
144
+    }
145
+    else
146
+      timer.detachInterrupt();
147
+    cur_speed = speed;
148
+  }
149
+}
150
+
151
+// This function sets the current object as the "listening"
152
+// one and returns true if it replaces another
153
+bool SoftwareSerial::listen() {
154
+  if (active_listener != this) {
155
+    // wait for any transmit to complete as we may change speed
156
+    while (active_out);
157
+    active_listener->stopListening();
158
+    rx_tick_cnt = 1; // 1 : next interrupt will decrease rx_tick_cnt to 0 which means RX pin level will be considered.
159
+    rx_bit_cnt = -1; // rx_bit_cnt = -1 :  waiting for start bit
160
+    setSpeed(_speed);
161
+    active_listener = this;
162
+    if (!_half_duplex) active_in = this;
163
+    return true;
164
+  }
165
+  return false;
166
+}
167
+
168
+// Stop listening. Returns true if we were actually listening.
169
+bool SoftwareSerial::stopListening() {
170
+  if (active_listener == this) {
171
+    // wait for any output to complete
172
+    while (active_out);
173
+    if (_half_duplex) setRXTX(false);
174
+    active_listener = nullptr;
175
+    active_in = nullptr;
176
+    // turn off ints
177
+    setSpeed(0);
178
+    return true;
179
+  }
180
+  return false;
181
+}
182
+
183
+inline void SoftwareSerial::setTX() {
184
+  if (_inverse_logic)
185
+    LL_GPIO_ResetOutputPin(_transmitPinPort, _transmitPinNumber);
186
+  else
187
+    LL_GPIO_SetOutputPin(_transmitPinPort, _transmitPinNumber);
188
+  pinMode(_transmitPin, OUTPUT);
189
+}
190
+
191
+inline void SoftwareSerial::setRX() {
192
+  pinMode(_receivePin, _inverse_logic ? INPUT_PULLDOWN : INPUT_PULLUP); // pullup for normal logic!
193
+}
194
+
195
+inline void SoftwareSerial::setRXTX(bool input) {
196
+  if (_half_duplex) {
197
+    if (input) {
198
+      if (active_in != this) {
199
+        setRX();
200
+        rx_bit_cnt = -1; // rx_bit_cnt = -1 :  waiting for start bit
201
+        rx_tick_cnt = 2; // 2 : next interrupt will be discarded. 2 interrupts required to consider RX pin level
202
+        active_in = this;
203
+      }
204
+    }
205
+    else {
206
+      if (active_in == this) {
207
+        setTX();
208
+        active_in = nullptr;
209
+      }
210
+    }
211
+  }
212
+}
213
+
214
+inline void SoftwareSerial::send() {
215
+  if (--tx_tick_cnt <= 0) { // if tx_tick_cnt > 0 interrupt is discarded. Only when tx_tick_cnt reaches 0 is TX pin set.
216
+    if (tx_bit_cnt++ < 10) { // tx_bit_cnt < 10 transmission is not finished (10 = 1 start +8 bits + 1 stop)
217
+      // Send data (including start and stop bits)
218
+      if (tx_buffer & 1)
219
+        LL_GPIO_SetOutputPin(_transmitPinPort, _transmitPinNumber);
220
+      else
221
+        LL_GPIO_ResetOutputPin(_transmitPinPort, _transmitPinNumber);
222
+      tx_buffer >>= 1;
223
+      tx_tick_cnt = OVERSAMPLE; // Wait OVERSAMPLE ticks to send next bit
224
+    }
225
+    else { // Transmission finished
226
+      tx_tick_cnt = 1;
227
+      if (_output_pending) {
228
+        active_out = nullptr;
229
+
230
+        // In half-duplex mode wait HALFDUPLEX_SWITCH_DELAY bit-periods after the byte has
231
+        // been transmitted before allowing the switch to RX mode
232
+      }
233
+      else if (tx_bit_cnt > 10 + OVERSAMPLE * HALFDUPLEX_SWITCH_DELAY) {
234
+        if (_half_duplex && active_listener == this) setRXTX(true);
235
+        active_out = nullptr;
236
+      }
237
+    }
238
+  }
239
+}
240
+
241
+//
242
+// The receive routine called by the interrupt handler
243
+//
244
+inline void SoftwareSerial::recv() {
245
+  if (--rx_tick_cnt <= 0) { // if rx_tick_cnt > 0 interrupt is discarded. Only when rx_tick_cnt reaches 0 is RX pin considered
246
+    bool inbit = LL_GPIO_IsInputPinSet(_receivePinPort, _receivePinNumber) ^ _inverse_logic;
247
+    if (rx_bit_cnt == -1) {  // rx_bit_cnt = -1 :  waiting for start bit
248
+      if (!inbit) {
249
+        // got start bit
250
+        rx_bit_cnt = 0; // rx_bit_cnt == 0 : start bit received
251
+        rx_tick_cnt = OVERSAMPLE + 1; // Wait 1 bit (OVERSAMPLE ticks) + 1 tick in order to sample RX pin in the middle of the edge (and not too close to the edge)
252
+        rx_buffer = 0;
253
+      }
254
+      else
255
+        rx_tick_cnt = 1; // Waiting for start bit, but wrong level. Wait for next Interrupt to check RX pin level
256
+    }
257
+    else if (rx_bit_cnt >= 8) { // rx_bit_cnt >= 8 : waiting for stop bit
258
+      if (inbit) {
259
+        // Stop-bit read complete. Add to buffer.
260
+        uint8_t next = (_receive_buffer_tail + 1) % _SS_MAX_RX_BUFF;
261
+        if (next != _receive_buffer_head) {
262
+          // save new data in buffer: tail points to byte destination
263
+          _receive_buffer[_receive_buffer_tail] = rx_buffer; // save new byte
264
+          _receive_buffer_tail = next;
265
+        }
266
+        else // rx_bit_cnt = x  with x = [0..7] correspond to new bit x received
267
+          _buffer_overflow = true;
268
+      }
269
+      // Full trame received. Restart waiting for start bit at next interrupt
270
+      rx_tick_cnt = 1;
271
+      rx_bit_cnt = -1;
272
+    }
273
+    else {
274
+      // data bits
275
+      rx_buffer >>= 1;
276
+      if (inbit) rx_buffer |= 0x80;
277
+      rx_bit_cnt++; // Prepare for next bit
278
+      rx_tick_cnt = OVERSAMPLE; // Wait OVERSAMPLE ticks before sampling next bit
279
+    }
280
+  }
281
+}
282
+
283
+//
284
+// Interrupt handling
285
+//
286
+
287
+/* static */
288
+inline void SoftwareSerial::handleInterrupt(HardwareTimer*) {
289
+  if (active_in)   active_in->recv();
290
+  if (active_out) active_out->send();
291
+}
292
+
293
+//
294
+// Constructor
295
+//
296
+SoftwareSerial::SoftwareSerial(uint16_t receivePin, uint16_t transmitPin, bool inverse_logic /* = false */) :
297
+  _receivePin(receivePin),
298
+  _transmitPin(transmitPin),
299
+  _receivePinPort(digitalPinToPort(receivePin)),
300
+  _receivePinNumber(STM_LL_GPIO_PIN(digitalPinToPinName(receivePin))),
301
+  _transmitPinPort(digitalPinToPort(transmitPin)),
302
+  _transmitPinNumber(STM_LL_GPIO_PIN(digitalPinToPinName(transmitPin))),
303
+  _speed(0),
304
+  _buffer_overflow(false),
305
+  _inverse_logic(inverse_logic),
306
+  _half_duplex(receivePin == transmitPin),
307
+  _output_pending(0),
308
+  _receive_buffer_tail(0),
309
+  _receive_buffer_head(0)
310
+{
311
+  if ((receivePin < NUM_DIGITAL_PINS) || (transmitPin < NUM_DIGITAL_PINS)) {
312
+    /* Enable GPIO clock for tx and rx pin*/
313
+    set_GPIO_Port_Clock(STM_PORT(digitalPinToPinName(transmitPin)));
314
+    set_GPIO_Port_Clock(STM_PORT(digitalPinToPinName(receivePin)));
315
+  }
316
+  else
317
+    _Error_Handler("ERROR: invalid pin number\n", -1);
318
+}
319
+
320
+//
321
+// Destructor
322
+//
323
+SoftwareSerial::~SoftwareSerial() { end(); }
324
+
325
+//
326
+// Public methods
327
+//
328
+
329
+void SoftwareSerial::begin(long speed) {
330
+  #ifdef FORCE_BAUD_RATE
331
+    speed = FORCE_BAUD_RATE;
332
+  #endif
333
+  _speed = speed;
334
+  if (!_half_duplex) {
335
+    setTX();
336
+    setRX();
337
+    listen();
338
+  }
339
+  else
340
+    setTX();
341
+}
342
+
343
+void SoftwareSerial::end() {
344
+  stopListening();
345
+}
346
+
347
+// Read data from buffer
348
+int SoftwareSerial::read() {
349
+  // Empty buffer?
350
+  if (_receive_buffer_head == _receive_buffer_tail) return -1;
351
+
352
+  // Read from "head"
353
+  uint8_t d = _receive_buffer[_receive_buffer_head]; // grab next byte
354
+  _receive_buffer_head = (_receive_buffer_head + 1) % _SS_MAX_RX_BUFF;
355
+  return d;
356
+}
357
+
358
+int SoftwareSerial::available() {
359
+  return (_receive_buffer_tail + _SS_MAX_RX_BUFF - _receive_buffer_head) % _SS_MAX_RX_BUFF;
360
+}
361
+
362
+size_t SoftwareSerial::write(uint8_t b) {
363
+  // wait for previous transmit to complete
364
+  _output_pending = 1;
365
+  while (active_out) { /* nada */ }
366
+  // add start and stop bits.
367
+  tx_buffer = b << 1 | 0x200;
368
+  if (_inverse_logic) tx_buffer = ~tx_buffer;
369
+  tx_bit_cnt = 0;
370
+  tx_tick_cnt = OVERSAMPLE;
371
+  setSpeed(_speed);
372
+  if (_half_duplex) setRXTX(false);
373
+  _output_pending = 0;
374
+  // make us active
375
+  active_out = this;
376
+  return 1;
377
+}
378
+
379
+void SoftwareSerial::flush() {
380
+  noInterrupts();
381
+  _receive_buffer_head = _receive_buffer_tail = 0;
382
+  interrupts();
383
+}
384
+
385
+int SoftwareSerial::peek() {
386
+  // Empty buffer?
387
+  if (_receive_buffer_head == _receive_buffer_tail) return -1;
388
+
389
+  // Read from "head"
390
+  return _receive_buffer[_receive_buffer_head];
391
+}

+ 119
- 0
Marlin/src/HAL/HAL_STM32/SoftwareSerial.h Datei anzeigen

@@ -0,0 +1,119 @@
1
+/**
2
+ * SoftwareSerial.h (formerly NewSoftSerial.h)
3
+ *
4
+ * Multi-instance software serial library for Arduino/Wiring
5
+ * -- Interrupt-driven receive and other improvements by ladyada
6
+ *    (http://ladyada.net)
7
+ * -- Tuning, circular buffer, derivation from class Print/Stream,
8
+ *    multi-instance support, porting to 8MHz processors,
9
+ *    various optimizations, PROGMEM delay tables, inverse logic and
10
+ *    direct port writing by Mikal Hart (http://www.arduiniana.org)
11
+ * -- Pin change interrupt macros by Paul Stoffregen (http://www.pjrc.com)
12
+ * -- 20MHz processor support by Garrett Mace (http://www.macetech.com)
13
+ * -- ATmega1280/2560 support by Brett Hagman (http://www.roguerobotics.com/)
14
+ *
15
+ * This library is free software; you can redistribute it and/or
16
+ * modify it under the terms of the GNU Lesser General Public
17
+ * License as published by the Free Software Foundation; either
18
+ * version 2.1 of the License, or (at your option) any later version.
19
+ *
20
+ * This library is distributed in the hope that it will be useful,
21
+ * but WITHOUT ANY WARRANTY; without even the implied warranty of
22
+ * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the GNU
23
+ * Lesser General Public License for more details.
24
+ *
25
+ * You should have received a copy of the GNU Lesser General Public
26
+ * License along with this library; if not, write to the Free Software
27
+ * Foundation, Inc., 51 Franklin St, Fifth Floor, Boston, MA  02110-1301  USA
28
+ *
29
+ * The latest version of this library can always be found at
30
+ * http://arduiniana.org.
31
+ */
32
+
33
+#ifndef SOFTWARESERIAL_H
34
+#define SOFTWARESERIAL_H
35
+
36
+#include <Arduino.h>
37
+
38
+/******************************************************************************
39
+ * Definitions
40
+ ******************************************************************************/
41
+
42
+#define _SS_MAX_RX_BUFF 64 // RX buffer size
43
+
44
+class SoftwareSerial : public Stream {
45
+  private:
46
+    // per object data
47
+    uint16_t _receivePin;
48
+    uint16_t _transmitPin;
49
+    GPIO_TypeDef *_receivePinPort;
50
+    uint32_t _receivePinNumber;
51
+    GPIO_TypeDef *_transmitPinPort;
52
+    uint32_t _transmitPinNumber;
53
+    uint32_t _speed;
54
+
55
+    uint16_t _buffer_overflow: 1;
56
+    uint16_t _inverse_logic: 1;
57
+    uint16_t _half_duplex: 1;
58
+    uint16_t _output_pending: 1;
59
+
60
+    unsigned char _receive_buffer[_SS_MAX_RX_BUFF];
61
+    volatile uint8_t _receive_buffer_tail;
62
+    volatile uint8_t _receive_buffer_head;
63
+
64
+    uint32_t delta_start = 0;
65
+
66
+    // static data
67
+    static bool initialised;
68
+    static HardwareTimer timer;
69
+    static const IRQn_Type timer_interrupt_number;
70
+    static uint32_t timer_interrupt_priority;
71
+    static SoftwareSerial *active_listener;
72
+    static SoftwareSerial *volatile active_out;
73
+    static SoftwareSerial *volatile active_in;
74
+    static int32_t tx_tick_cnt;
75
+    static volatile int32_t rx_tick_cnt;
76
+    static uint32_t tx_buffer;
77
+    static int32_t tx_bit_cnt;
78
+    static uint32_t rx_buffer;
79
+    static int32_t rx_bit_cnt;
80
+    static uint32_t cur_speed;
81
+
82
+    // private methods
83
+    void send();
84
+    void recv();
85
+    void setTX();
86
+    void setRX();
87
+    void setSpeed(uint32_t speed);
88
+    void setRXTX(bool input);
89
+    static void handleInterrupt(HardwareTimer *timer);
90
+
91
+  public:
92
+    // public methods
93
+
94
+    SoftwareSerial(uint16_t receivePin, uint16_t transmitPin, bool inverse_logic = false);
95
+    virtual ~SoftwareSerial();
96
+    void begin(long speed);
97
+    bool listen();
98
+    void end();
99
+    bool isListening() { return active_listener == this; }
100
+    bool stopListening();
101
+    bool overflow() {
102
+      bool ret = _buffer_overflow;
103
+      if (ret) _buffer_overflow = false;
104
+      return ret;
105
+    }
106
+    int peek();
107
+
108
+    virtual size_t write(uint8_t byte);
109
+    virtual int read();
110
+    virtual int available();
111
+    virtual void flush();
112
+    operator bool() { return true; }
113
+
114
+    static void setInterruptPriority(uint32_t preemptPriority, uint32_t subPriority);
115
+
116
+    using Print::write;
117
+};
118
+
119
+#endif // SOFTWARESERIAL_H

+ 74
- 28
Marlin/src/HAL/HAL_STM32/timers.cpp Datei anzeigen

@@ -32,62 +32,108 @@
32 32
 
33 33
 #define NUM_HARDWARE_TIMERS 2
34 34
 
35
+#define __TIMER_DEV(X) TIM##X
36
+#define _TIMER_DEV(X) __TIMER_DEV(X)
37
+#define STEP_TIMER_DEV _TIMER_DEV(STEP_TIMER)
38
+#define TEMP_TIMER_DEV _TIMER_DEV(TEMP_TIMER)
39
+
35 40
 // ------------------------
36 41
 // Private Variables
37 42
 // ------------------------
38 43
 
39
-stm32_timer_t TimerHandle[NUM_HARDWARE_TIMERS];
44
+HardwareTimer *timer_instance[NUM_HARDWARE_TIMERS] = { NULL };
45
+bool timer_enabled[NUM_HARDWARE_TIMERS] = { false };
40 46
 
41 47
 // ------------------------
42 48
 // Public functions
43 49
 // ------------------------
44 50
 
45
-bool timers_initialized[NUM_HARDWARE_TIMERS] = { false };
46
-
51
+// frequency is in Hertz
47 52
 void HAL_timer_start(const uint8_t timer_num, const uint32_t frequency) {
48
-
49
-  if (!timers_initialized[timer_num]) {
50
-    uint32_t step_prescaler = STEPPER_TIMER_PRESCALE - 1,
51
-                       temp_prescaler = TEMP_TIMER_PRESCALE - 1;
53
+  if (!HAL_timer_initialized(timer_num)) {
52 54
     switch (timer_num) {
55
+      case STEP_TIMER_NUM: // STEPPER TIMER - use a 32bit timer if possible
56
+        timer_instance[timer_num] = new HardwareTimer(STEP_TIMER_DEV);
57
+        /* Set the prescaler to the final desired value.
58
+         * This will change the effective ISR callback frequency but when
59
+         * HAL_timer_start(timer_num=0) is called in the core for the first time
60
+         * the real frequency isn't important as long as, after boot, the ISR
61
+         * gets called with the correct prescaler and count register. So here
62
+         * we set the prescaler to the correct, final value and ignore the frequency
63
+         * asked. We will call back the ISR in 1 second to start at full speed.
64
+         *
65
+         * The proper fix, however, would be a correct initialization OR a
66
+         * HAL_timer_change(const uint8_t timer_num, const uint32_t frequency)
67
+         * which changes the prescaler when an IRQ frequency change is needed
68
+         * (for example when steppers are turned on)
69
+         */
70
+        timer_instance[timer_num]->setPrescaleFactor(STEPPER_TIMER_PRESCALE); //the -1 is done internally
71
+        timer_instance[timer_num]->setOverflow(_MIN(hal_timer_t(HAL_TIMER_TYPE_MAX), (HAL_TIMER_RATE) / (STEPPER_TIMER_PRESCALE) /* /frequency */), TICK_FORMAT);
72
+        break;
73
+      case TEMP_TIMER_NUM: // TEMP TIMER - any available 16bit timer
74
+        timer_instance[timer_num] = new HardwareTimer(TEMP_TIMER_DEV);
75
+        // The prescale factor is computed automatically for HERTZ_FORMAT
76
+        timer_instance[timer_num]->setOverflow(frequency, HERTZ_FORMAT);
77
+        break;
78
+    }
79
+
80
+    HAL_timer_enable_interrupt(timer_num);
81
+
82
+    /*
83
+     * Initializes (and unfortunately starts) the timer.
84
+     * This is needed to set correct IRQ priority at the moment but causes
85
+     * no harm since every call to HAL_timer_start() is actually followed by
86
+     * a call to HAL_timer_enable_interrupt() which means that there isn't
87
+     * a case in which you want the timer to run without a callback.
88
+     */
89
+    timer_instance[timer_num]->resume(); // First call to resume() MUST follow the attachInterrupt()
90
+
91
+    // This is fixed in Arduino_Core_STM32 1.8.
92
+    // These calls can be removed and replaced with
93
+    // timer_instance[timer_num]->setInterruptPriority
94
+    switch (timer_num) {                 
53 95
       case STEP_TIMER_NUM:
54
-        // STEPPER TIMER - use a 32bit timer if possible
55
-        TimerHandle[timer_num].timer = STEP_TIMER_DEV;
56
-        TimerHandle[timer_num].irqHandle = Step_Handler;
57
-        TimerHandleInit(&TimerHandle[timer_num], (((HAL_TIMER_RATE) / step_prescaler) / frequency) - 1, step_prescaler);
58 96
         HAL_NVIC_SetPriority(STEP_TIMER_IRQ_NAME, STEP_TIMER_IRQ_PRIO, 0);
59 97
         break;
60
-
61 98
       case TEMP_TIMER_NUM:
62
-        // TEMP TIMER - any available 16bit Timer
63
-        TimerHandle[timer_num].timer = TEMP_TIMER_DEV;
64
-        TimerHandle[timer_num].irqHandle = Temp_Handler;
65
-        TimerHandleInit(&TimerHandle[timer_num], (((HAL_TIMER_RATE) / temp_prescaler) / frequency) - 1, temp_prescaler);
66 99
         HAL_NVIC_SetPriority(TEMP_TIMER_IRQ_NAME, TEMP_TIMER_IRQ_PRIO, 0);
67 100
         break;
68 101
     }
69
-    timers_initialized[timer_num] = true;
70 102
   }
71 103
 }
72 104
 
73 105
 void HAL_timer_enable_interrupt(const uint8_t timer_num) {
74
-  const IRQn_Type IRQ_Id = IRQn_Type(getTimerIrq(TimerHandle[timer_num].timer));
75
-  HAL_NVIC_EnableIRQ(IRQ_Id);
106
+  if (HAL_timer_initialized(timer_num) && !timer_enabled[timer_num]) {
107
+    timer_enabled[timer_num] = true;
108
+    switch (timer_num) {
109
+      case STEP_TIMER_NUM:
110
+      timer_instance[timer_num]->attachInterrupt(Step_Handler);
111
+      break;
112
+    case TEMP_TIMER_NUM:
113
+      timer_instance[timer_num]->attachInterrupt(Temp_Handler);
114
+      break;
115
+    }
116
+  }
76 117
 }
77 118
 
78 119
 void HAL_timer_disable_interrupt(const uint8_t timer_num) {
79
-  const IRQn_Type IRQ_Id = IRQn_Type(getTimerIrq(TimerHandle[timer_num].timer));
80
-  HAL_NVIC_DisableIRQ(IRQ_Id);
81
-
82
-  // We NEED memory barriers to ensure Interrupts are actually disabled!
83
-  // ( https://dzone.com/articles/nvic-disabling-interrupts-on-arm-cortex-m-and-the )
84
-  __DSB();
85
-  __ISB();
120
+  if (HAL_timer_interrupt_enabled(timer_num)) {
121
+    timer_instance[timer_num]->detachInterrupt();
122
+    timer_enabled[timer_num] = false;
123
+  }
86 124
 }
87 125
 
88 126
 bool HAL_timer_interrupt_enabled(const uint8_t timer_num) {
89
-  const uint32_t IRQ_Id = getTimerIrq(TimerHandle[timer_num].timer);
90
-  return NVIC->ISER[IRQ_Id >> 5] & _BV32(IRQ_Id & 0x1F);
127
+  return HAL_timer_initialized(timer_num) && timer_enabled[timer_num];
128
+}
129
+
130
+// Only for use within the HAL
131
+TIM_TypeDef * HAL_timer_device(const uint8_t timer_num) {
132
+  switch (timer_num) {
133
+    case STEP_TIMER_NUM: return STEP_TIMER_DEV;
134
+    case TEMP_TIMER_NUM: return TEMP_TIMER_DEV;
135
+  }
136
+  return nullptr;
91 137
 }
92 138
 
93 139
 #endif // ARDUINO_ARCH_STM32 && !STM32GENERIC

+ 32
- 37
Marlin/src/HAL/HAL_STM32/timers.h Datei anzeigen

@@ -33,6 +33,7 @@
33 33
 #define hal_timer_t uint32_t
34 34
 #define HAL_TIMER_TYPE_MAX 0xFFFFFFFF // Timers can be 16 or 32 bit
35 35
 
36
+
36 37
 #ifdef STM32F0xx
37 38
 
38 39
   #define HAL_TIMER_RATE (F_CPU) // frequency of timer peripherals
@@ -66,27 +67,30 @@
66 67
   #endif
67 68
 
68 69
   #ifndef TEMP_TIMER
69
-    #define TEMP_TIMER 7
70
+    #define TEMP_TIMER 14 // TIM7 is consumed by Software Serial if used.
70 71
   #endif
71 72
 
72 73
 #endif
73 74
 
75
+#ifndef SWSERIAL_TIMER_IRQ_PRIO
76
+  #define SWSERIAL_TIMER_IRQ_PRIO 1
77
+#endif
78
+
74 79
 #ifndef STEP_TIMER_IRQ_PRIO
75
-  #define STEP_TIMER_IRQ_PRIO 1
80
+  #define STEP_TIMER_IRQ_PRIO 2
76 81
 #endif
77 82
 
78 83
 #ifndef TEMP_TIMER_IRQ_PRIO
79
-  #define TEMP_TIMER_IRQ_PRIO 2
84
+  #define TEMP_TIMER_IRQ_PRIO 14 //14 = after hardware ISRs
80 85
 #endif
81 86
 
82 87
 #define STEP_TIMER_NUM 0  // index of timer to use for stepper
83 88
 #define TEMP_TIMER_NUM 1  // index of timer to use for temperature
84 89
 #define PULSE_TIMER_NUM STEP_TIMER_NUM
85 90
 
86
-#define TEMP_TIMER_RATE 72000 // 72 Khz
87
-#define TEMP_TIMER_PRESCALE ((HAL_TIMER_RATE)/(TEMP_TIMER_RATE))
88
-#define TEMP_TIMER_FREQUENCY 1000
91
+#define TEMP_TIMER_FREQUENCY 1000 //Temperature::isr() is expected to be called at around 1kHz
89 92
 
93
+//TODO: get rid of manual rate/prescale/ticks/cycles taken for procedures in stepper.cpp
90 94
 #define STEPPER_TIMER_RATE 2000000 // 2 Mhz
91 95
 #define STEPPER_TIMER_PRESCALE ((HAL_TIMER_RATE)/(STEPPER_TIMER_RATE))
92 96
 #define STEPPER_TIMER_TICKS_PER_US ((STEPPER_TIMER_RATE) / 1000000) // stepper timer ticks per µs
@@ -95,17 +99,6 @@
95 99
 #define PULSE_TIMER_PRESCALE STEPPER_TIMER_PRESCALE
96 100
 #define PULSE_TIMER_TICKS_PER_US STEPPER_TIMER_TICKS_PER_US
97 101
 
98
-#define __TIMER_DEV(X) TIM##X
99
-#define _TIMER_DEV(X) __TIMER_DEV(X)
100
-#define STEP_TIMER_DEV _TIMER_DEV(STEP_TIMER)
101
-#define TEMP_TIMER_DEV _TIMER_DEV(TEMP_TIMER)
102
-
103
-#define __TIMER_CALLBACK(X) TIM##X##_IRQHandler
104
-#define _TIMER_CALLBACK(X) __TIMER_CALLBACK(X)
105
-
106
-#define STEP_TIMER_CALLBACK _TIMER_CALLBACK(STEP_TIMER)
107
-#define TEMP_TIMER_CALLBACK _TIMER_CALLBACK(TEMP_TIMER)
108
-
109 102
 #define __TIMER_IRQ_NAME(X) TIM##X##_IRQn
110 103
 #define _TIMER_IRQ_NAME(X) __TIMER_IRQ_NAME(X)
111 104
 
@@ -119,22 +112,16 @@
119 112
 #define ENABLE_TEMPERATURE_INTERRUPT() HAL_timer_enable_interrupt(TEMP_TIMER_NUM)
120 113
 #define DISABLE_TEMPERATURE_INTERRUPT() HAL_timer_disable_interrupt(TEMP_TIMER_NUM)
121 114
 
122
-extern void Step_Handler(stimer_t *htim);
123
-extern void Temp_Handler(stimer_t *htim);
124
-#define HAL_STEP_TIMER_ISR() void Step_Handler(stimer_t *htim)
125
-#define HAL_TEMP_TIMER_ISR() void Temp_Handler(stimer_t *htim)
126
-
127
-// ------------------------
128
-// Types
129
-// ------------------------
130
-
131
-typedef stimer_t stm32_timer_t;
115
+extern void Step_Handler(HardwareTimer *htim);
116
+extern void Temp_Handler(HardwareTimer *htim);
117
+#define HAL_STEP_TIMER_ISR() void Step_Handler(HardwareTimer *htim)
118
+#define HAL_TEMP_TIMER_ISR() void Temp_Handler(HardwareTimer *htim)
132 119
 
133 120
 // ------------------------
134 121
 // Public Variables
135 122
 // ------------------------
136 123
 
137
-extern stm32_timer_t TimerHandle[];
124
+extern HardwareTimer *timer_instance[];
138 125
 
139 126
 // ------------------------
140 127
 // Public functions
@@ -145,18 +132,26 @@ void HAL_timer_enable_interrupt(const uint8_t timer_num);
145 132
 void HAL_timer_disable_interrupt(const uint8_t timer_num);
146 133
 bool HAL_timer_interrupt_enabled(const uint8_t timer_num);
147 134
 
148
-FORCE_INLINE static uint32_t HAL_timer_get_count(const uint8_t timer_num) {
149
-  return __HAL_TIM_GET_COUNTER(&TimerHandle[timer_num].handle);
150
-}
135
+//TIM_TypeDef* HAL_timer_device(const uint8_t timer_num); no need to be public for now. not public = not used externally
151 136
 
152
-FORCE_INLINE static void HAL_timer_set_compare(const uint8_t timer_num, const uint32_t compare) {
153
-  __HAL_TIM_SET_AUTORELOAD(&TimerHandle[timer_num].handle, compare);
154
-  if (HAL_timer_get_count(timer_num) >= compare)
155
-    TimerHandle[timer_num].handle.Instance->EGR |= TIM_EGR_UG; // Generate an immediate update interrupt
137
+// FORCE_INLINE because these are used in performance-critical situations
138
+FORCE_INLINE bool HAL_timer_initialized(const uint8_t timer_num) {
139
+  return timer_instance[timer_num] != NULL;
140
+}
141
+FORCE_INLINE static hal_timer_t HAL_timer_get_count(const uint8_t timer_num) {
142
+  return HAL_timer_initialized(timer_num) ? timer_instance[timer_num]->getCount() : 0;
156 143
 }
157 144
 
158
-FORCE_INLINE static hal_timer_t HAL_timer_get_compare(const uint8_t timer_num) {
159
-  return __HAL_TIM_GET_AUTORELOAD(&TimerHandle[timer_num].handle);
145
+// NOTE: Method name may be misleading.
146
+// STM32 has an Auto-Reload Register (ARR) as opposed to a "compare" register
147
+FORCE_INLINE static void HAL_timer_set_compare(const uint8_t timer_num, const hal_timer_t overflow) {
148
+  if (HAL_timer_initialized(timer_num)) {
149
+    timer_instance[timer_num]->setOverflow(overflow + 1, TICK_FORMAT); // Value decremented by setOverflow()
150
+    // wiki: "force all registers (Autoreload, prescaler, compare) to be taken into account"
151
+    // So, if the new overflow value is less than the count it will trigger a rollover interrupt.
152
+    if (overflow < timer_instance[timer_num]->getCount())  // Added 'if' here because reports say it won't boot without it
153
+      timer_instance[timer_num]->refresh();
154
+  }
160 155
 }
161 156
 
162 157
 #define HAL_timer_isr_prologue(TIMER_NUM)

+ 2
- 2
Marlin/src/HAL/HAL_STM32F1/timers.cpp Datei anzeigen

@@ -82,7 +82,7 @@ void HAL_timer_start(const uint8_t timer_num, const uint32_t frequency) {
82 82
       timer_set_prescaler(STEP_TIMER_DEV, (uint16_t)(STEPPER_TIMER_PRESCALE - 1));
83 83
       timer_set_reload(STEP_TIMER_DEV, 0xFFFF);
84 84
       timer_oc_set_mode(STEP_TIMER_DEV, STEP_TIMER_CHAN, TIMER_OC_MODE_FROZEN, TIMER_OC_NO_PRELOAD); // no output pin change
85
-      timer_set_compare(STEP_TIMER_DEV, STEP_TIMER_CHAN, _MIN(hal_timer_t(HAL_TIMER_TYPE_MAX), (STEPPER_TIMER_RATE / frequency)));
85
+      timer_set_compare(STEP_TIMER_DEV, STEP_TIMER_CHAN, _MIN(hal_timer_t(HAL_TIMER_TYPE_MAX), (STEPPER_TIMER_RATE) / frequency));
86 86
       timer_no_ARR_preload_ARPE(STEP_TIMER_DEV); // Need to be sure no preload on ARR register
87 87
       timer_attach_interrupt(STEP_TIMER_DEV, STEP_TIMER_CHAN, stepTC_Handler);
88 88
       nvic_irq_set_priority(irq_num, STEP_TIMER_IRQ_PRIO);
@@ -95,7 +95,7 @@ void HAL_timer_start(const uint8_t timer_num, const uint32_t frequency) {
95 95
       timer_set_count(TEMP_TIMER_DEV, 0);
96 96
       timer_set_prescaler(TEMP_TIMER_DEV, (uint16_t)(TEMP_TIMER_PRESCALE - 1));
97 97
       timer_set_reload(TEMP_TIMER_DEV, 0xFFFF);
98
-      timer_set_compare(TEMP_TIMER_DEV, TEMP_TIMER_CHAN, _MIN(hal_timer_t(HAL_TIMER_TYPE_MAX), ((F_CPU / TEMP_TIMER_PRESCALE) / frequency)));
98
+      timer_set_compare(TEMP_TIMER_DEV, TEMP_TIMER_CHAN, _MIN(hal_timer_t(HAL_TIMER_TYPE_MAX), (F_CPU) / (TEMP_TIMER_PRESCALE) / frequency));
99 99
       timer_attach_interrupt(TEMP_TIMER_DEV, TEMP_TIMER_CHAN, tempTC_Handler);
100 100
       nvic_irq_set_priority(irq_num, TEMP_TIMER_IRQ_PRIO);
101 101
       timer_generate_update(TEMP_TIMER_DEV);

+ 3
- 4
Marlin/src/HAL/HAL_STM32_F4_F7/HAL.h Datei anzeigen

@@ -24,16 +24,15 @@
24 24
 
25 25
 #define CPU_32_BIT
26 26
 
27
+#include "../../inc/MarlinConfigPre.h"
28
+
27 29
 #include "../shared/Marduino.h"
28 30
 #include "../shared/math_32bit.h"
29 31
 #include "../shared/HAL_SPI.h"
30 32
 
31 33
 #include "fastio.h"
32
-#include "watchdog.h"
33
-
34 34
 #include "timers.h"
35
-
36
-#include "../../inc/MarlinConfigPre.h"
35
+#include "watchdog.h"
37 36
 
38 37
 #include <stdint.h>
39 38
 

+ 2
- 2
Marlin/src/HAL/HAL_TEENSY31_32/timers.cpp Datei anzeigen

@@ -53,7 +53,7 @@ void HAL_timer_start(const uint8_t timer_num, const uint32_t frequency) {
53 53
       FTM0_SC = 0x00; // Set this to zero before changing the modulus
54 54
       FTM0_CNT = 0x0000; // Reset the count to zero
55 55
       FTM0_MOD = 0xFFFF; // max modulus = 65535
56
-      FTM0_C0V = FTM0_TIMER_RATE / frequency; // Initial FTM Channel 0 compare value
56
+      FTM0_C0V = (FTM0_TIMER_RATE) / frequency; // Initial FTM Channel 0 compare value
57 57
       FTM0_SC = (FTM_SC_CLKS(0b1) & FTM_SC_CLKS_MASK) | (FTM_SC_PS(FTM0_TIMER_PRESCALE_BITS) & FTM_SC_PS_MASK); // Bus clock 60MHz divided by prescaler 8
58 58
       FTM0_C0SC = FTM_CSC_CHIE | FTM_CSC_MSA | FTM_CSC_ELSA;
59 59
       break;
@@ -62,7 +62,7 @@ void HAL_timer_start(const uint8_t timer_num, const uint32_t frequency) {
62 62
       FTM1_SC = 0x00; // Set this to zero before changing the modulus
63 63
       FTM1_CNT = 0x0000; // Reset the count to zero
64 64
       FTM1_MOD = 0xFFFF; // max modulus = 65535
65
-      FTM1_C0V = FTM1_TIMER_RATE / frequency; // Initial FTM Channel 0 compare value 65535
65
+      FTM1_C0V = (FTM1_TIMER_RATE) / frequency; // Initial FTM Channel 0 compare value 65535
66 66
       FTM1_SC = (FTM_SC_CLKS(0b1) & FTM_SC_CLKS_MASK) | (FTM_SC_PS(FTM1_TIMER_PRESCALE_BITS) & FTM_SC_PS_MASK); // Bus clock 60MHz divided by prescaler 4
67 67
       FTM1_C0SC = FTM_CSC_CHIE | FTM_CSC_MSA | FTM_CSC_ELSA;
68 68
       break;

+ 2
- 2
Marlin/src/HAL/HAL_TEENSY35_36/timers.cpp Datei anzeigen

@@ -54,7 +54,7 @@ void HAL_timer_start(const uint8_t timer_num, const uint32_t frequency) {
54 54
       FTM0_SC = 0x00; // Set this to zero before changing the modulus
55 55
       FTM0_CNT = 0x0000; // Reset the count to zero
56 56
       FTM0_MOD = 0xFFFF; // max modulus = 65535
57
-      FTM0_C0V = FTM0_TIMER_RATE / frequency; // Initial FTM Channel 0 compare value
57
+      FTM0_C0V = (FTM0_TIMER_RATE) / frequency; // Initial FTM Channel 0 compare value
58 58
       FTM0_SC = (FTM_SC_CLKS(0b1) & FTM_SC_CLKS_MASK) | (FTM_SC_PS(FTM0_TIMER_PRESCALE_BITS) & FTM_SC_PS_MASK); // Bus clock 60MHz divided by prescaler 8
59 59
       FTM0_C0SC = FTM_CSC_CHIE | FTM_CSC_MSA | FTM_CSC_ELSA;
60 60
       break;
@@ -63,7 +63,7 @@ void HAL_timer_start(const uint8_t timer_num, const uint32_t frequency) {
63 63
       FTM1_SC = 0x00; // Set this to zero before changing the modulus
64 64
       FTM1_CNT = 0x0000; // Reset the count to zero
65 65
       FTM1_MOD = 0xFFFF; // max modulus = 65535
66
-      FTM1_C0V = FTM1_TIMER_RATE / frequency; // Initial FTM Channel 0 compare value 65535
66
+      FTM1_C0V = (FTM1_TIMER_RATE) / frequency; // Initial FTM Channel 0 compare value 65535
67 67
       FTM1_SC = (FTM_SC_CLKS(0b1) & FTM_SC_CLKS_MASK) | (FTM_SC_PS(FTM1_TIMER_PRESCALE_BITS) & FTM_SC_PS_MASK); // Bus clock 60MHz divided by prescaler 4
68 68
       FTM1_C0SC = FTM_CSC_CHIE | FTM_CSC_MSA | FTM_CSC_ELSA;
69 69
       break;

+ 1
- 1
Marlin/src/module/stepper.cpp Datei anzeigen

@@ -1537,7 +1537,7 @@ void Stepper::stepper_pulse_phase_isr() {
1537 1537
 uint32_t Stepper::stepper_block_phase_isr() {
1538 1538
 
1539 1539
   // If no queued movements, just wait 1ms for the next move
1540
-  uint32_t interval = (STEPPER_TIMER_RATE / 1000);
1540
+  uint32_t interval = (STEPPER_TIMER_RATE) / 1000;
1541 1541
 
1542 1542
   // If there is a current block
1543 1543
   if (current_block) {

+ 12
- 2
Marlin/src/module/temperature.cpp Datei anzeigen

@@ -2290,7 +2290,7 @@ void Temperature::readings_ready() {
2290 2290
 HAL_TEMP_TIMER_ISR() {
2291 2291
   HAL_timer_isr_prologue(TEMP_TIMER_NUM);
2292 2292
 
2293
-  Temperature::isr();
2293
+  Temperature::tick();
2294 2294
 
2295 2295
   HAL_timer_isr_epilogue(TEMP_TIMER_NUM);
2296 2296
 }
@@ -2320,11 +2320,21 @@ public:
2320 2320
   #endif
2321 2321
 };
2322 2322
 
2323
-void Temperature::isr() {
2323
+/**
2324
+ * Handle various ~1KHz tasks associated with temperature
2325
+ *  - Heater PWM (~1KHz with scaler)
2326
+ *  - LCD Button polling (~500Hz)
2327
+ *  - Start / Read one ADC sensor
2328
+ *  - Advance Babysteps
2329
+ *  - Endstop polling
2330
+ *  - Planner clean buffer
2331
+ */
2332
+void Temperature::tick() {
2324 2333
 
2325 2334
   static int8_t temp_count = -1;
2326 2335
   static ADCSensorState adc_sensor_state = StartupDelay;
2327 2336
   static uint8_t pwm_count = _BV(SOFT_PWM_SCALE);
2337
+
2328 2338
   // avoid multiple loads of pwm_count
2329 2339
   uint8_t pwm_count_tmp = pwm_count;
2330 2340
 

+ 3
- 5
Marlin/src/module/temperature.h Datei anzeigen

@@ -217,8 +217,8 @@ typedef struct { int16_t raw_min, raw_max; } raw_range_t;
217 217
 typedef struct { int16_t mintemp, maxtemp; } celsius_range_t;
218 218
 typedef struct { int16_t raw_min, raw_max, mintemp, maxtemp; } temp_range_t;
219 219
 
220
-#define THERMISTOR_ABS_ZERO_C           -273.15f       // bbbbrrrrr cold !
221
-#define THERMISTOR_RESISTANCE_NOMINAL_C 25.0f          // mmmmm comfortable
220
+#define THERMISTOR_ABS_ZERO_C           -273.15f  // bbbbrrrrr cold !
221
+#define THERMISTOR_RESISTANCE_NOMINAL_C 25.0f     // mmmmm comfortable
222 222
 
223 223
 #if HAS_USER_THERMISTORS
224 224
 
@@ -267,8 +267,6 @@ class Temperature {
267 267
 
268 268
   public:
269 269
 
270
-    static volatile bool in_temp_isr;
271
-
272 270
     #if HOTENDS
273 271
       #if ENABLED(TEMP_SENSOR_1_AS_REDUNDANT)
274 272
         #define HOTEND_TEMPS (HOTENDS + 1)
@@ -513,7 +511,7 @@ class Temperature {
513 511
      * Called from the Temperature ISR
514 512
      */
515 513
     static void readings_ready();
516
-    static void isr();
514
+    static void tick();
517 515
 
518 516
     /**
519 517
      * Call periodically to manage heaters

+ 2
- 4
buildroot/share/PlatformIO/boards/BigTree_Btt002.json Datei anzeigen

@@ -16,7 +16,7 @@
16 16
     ],
17 17
     "ldscript": "stm32f407xg.ld",
18 18
     "mcu": "stm32f407vet6",
19
-    "variant": "BIGTREE_GENERIC_STM32F407_5X"
19
+    "variant": "BIGTREE_TBD"
20 20
   },
21 21
   "debug": {
22 22
     "jlink_device": "STM32F407VE",
@@ -24,9 +24,7 @@
24 24
     "svd_path": "STM32F40x.svd"
25 25
   },
26 26
   "frameworks": [
27
-    "arduino",
28
-    "cmsis",
29
-    "stm32cube"
27
+    "arduino"
30 28
   ],
31 29
   "name": "STM32F407VE (192k RAM. 512k Flash)",
32 30
   "upload": {

+ 2
- 4
buildroot/share/PlatformIO/boards/BigTree_SKR_Pro.json Datei anzeigen

@@ -16,7 +16,7 @@
16 16
     ],
17 17
     "ldscript": "stm32f407xg.ld",
18 18
     "mcu": "stm32f407zgt6",
19
-    "variant": "BIGTREE_GENERIC_STM32F407_5X"
19
+    "variant": "BIGTREE_SKR_PRO_1v1"
20 20
   },
21 21
   "debug": {
22 22
     "jlink_device": "STM32F407ZG",
@@ -24,9 +24,7 @@
24 24
     "svd_path": "STM32F40x.svd"
25 25
   },
26 26
   "frameworks": [
27
-    "arduino",
28
-    "cmsis",
29
-    "stm32cube"
27
+    "arduino"
30 28
   ],
31 29
   "name": "STM32F407ZG (192k RAM. 1024k Flash)",
32 30
   "upload": {

+ 0
- 29
buildroot/share/PlatformIO/scripts/black_stm32f407vet6.py Datei anzeigen

@@ -1,29 +0,0 @@
1
-import os,shutil
2
-from SCons.Script import DefaultEnvironment
3
-from platformio import util
4
-
5
-env = DefaultEnvironment()
6
-platform = env.PioPlatform()
7
-board = env.BoardConfig()
8
-
9
-FRAMEWORK_DIR = platform.get_package_dir("framework-arduinoststm32")
10
-CMSIS_DIR = os.path.join(FRAMEWORK_DIR, "CMSIS", "CMSIS")
11
-assert os.path.isdir(FRAMEWORK_DIR)
12
-assert os.path.isdir(CMSIS_DIR)
13
-assert os.path.isdir("buildroot/share/PlatformIO/variants")
14
-
15
-mcu_type = board.get("build.mcu")[:-2]
16
-variant = board.get("build.variant")
17
-series = mcu_type[:7].upper() + "xx"
18
-variant_dir = os.path.join(FRAMEWORK_DIR, "variants", variant)
19
-
20
-source_dir = os.path.join("buildroot/share/PlatformIO/variants", variant)
21
-assert os.path.isdir(source_dir)
22
-
23
-if not os.path.isdir(variant_dir):
24
-    os.mkdir(variant_dir)
25
-
26
-for file_name in os.listdir(source_dir):
27
-    full_file_name = os.path.join(source_dir, file_name)
28
-    if os.path.isfile(full_file_name):
29
-        shutil.copy(full_file_name, variant_dir)

+ 0
- 2
buildroot/share/PlatformIO/scripts/generic_create_variant.py Datei anzeigen

@@ -7,9 +7,7 @@ platform = env.PioPlatform()
7 7
 board = env.BoardConfig()
8 8
 
9 9
 FRAMEWORK_DIR = platform.get_package_dir("framework-arduinoststm32")
10
-CMSIS_DIR = os.path.join(FRAMEWORK_DIR, "CMSIS", "CMSIS")
11 10
 assert os.path.isdir(FRAMEWORK_DIR)
12
-assert os.path.isdir(CMSIS_DIR)
13 11
 assert os.path.isdir("buildroot/share/PlatformIO/variants")
14 12
 
15 13
 mcu_type = board.get("build.mcu")[:-2]

buildroot/share/PlatformIO/variants/BIGTREE_GENERIC_STM32F407_5X/PeripheralPins.c → buildroot/share/PlatformIO/variants/BIGTREE_SKR_PRO_1v1/PeripheralPins.c Datei anzeigen

@@ -41,56 +41,32 @@
41 41
 
42 42
 #ifdef HAL_ADC_MODULE_ENABLED
43 43
 const PinMap PinMap_ADC[] = {
44
-  {PA_0,  ADC1,  STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 0, 0)}, // ADC1_IN0
45
-  //{PA_0,  ADC2,  STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 0, 0)}, // ADC2_IN0
46
-  //{PA_0,  ADC3,  STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 0, 0)}, // ADC3_IN0
47
-  {PA_1,  ADC1,  STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 1, 0)}, // ADC1_IN1
48
-  //{PA_1,  ADC2,  STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 1, 0)}, // ADC2_IN1
49
-  //{PA_1,  ADC3,  STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 1, 0)}, // ADC3_IN1
50
-  {PA_2,  ADC1,  STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 2, 0)}, // ADC1_IN2
51
-  //{PA_2,  ADC2,  STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 2, 0)}, // ADC2_IN2
52
-  //{PA_2,  ADC3,  STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 2, 0)}, // ADC3_IN2
53
-  {PA_3,  ADC1,  STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 3, 0)}, // ADC1_IN3
54
-  //{PA_3,  ADC2,  STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 3, 0)}, // ADC2_IN3
55
-  //{PA_3,  ADC3,  STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 3, 0)}, // ADC3_IN3
56
-  {PA_4,  ADC1,  STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 4, 0)}, // ADC1_IN4
57
-  //{PA_4,  ADC2,  STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 4, 0)}, // ADC2_IN4
58
-  {PA_5,  ADC1,  STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 5, 0)}, // ADC1_IN5
59
-  //{PA_5,  ADC2,  STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 5, 0)}, // ADC2_IN5
60
-  {PA_6,  ADC1,  STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 6, 0)}, // ADC1_IN6
61
-  //{PA_6,  ADC2,  STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 6, 0)}, // ADC2_IN6
62
-  {PA_7,  ADC1,  STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 7, 0)}, // ADC1_IN7
63
-  //{PA_7,  ADC2,  STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 7, 0)}, // ADC2_IN7
64
-  {PB_0,  ADC1,  STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 8, 0)}, // ADC1_IN8
65
-  //{PB_0,  ADC2,  STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 8, 0)}, // ADC2_IN8
66
-  {PB_1,  ADC1,  STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 9, 0)}, // ADC1_IN9
67
-  //{PB_1,  ADC2,  STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 9, 0)}, // ADC2_IN9
68
-  {PC_0,  ADC1,  STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 10, 0)}, // ADC1_IN10
69
-  //{PC_0,  ADC2,  STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 10, 0)}, // ADC2_IN10
70
-  //{PC_0,  ADC3,  STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 10, 0)}, // ADC3_IN10
71
-  {PC_1,  ADC1,  STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 11, 0)}, // ADC1_IN11
72
-  //{PC_1,  ADC2,  STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 11, 0)}, // ADC2_IN11
73
-  //{PC_1,  ADC3,  STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 11, 0)}, // ADC3_IN11
74
-  {PC_2,  ADC1,  STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 12, 0)}, // ADC1_IN12
75
-  //{PC_2,  ADC2,  STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 12, 0)}, // ADC2_IN12
76
-  //{PC_2,  ADC3,  STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 12, 0)}, // ADC3_IN12
77
-  {PC_3,  ADC1,  STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 13, 0)}, // ADC1_IN13
78
-  //{PC_3,  ADC2,  STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 13, 0)}, // ADC2_IN13
79
-  //{PC_3,  ADC3,  STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 13, 0)}, // ADC3_IN13
80
-  {PC_4,  ADC1,  STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 14, 0)}, // ADC1_IN14
81
-  //{PC_4,  ADC2,  STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 14, 0)}, // ADC2_IN14
82
-  {PC_5,  ADC1,  STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 15, 0)}, // ADC1_IN15
83
-  //{PC_5,  ADC2,  STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 15, 0)}, // ADC2_IN15
44
+  {PA_0,  ADC1,  STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 0, 0)}, // ADC1_IN0      E0_DIR
45
+  {PA_1,  ADC1,  STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 1, 0)}, // ADC1_IN1      BLTOUCH_2
46
+  {PA_2,  ADC1,  STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 2, 0)}, // ADC1_IN2      BLTOUCH_4
47
+  {PA_3,  ADC1,  STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 3, 0)}, // ADC1_IN3      E1_EN
48
+  {PA_4,  ADC1,  STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 4, 0)}, // ADC1_IN4      TF_SS
49
+  {PA_5,  ADC1,  STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 5, 0)}, // ADC1_IN5      TF_SCLK
50
+  {PA_6,  ADC1,  STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 6, 0)}, // ADC1_IN6      TF_MISO
51
+  {PA_7,  ADC1,  STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 7, 0)}, // ADC1_IN7      LED
52
+  {PB_0,  ADC1,  STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 8, 0)}, // ADC1_IN8      HEATER2
53
+  {PB_1,  ADC1,  STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 9, 0)}, // ADC1_IN9      HEATER0
54
+  {PC_0,  ADC1,  STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 10, 0)}, // ADC1_IN10    Z_EN
55
+  {PC_1,  ADC1,  STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 11, 0)}, // ADC1_IN11    EXP_14
56
+  {PC_2,  ADC1,  STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 12, 0)}, // ADC1_IN12    Z_DIR
57
+  {PC_3,  ADC1,  STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 13, 0)}, // ADC1_IN13    E0_EN
58
+  {PC_4,  ADC1,  STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 14, 0)}, // ADC1_IN14    EXP_8
59
+  {PC_5,  ADC1,  STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 15, 0)}, // ADC1_IN15    EXP_7
84 60
 
85 61
   #if STM32F4X_PIN_NUM >= 144  //144 pins mcu, 114 gpio, 24 ADC
86
-    {PF_3,  ADC3,  STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 9, 0)}, // ADC3_IN9
87
-    {PF_4,  ADC3,  STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 14, 0)}, // ADC3_IN14
88
-    {PF_5,  ADC3,  STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 15, 0)}, // ADC3_IN15
89
-    {PF_6,  ADC3,  STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 4, 0)}, // ADC3_IN4
90
-    {PF_7,  ADC3,  STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 5, 0)}, // ADC3_IN5
91
-    {PF_8,  ADC3,  STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 6, 0)}, // ADC3_IN6
92
-    {PF_9,  ADC3,  STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 7, 0)}, // ADC3_IN7
93
-    {PF_10, ADC3,  STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 8, 0)}, // ADC3_IN8
62
+    {PF_3,  ADC3,  STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 9, 0)}, // ADC3_IN9    TH_0
63
+    {PF_4,  ADC3,  STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 14, 0)}, // ADC3_IN14  TH_1
64
+    {PF_5,  ADC3,  STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 15, 0)}, // ADC3_IN15  TH_2
65
+    {PF_6,  ADC3,  STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 4, 0)}, // ADC3_IN4    TH_3
66
+    {PF_7,  ADC3,  STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 5, 0)}, // ADC3_IN5    EXP_13
67
+    {PF_8,  ADC3,  STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 6, 0)}, // ADC3_IN6    EXP_3
68
+    {PF_9,  ADC3,  STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 7, 0)}, // ADC3_IN7    EXP_6
69
+    {PF_10, ADC3,  STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 8, 0)}, // ADC3_IN8    EXP_5
94 70
   #endif
95 71
   {NC,    NP,    0}
96 72
 };
@@ -138,79 +114,81 @@ const PinMap PinMap_I2C_SCL[] = {
138 114
 
139 115
 #ifdef HAL_TIM_MODULE_ENABLED
140 116
 const PinMap PinMap_PWM[] = {
141
-  {PA_0,  TIM2,   STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM2, 1, 0)}, // TIM2_CH1
117
+  {PB_1,  TIM3,   STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM3, 4, 0)}, // TIM3_CH4    HEATER0
118
+  {PD_14, TIM4,   STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM4, 3, 0)}, // TIM4_CH3    HEATER1
119
+  {PB_0,  TIM3,   STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM3, 3, 0)}, // TIM3_CH3    HEATER2
120
+  {PD_12, TIM4,   STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM4, 1, 0)}, // TIM4_CH1    BED
121
+  {PC_8,  TIM3,   STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM3, 3, 0)}, // TIM3_CH3    FAN0
122
+  {PE_5,  TIM9,   STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF3_TIM9, 1, 0)}, // TIM9_CH1    FAN1
123
+  {PE_6,  TIM9,   STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF3_TIM9, 2, 0)}, // TIM9_CH2    FAN2
124
+  {PC_9,  TIM8,   STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF3_TIM8, 4, 0)}, // TIM8_CH4    EXTENSION1-4
125
+  
126
+  //probably unused on SKR-Pro. confirmation needed, please.
127
+  //{PA_0,  TIM2,   STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM2, 1, 0)}, // TIM2_CH1
142 128
   //{PA_0,  TIM5,   STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM5, 1, 0)}, // TIM5_CH1
143
-  {PA_1,  TIM2,   STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM2, 2, 0)}, // TIM2_CH2
129
+  //{PA_1,  TIM2,   STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM2, 2, 0)}, // TIM2_CH2 is bltouch analog?
144 130
   //{PA_1,  TIM5,   STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM5, 2, 0)}, // TIM5_CH2
145
-  {PA_2,  TIM2,   STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM2, 3, 0)}, // TIM2_CH3
131
+  //{PA_2,  TIM2,   STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM2, 3, 0)}, // TIM2_CH3 is bltouch analog?
146 132
   //{PA_2,  TIM5,   STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM5, 3, 0)}, // TIM5_CH3
147 133
   //{PA_2,  TIM9,   STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF3_TIM9, 1, 0)}, // TIM9_CH1
148
-  {PA_3,  TIM2,   STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM2, 4, 0)}, // TIM2_CH4
134
+  //{PA_3,  TIM2,   STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM2, 4, 0)}, // TIM2_CH4
149 135
   //{PA_3,  TIM5,   STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM5, 4, 0)}, // TIM5_CH4
150 136
   //{PA_3,  TIM9,   STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF3_TIM9, 2, 0)}, // TIM9_CH2
151
-  {PA_5,  TIM2,   STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM2, 1, 0)}, // TIM2_CH1
137
+  //{PA_5,  TIM2,   STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM2, 1, 0)}, // TIM2_CH1
152 138
   //{PA_5,  TIM8,   STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF3_TIM8, 1, 1)}, // TIM8_CH1N
153
-  {PA_6,  TIM3,   STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM3, 1, 0)}, // TIM3_CH1
139
+  //{PA_6,  TIM3,   STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM3, 1, 0)}, // TIM3_CH1
154 140
   //{PA_6,  TIM13,  STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF9_TIM13, 1, 0)}, // TIM13_CH1
155 141
   //{PA_7,  TIM1,   STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM1, 1, 1)}, // TIM1_CH1N
156
-  {PA_7,  TIM3,   STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM3, 2, 0)}, // TIM3_CH2
142
+  //{PA_7,  TIM3,   STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM3, 2, 0)}, // TIM3_CH2
157 143
   //{PA_7,  TIM8,   STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF3_TIM8, 1, 1)}, // TIM8_CH1N
158 144
   //{PA_7,  TIM14,  STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF9_TIM14, 1, 0)}, // TIM14_CH1
159
-  {PA_8,  TIM1,   STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM1, 1, 0)}, // TIM1_CH1
160
-  {PA_9,  TIM1,   STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM1, 2, 0)}, // TIM1_CH2
161
-  {PA_10, TIM1,   STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM1, 3, 0)}, // TIM1_CH3
162
-  {PA_11, TIM1,   STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM1, 4, 0)}, // TIM1_CH4
145
+  //{PA_8,  TIM1,   STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM1, 1, 0)}, // TIM1_CH1
146
+  //{PA_9,  TIM1,   STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM1, 2, 0)}, // TIM1_CH2
147
+  //{PA_10, TIM1,   STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM1, 3, 0)}, // TIM1_CH3
148
+  //{PA_11, TIM1,   STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM1, 4, 0)}, // TIM1_CH4
163 149
   //{PA_15, TIM2,   STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM2, 1, 0)}, // TIM2_CH1
164 150
   //{PB_0,  TIM1,   STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM1, 2, 1)}, // TIM1_CH2N
165
-  {PB_0,  TIM3,   STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM3, 3, 0)}, // TIM3_CH3
166 151
   //{PB_0,  TIM8,   STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF3_TIM8, 2, 1)}, // TIM8_CH2N
167 152
   //{PB_1,  TIM1,   STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM1, 3, 1)}, // TIM1_CH3N
168
-  {PB_1,  TIM3,   STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM3, 4, 0)}, // TIM3_CH4
169 153
   //{PB_1,  TIM8,   STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF3_TIM8, 3, 1)}, // TIM8_CH3N
170 154
   //{PB_3,  TIM2,   STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM2, 2, 0)}, // TIM2_CH2
171
-  {PB_4,  TIM3,   STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM3, 1, 0)}, // TIM3_CH1
172
-  {PB_5,  TIM3,   STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM3, 2, 0)}, // TIM3_CH2
155
+  //{PB_4,  TIM3,   STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM3, 1, 0)}, // TIM3_CH1
156
+  //{PB_5,  TIM3,   STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM3, 2, 0)}, // TIM3_CH2
173 157
   //{PB_6,  TIM4,   STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM4, 1, 0)}, // TIM4_CH1
174 158
   //{PB_7,  TIM4,   STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM4, 2, 0)}, // TIM4_CH2
175 159
   //{PB_8,  TIM4,   STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM4, 3, 0)}, // TIM4_CH3
176
-  {PB_8,  TIM10,  STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF3_TIM10, 1, 0)}, // TIM10_CH1
160
+  //{PB_8,  TIM10,  STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF3_TIM10, 1, 0)}, // TIM10_CH1
177 161
   //{PB_9,  TIM4,   STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM4, 4, 0)}, // TIM4_CH4
178
-  {PB_9,  TIM11,  STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF3_TIM11, 1, 0)}, // TIM11_CH1
179
-  {PB_10, TIM2,   STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM2, 3, 0)}, // TIM2_CH3
180
-  {PB_11, TIM2,   STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM2, 4, 0)}, // TIM2_CH4
181
-  {PB_13, TIM1,   STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM1, 1, 1)}, // TIM1_CH1N
182
-  {PB_14, TIM1,   STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM1, 2, 1)}, // TIM1_CH2N
183
-  {PB_14, TIM8,   STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF3_TIM8, 2, 1)}, // TIM8_CH2N
184
-  {PB_14, TIM12,  STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF9_TIM12, 1, 0)}, // TIM12_CH1
185
-  {PB_15, TIM1,   STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM1, 3, 1)}, // TIM1_CH3N
186
-  {PB_15, TIM8,   STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF3_TIM8, 3, 1)}, // TIM8_CH3N
187
-  {PB_15, TIM12,  STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF9_TIM12, 2, 0)}, // TIM12_CH2
188
-  {PC_6,  TIM3,   STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM3, 1, 0)}, // TIM3_CH1
189
-  {PC_6,  TIM8,   STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF3_TIM8, 1, 0)}, // TIM8_CH1
190
-  {PC_7,  TIM3,   STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM3, 2, 0)}, // TIM3_CH2
191
-  {PC_7,  TIM8,   STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF3_TIM8, 2, 0)}, // TIM8_CH2
192
-  {PC_8,  TIM3,   STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM3, 3, 0)}, // TIM3_CH3
193
-  {PC_8,  TIM8,   STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF3_TIM8, 3, 0)}, // TIM8_CH3
162
+  //{PB_9,  TIM11,  STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF3_TIM11, 1, 0)}, // TIM11_CH1
163
+  //{PB_10, TIM2,   STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM2, 3, 0)}, // TIM2_CH3
164
+  //{PB_11, TIM2,   STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM2, 4, 0)}, // TIM2_CH4
165
+  //{PB_13, TIM1,   STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM1, 1, 1)}, // TIM1_CH1N
166
+  //{PB_14, TIM1,   STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM1, 2, 1)}, // TIM1_CH2N
167
+  //{PB_14, TIM8,   STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF3_TIM8, 2, 1)}, // TIM8_CH2N
168
+  //{PB_14, TIM12,  STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF9_TIM12, 1, 0)}, // TIM12_CH1
169
+  //{PB_15, TIM1,   STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM1, 3, 1)}, // TIM1_CH3N
170
+  //{PB_15, TIM8,   STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF3_TIM8, 3, 1)}, // TIM8_CH3N
171
+  //{PB_15, TIM12,  STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF9_TIM12, 2, 0)}, // TIM12_CH2
172
+  //{PC_6,  TIM3,   STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM3, 1, 0)}, // TIM3_CH1
173
+  //{PC_6,  TIM8,   STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF3_TIM8, 1, 0)}, // TIM8_CH1
174
+  //{PC_7,  TIM3,   STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM3, 2, 0)}, // TIM3_CH2
175
+  //{PC_7,  TIM8,   STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF3_TIM8, 2, 0)}, // TIM8_CH2
176
+  //{PC_8,  TIM8,   STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF3_TIM8, 3, 0)}, // TIM8_CH3
194 177
   //{PC_9,  TIM3,   STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM3, 4, 0)}, // TIM3_CH4
195
-  //{PC_9,  TIM8,   STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF3_TIM8, 4, 0)}, // TIM8_CH4
196
-  {PD_12, TIM4,   STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM4, 1, 0)}, // TIM4_CH1
197
-  {PD_13, TIM4,   STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM4, 2, 0)}, // TIM4_CH2
198
-  {PD_14, TIM4,   STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM4, 3, 0)}, // TIM4_CH3
199
-  {PD_15, TIM4,   STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM4, 4, 0)}, // TIM4_CH4
200
-  {PE_5,  TIM9,   STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF3_TIM9, 1, 0)}, // TIM9_CH1
201
-  {PE_6,  TIM9,   STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF3_TIM9, 2, 0)}, // TIM9_CH2
202
-  {PE_8,  TIM1,   STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM1, 1, 1)}, // TIM1_CH1N
203
-  {PE_9,  TIM1,   STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM1, 1, 0)}, // TIM1_CH1
204
-  {PE_10, TIM1,   STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM1, 2, 1)}, // TIM1_CH2N
205
-  {PE_11, TIM1,   STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM1, 2, 0)}, // TIM1_CH2
206
-  {PE_12, TIM1,   STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM1, 3, 1)}, // TIM1_CH3N
207
-  {PE_13, TIM1,   STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM1, 3, 0)}, // TIM1_CH3
208
-  {PE_14, TIM1,   STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM1, 4, 0)}, // TIM1_CH4
178
+  //{PD_13, TIM4,   STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM4, 2, 0)}, // TIM4_CH2
179
+  //{PD_15, TIM4,   STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM4, 4, 0)}, // TIM4_CH4
180
+  //{PE_8,  TIM1,   STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM1, 1, 1)}, // TIM1_CH1N
181
+  //{PE_9,  TIM1,   STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM1, 1, 0)}, // TIM1_CH1
182
+  //{PE_10, TIM1,   STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM1, 2, 1)}, // TIM1_CH2N
183
+  //{PE_11, TIM1,   STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM1, 2, 0)}, // TIM1_CH2
184
+  //{PE_12, TIM1,   STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM1, 3, 1)}, // TIM1_CH3N
185
+  //{PE_13, TIM1,   STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM1, 3, 0)}, // TIM1_CH3
186
+  //{PE_14, TIM1,   STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM1, 4, 0)}, // TIM1_CH4
209 187
   #if STM32F4X_PIN_NUM >= 144  //144 pins mcu, 114 gpio
210
-    {PF_6,  TIM10,  STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF3_TIM10, 1, 0)}, // TIM10_CH1
211
-    {PF_7,  TIM11,  STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF3_TIM11, 1, 0)}, // TIM11_CH1
212
-    {PF_8,  TIM13,  STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF9_TIM13, 1, 0)}, // TIM13_CH1
213
-    {PF_9,  TIM14,  STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF9_TIM14, 1, 0)}, // TIM14_CH1
188
+    //{PF_6,  TIM10,  STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF3_TIM10, 1, 0)}, // TIM10_CH1
189
+    //{PF_7,  TIM11,  STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF3_TIM11, 1, 0)}, // TIM11_CH1
190
+    //{PF_8,  TIM13,  STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF9_TIM13, 1, 0)}, // TIM13_CH1
191
+    //{PF_9,  TIM14,  STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF9_TIM14, 1, 0)}, // TIM14_CH1
214 192
   #endif
215 193
   {NC,    NP,    0}
216 194
 };
@@ -236,9 +214,7 @@ const PinMap PinMap_UART_TX[] = {
236 214
   #endif
237 215
   {NC,    NP,    0}
238 216
 };
239
-#endif
240 217
 
241
-#ifdef HAL_UART_MODULE_ENABLED
242 218
 const PinMap PinMap_UART_RX[] = {
243 219
   {PA_1,  UART4,   STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF8_UART4)},
244 220
   {PA_3,  USART2,  STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_USART2)},
@@ -256,9 +232,7 @@ const PinMap PinMap_UART_RX[] = {
256 232
   #endif
257 233
   {NC,    NP,    0}
258 234
 };
259
-#endif
260 235
 
261
-#ifdef HAL_UART_MODULE_ENABLED
262 236
 const PinMap PinMap_UART_RTS[] = {
263 237
   {PA_1,  USART2,  STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_USART2)},
264 238
   {PA_12, USART1,  STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_USART1)},
@@ -271,9 +245,7 @@ const PinMap PinMap_UART_RTS[] = {
271 245
   #endif
272 246
   {NC,    NP,    0}
273 247
 };
274
-#endif
275 248
 
276
-#ifdef HAL_UART_MODULE_ENABLED
277 249
 const PinMap PinMap_UART_CTS[] = {
278 250
   {PA_0,  USART2,  STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_USART2)},
279 251
   {PA_11, USART1,  STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_USART1)},
@@ -292,48 +264,30 @@ const PinMap PinMap_UART_CTS[] = {
292 264
 
293 265
 #ifdef HAL_SPI_MODULE_ENABLED
294 266
 const PinMap PinMap_SPI_MOSI[] = {
295
-  {PA_7,  SPI1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF5_SPI1)},
296
-  {PB_5,  SPI1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF5_SPI1)},
297
-  {PB_5,  SPI3, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF6_SPI3)},
267
+  {PB_5,  SPI1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_NOPULL, GPIO_AF5_SPI1)},
298 268
   {PB_15, SPI2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF5_SPI2)},
299
-  {PC_3,  SPI2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF5_SPI2)},
300 269
   {PC_12, SPI3, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF6_SPI3)},
301 270
   {NC,    NP,    0}
302 271
 };
303
-#endif
304 272
 
305
-#ifdef HAL_SPI_MODULE_ENABLED
306 273
 const PinMap PinMap_SPI_MISO[] = {
307
-  {PA_6,  SPI1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF5_SPI1)},
308
-  {PB_4,  SPI1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF5_SPI1)},
309
-  {PB_4,  SPI3, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF6_SPI3)},
274
+  {PA_6,  SPI1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_NOPULL, GPIO_AF5_SPI1)},
310 275
   {PB_14, SPI2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF5_SPI2)},
311
-  {PC_2,  SPI2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF5_SPI2)},
312 276
   {PC_11, SPI3, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF6_SPI3)},
313 277
   {NC,    NP,    0}
314 278
 };
315
-#endif
316 279
 
317
-#ifdef HAL_SPI_MODULE_ENABLED
318 280
 const PinMap PinMap_SPI_SCLK[] = {
319
-  {PA_5,  SPI1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF5_SPI1)},
320
-  {PB_3,  SPI1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF5_SPI1)},
321
-  {PB_3,  SPI3, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF6_SPI3)},
322
-  {PB_10, SPI2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF5_SPI2)},
281
+  {PA_5,  SPI1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_NOPULL, GPIO_AF5_SPI1)},
323 282
   {PB_13, SPI2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF5_SPI2)},
324 283
   {PC_10, SPI3, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF6_SPI3)},
325 284
   {NC,    NP,    0}
326 285
 };
327
-#endif
328 286
 
329
-#ifdef HAL_SPI_MODULE_ENABLED
330 287
 const PinMap PinMap_SPI_SSEL[] = {
331
-  {PA_4,  SPI1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF5_SPI1)},
332
-  {PA_4,  SPI3, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF6_SPI3)},
333
-  {PA_15, SPI1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF5_SPI1)},
334
-  {PA_15, SPI3, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF6_SPI3)},
335
-  {PB_9,  SPI2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF5_SPI2)},
288
+  {PA_4,  SPI1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_NOPULL, GPIO_AF5_SPI1)},
336 289
   {PB_12, SPI2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF5_SPI2)},
290
+  {PA_15, SPI3, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF6_SPI3)},
337 291
   {NC,    NP,    0}
338 292
 };
339 293
 #endif
@@ -341,91 +295,40 @@ const PinMap PinMap_SPI_SSEL[] = {
341 295
 //*** CAN ***
342 296
 
343 297
 #ifdef HAL_CAN_MODULE_ENABLED
344
-const PinMap PinMap_CAN_RD[] = {
345
-  {PA_11, CAN1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_NOPULL, GPIO_AF9_CAN1)},
346
-  {PB_5,  CAN2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_NOPULL, GPIO_AF9_CAN2)},
347
-  {PB_8,  CAN1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_NOPULL, GPIO_AF9_CAN1)},
348
-  {PB_12, CAN2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_NOPULL, GPIO_AF9_CAN2)},
349
-  {PD_0,  CAN1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_NOPULL, GPIO_AF9_CAN1)},
350
-  {NC,    NP,    0}
351
-};
352
-#endif
353
-
354
-#ifdef HAL_CAN_MODULE_ENABLED
355
-const PinMap PinMap_CAN_TD[] = {
356
-  {PA_12, CAN1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_NOPULL, GPIO_AF9_CAN1)},
357
-  {PB_6,  CAN2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_NOPULL, GPIO_AF9_CAN2)},
358
-  {PB_9,  CAN1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_NOPULL, GPIO_AF9_CAN1)},
359
-  {PB_13, CAN2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_NOPULL, GPIO_AF9_CAN2)},
360
-  {PD_1,  CAN1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_NOPULL, GPIO_AF9_CAN1)},
361
-  {NC,    NP,    0}
362
-};
298
+#error "CAN bus isn't available on this board. Driver should be disabled."
363 299
 #endif
364 300
 
365 301
 //*** ETHERNET ***
366
-
367 302
 #ifdef HAL_ETH_MODULE_ENABLED
368
-const PinMap PinMap_Ethernet[] = {
369
-  {PA_0,  ETH, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF11_ETH)}, // ETH_CRS
370
-  {PA_1,  ETH, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF11_ETH)}, // ETH_REF_CLK|ETH_RX_CLK
371
-  {PA_2,  ETH, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF11_ETH)}, // ETH_MDIO
372
-  {PA_3,  ETH, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF11_ETH)}, // ETH_COL
373
-  {PA_7,  ETH, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF11_ETH)}, // ETH_CRS_DV|ETH_RX_DV
374
-  {PB_0,  ETH, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF11_ETH)}, // ETH_RXD2
375
-  {PB_1,  ETH, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF11_ETH)}, // ETH_RXD3
376
-  {PB_5,  ETH, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF11_ETH)}, // ETH_PPS_OUT
377
-  {PB_8,  ETH, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF11_ETH)}, // ETH_TXD3
378
-  {PB_10, ETH, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF11_ETH)}, // ETH_RX_ER
379
-  {PB_11, ETH, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF11_ETH)}, // ETH_TX_EN
380
-  {PB_12, ETH, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF11_ETH)}, // ETH_TXD0
381
-  {PB_13, ETH, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF11_ETH)}, // ETH_TXD1
382
-  {PC_1,  ETH, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF11_ETH)}, // ETH_MDC
383
-  {PC_2,  ETH, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF11_ETH)}, // ETH_TXD2
384
-  {PC_3,  ETH, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF11_ETH)}, // ETH_TX_CLK
385
-  {PC_4,  ETH, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF11_ETH)}, // ETH_RXD0
386
-  {PC_5,  ETH, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF11_ETH)}, // ETH_RXD1
387
-  {PE_2,  ETH, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF11_ETH)}, // ETH_TXD3
388
-  #if STM32F4X_PIN_NUM >= 144  //144 pins mcu, 114 gpio
389
-    {PG_8,  ETH, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF11_ETH)}, // ETH_PPS_OUT
390
-    {PG_11, ETH, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF11_ETH)}, // ETH_TX_EN
391
-    {PG_13, ETH, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF11_ETH)}, // ETH_TXD0
392
-    {PG_14, ETH, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF11_ETH)}, // ETH_TXD1
393
-  #endif
394
-  {NC,    NP,    0}
395
-};
303
+#error "Ethernet port isn't available on this board. Driver should be disabled."
396 304
 #endif
397 305
 
398 306
 //*** No QUADSPI ***
399 307
 
400 308
 //*** USB ***
401
-
402 309
 #ifdef HAL_PCD_MODULE_ENABLED
403 310
 const PinMap PinMap_USB_OTG_FS[] = {
404
-  //{PA_8,  USB_OTG_FS, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF10_OTG_FS)}, // USB_OTG_FS_SOF
405
-  //{PA_9,  USB_OTG_FS, STM_PIN_DATA(STM_MODE_INPUT, GPIO_NOPULL, GPIO_AF_NONE)}, // USB_OTG_FS_VBUS
406
-  //{PA_10, USB_OTG_FS, STM_PIN_DATA(STM_MODE_AF_OD, GPIO_PULLUP, GPIO_AF10_OTG_FS)}, // USB_OTG_FS_ID
311
+  //{PA_8,  USB_OTG_FS, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF10_OTG_FS)}, // USB_OTG_FS_SOF   used by LCD
312
+  //{PA_9,  USB_OTG_FS, STM_PIN_DATA(STM_MODE_INPUT, GPIO_NOPULL, GPIO_AF_NONE)},     // USB_OTG_FS_VBUS  available on wifi port, if empty
313
+  //{PA_10, USB_OTG_FS, STM_PIN_DATA(STM_MODE_AF_OD, GPIO_PULLUP, GPIO_AF10_OTG_FS)}, // USB_OTG_FS_ID    available on UART1_RX if not used
407 314
   {PA_11, USB_OTG_FS, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF10_OTG_FS)}, // USB_OTG_FS_DM
408 315
   {PA_12, USB_OTG_FS, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF10_OTG_FS)}, // USB_OTG_FS_DP
409 316
   {NC,    NP,    0}
410 317
 };
411
-#endif
412 318
 
413
-#ifdef HAL_PCD_MODULE_ENABLED
414
-const PinMap PinMap_USB_OTG_HS[] = {
319
+const PinMap PinMap_USB_OTG_HS[] = { /*
415 320
   #ifdef USE_USB_HS_IN_FS
416
-    {PA_4,  USB_OTG_HS, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF12_OTG_HS_FS)}, // USB_OTG_HS_SOF
417 321
     {PB_12, USB_OTG_HS, STM_PIN_DATA(STM_MODE_AF_OD, GPIO_PULLUP, GPIO_AF12_OTG_HS_FS)}, // USB_OTG_HS_ID
418 322
     {PB_13, USB_OTG_HS, STM_PIN_DATA(STM_MODE_INPUT, GPIO_NOPULL, GPIO_AF_NONE)}, // USB_OTG_HS_VBUS
419 323
     {PB_14, USB_OTG_HS, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF12_OTG_HS_FS)}, // USB_OTG_HS_DM
420 324
     {PB_15, USB_OTG_HS, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF12_OTG_HS_FS)}, // USB_OTG_HS_DP
421 325
   #else
326
+  #error "USB in HS mode isn't supported by the board"
422 327
     {PA_3,  USB_OTG_HS, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF10_OTG_HS)}, // USB_OTG_HS_ULPI_D0
423
-    {PA_5,  USB_OTG_HS, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF10_OTG_HS)}, // USB_OTG_HS_ULPI_CK
424 328
     {PB_0,  USB_OTG_HS, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF10_OTG_HS)}, // USB_OTG_HS_ULPI_D1
425 329
     {PB_1,  USB_OTG_HS, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF10_OTG_HS)}, // USB_OTG_HS_ULPI_D2
426 330
     {PB_5,  USB_OTG_HS, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF10_OTG_HS)}, // USB_OTG_HS_ULPI_D7
427 331
     {PB_10, USB_OTG_HS, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF10_OTG_HS)}, // USB_OTG_HS_ULPI_D3
428
-    {PB_11, USB_OTG_HS, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF10_OTG_HS)}, // USB_OTG_HS_ULPI_D4
429 332
     {PB_12, USB_OTG_HS, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF10_OTG_HS)}, // USB_OTG_HS_ULPI_D5
430 333
     {PB_13, USB_OTG_HS, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF10_OTG_HS)}, // USB_OTG_HS_ULPI_D6
431 334
     {PC_0,  USB_OTG_HS, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF10_OTG_HS)}, // USB_OTG_HS_ULPI_STP

buildroot/share/PlatformIO/variants/BIGTREE_GENERIC_STM32F407_5X/PinNamesVar.h → buildroot/share/PlatformIO/variants/BIGTREE_SKR_PRO_1v1/PinNamesVar.h Datei anzeigen


+ 52
- 0
buildroot/share/PlatformIO/variants/BIGTREE_SKR_PRO_1v1/hal_conf_extra.h Datei anzeigen

@@ -0,0 +1,52 @@
1
+#pragma once
2
+
3
+#define HAL_MODULE_ENABLED
4
+#define HAL_ADC_MODULE_ENABLED
5
+#define HAL_CRC_MODULE_ENABLED
6
+#define HAL_DMA_MODULE_ENABLED
7
+#define HAL_GPIO_MODULE_ENABLED
8
+#define HAL_I2C_MODULE_ENABLED
9
+#define HAL_PWR_MODULE_ENABLED
10
+#define HAL_RCC_MODULE_ENABLED
11
+//#define HAL_RTC_MODULE_ENABLED Real Time Clock...do we use it?
12
+#define HAL_SPI_MODULE_ENABLED
13
+#define HAL_TIM_MODULE_ENABLED
14
+#define HAL_USART_MODULE_ENABLED
15
+#define HAL_CORTEX_MODULE_ENABLED
16
+//#define HAL_UART_MODULE_ENABLED // by default
17
+//#define HAL_PCD_MODULE_ENABLED  // Since STM32 v3.10700.191028 this is automatically added if any type of USB is enabled (as in Arduino IDE)
18
+
19
+#undef HAL_SD_MODULE_ENABLED
20
+#undef HAL_DAC_MODULE_ENABLED
21
+#undef HAL_FLASH_MODULE_ENABLED
22
+#undef HAL_CAN_MODULE_ENABLED
23
+#undef HAL_CAN_LEGACY_MODULE_ENABLED
24
+#undef HAL_CEC_MODULE_ENABLED
25
+#undef HAL_CRYP_MODULE_ENABLED
26
+#undef HAL_DCMI_MODULE_ENABLED
27
+#undef HAL_DMA2D_MODULE_ENABLED
28
+#undef HAL_ETH_MODULE_ENABLED
29
+#undef HAL_NAND_MODULE_ENABLED
30
+#undef HAL_NOR_MODULE_ENABLED
31
+#undef HAL_PCCARD_MODULE_ENABLED
32
+#undef HAL_SRAM_MODULE_ENABLED
33
+#undef HAL_SDRAM_MODULE_ENABLED
34
+#undef HAL_HASH_MODULE_ENABLED
35
+#undef HAL_EXTI_MODULE_ENABLED
36
+#undef HAL_SMBUS_MODULE_ENABLED
37
+#undef HAL_I2S_MODULE_ENABLED
38
+#undef HAL_IWDG_MODULE_ENABLED
39
+#undef HAL_LTDC_MODULE_ENABLED
40
+#undef HAL_DSI_MODULE_ENABLED
41
+#undef HAL_QSPI_MODULE_ENABLED
42
+#undef HAL_RNG_MODULE_ENABLED
43
+#undef HAL_SAI_MODULE_ENABLED
44
+#undef HAL_IRDA_MODULE_ENABLED
45
+#undef HAL_SMARTCARD_MODULE_ENABLED
46
+#undef HAL_WWDG_MODULE_ENABLED
47
+#undef HAL_HCD_MODULE_ENABLED
48
+#undef HAL_FMPI2C_MODULE_ENABLED
49
+#undef HAL_SPDIFRX_MODULE_ENABLED
50
+#undef HAL_DFSDM_MODULE_ENABLED
51
+#undef HAL_LPTIM_MODULE_ENABLED
52
+#undef HAL_MMC_MODULE_ENABLED

buildroot/share/PlatformIO/variants/BIGTREE_GENERIC_STM32F407_5X/ldscript.ld → buildroot/share/PlatformIO/variants/BIGTREE_SKR_PRO_1v1/ldscript.ld Datei anzeigen

@@ -192,7 +192,6 @@ SECTIONS
192 192
     . = ALIGN(4);
193 193
   } >RAM
194 194
 
195
-
196 195
   /* Remove information from the standard libraries */
197 196
   /DISCARD/ :
198 197
   {
@@ -203,5 +202,3 @@ SECTIONS
203 202
 
204 203
   .ARM.attributes 0 : { *(.ARM.attributes) }
205 204
 }
206
-
207
-

buildroot/share/PlatformIO/variants/BIGTREE_GENERIC_STM32F407_5X/variant.cpp → buildroot/share/PlatformIO/variants/BIGTREE_SKR_PRO_1v1/variant.cpp Datei anzeigen


buildroot/share/PlatformIO/variants/BIGTREE_GENERIC_STM32F407_5X/variant.h → buildroot/share/PlatformIO/variants/BIGTREE_SKR_PRO_1v1/variant.h Datei anzeigen

@@ -222,9 +222,15 @@ extern "C" {
222 222
 //#define DACC_RESOLUTION         12
223 223
 
224 224
 // PWM resolution
225
-#define PWM_RESOLUTION          8
226
-#define PWM_FREQUENCY           20000
227
-#define PWM_MAX_DUTY_CYCLE      255
225
+/*
226
+ * BEWARE:
227
+ * Changing this value from the default (1000) will affect the PWM output value of analogWrite (to a PWM pin)
228
+ * Since the pin is toggled on capture, if you change the frequency of the timer you have to adapt the compare value (analogWrite thinks you did)
229
+ */
230
+//#define PWM_FREQUENCY           20000
231
+//The bottom values are the default and don't need to be redefined
232
+//#define PWM_RESOLUTION          8
233
+//#define PWM_MAX_DUTY_CYCLE      255
228 234
 
229 235
 // Below SPI and I2C definitions already done in the core
230 236
 // Could be redefined here if differs from the default one
@@ -241,6 +247,7 @@ extern "C" {
241 247
 // Timer Definitions
242 248
 //Do not use timer used by PWM pins when possible. See PinMap_PWM in PeripheralPins.c
243 249
 #define TIMER_TONE              TIM6
250
+#define TIMER_SERIAL            TIM7
244 251
 
245 252
 // Do not use basic timer: OC is required
246 253
 #define TIMER_SERVO             TIM2  //TODO: advanced-control timers don't work
@@ -260,9 +267,6 @@ extern "C" {
260 267
 #define PIN_SERIAL_RX           PA10
261 268
 #define PIN_SERIAL_TX           PA9
262 269
 
263
-/* Extra HAL modules */
264
-#define HAL_PCD_MODULE_ENABLED
265
-
266 270
 #ifdef __cplusplus
267 271
 } // extern "C"
268 272
 #endif

+ 112
- 92
buildroot/share/PlatformIO/variants/MARLIN_F407VE/PeripheralPins.c Datei anzeigen

@@ -3,8 +3,10 @@
3 3
  * Copyright (c) 2019, STMicroelectronics
4 4
  * All rights reserved.
5 5
  *
6
- * Redistribution and use in source and binary forms, with or without
7
- * modification, are permitted provided that the following conditions are met:
6
+ * This software component is licensed by ST under BSD 3-Clause license,
7
+ * the "License"; You may not use this file except in compliance with the
8
+ * License. You may obtain a copy of the License at:
9
+ *                        opensource.org/licenses/BSD-3-Clause
8 10
  *
9 11
  * 1. Redistributions of source code must retain the above copyright notice,
10 12
  *    this list of conditions and the following disclaimer.
@@ -28,8 +30,8 @@
28 30
  *******************************************************************************
29 31
  * Automatically generated from STM32F407Z(E-G)Tx.xml
30 32
  */
31
-#include <Arduino.h>
32
-#include <PeripheralPins.h>
33
+#include "Arduino.h"
34
+#include "PeripheralPins.h"
33 35
 
34 36
 /* =====
35 37
  * Note: Commented lines are alternative possibilities which are not used per default.
@@ -40,58 +42,58 @@
40 42
 //*** ADC ***
41 43
 
42 44
 #ifdef HAL_ADC_MODULE_ENABLED
43
-const PinMap PinMap_ADC[] = {
45
+WEAK const PinMap PinMap_ADC[] = {
44 46
   {PA_0,  ADC1,  STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 0, 0)}, // ADC1_IN0
45
-  //  {PA_0,  ADC2,  STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 0, 0)}, // ADC2_IN0
46
-  //  {PA_0,  ADC3,  STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 0, 0)}, // ADC3_IN0
47
+  //{PA_0,  ADC2,  STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 0, 0)}, // ADC2_IN0
48
+  //{PA_0,  ADC3,  STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 0, 0)}, // ADC3_IN0
47 49
   {PA_1,  ADC1,  STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 1, 0)}, // ADC1_IN1
48
-  //  {PA_1,  ADC2,  STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 1, 0)}, // ADC2_IN1
49
-  //  {PA_1,  ADC3,  STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 1, 0)}, // ADC3_IN1
50
-  //  {PA_2,  ADC1,  STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 2, 0)}, // ADC1_IN2
50
+  //{PA_1,  ADC2,  STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 1, 0)}, // ADC2_IN1
51
+  //{PA_1,  ADC3,  STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 1, 0)}, // ADC3_IN1
52
+  //{PA_2,  ADC1,  STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 2, 0)}, // ADC1_IN2
51 53
   {PA_2,  ADC2,  STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 2, 0)}, // ADC2_IN2
52
-  //  {PA_2,  ADC3,  STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 2, 0)}, // ADC3_IN2
53
-  //  {PA_3,  ADC1,  STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 3, 0)}, // ADC1_IN3
54
-  //  {PA_3,  ADC2,  STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 3, 0)}, // ADC2_IN3
54
+  //{PA_2,  ADC3,  STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 2, 0)}, // ADC3_IN2
55
+  //{PA_3,  ADC1,  STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 3, 0)}, // ADC1_IN3
56
+  //{PA_3,  ADC2,  STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 3, 0)}, // ADC2_IN3
55 57
   {PA_3,  ADC3,  STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 3, 0)}, // ADC3_IN3
56 58
   {PA_4,  ADC1,  STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 4, 0)}, // ADC1_IN4
57
-  //  {PA_4,  ADC2,  STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 4, 0)}, // ADC2_IN4
58
-  //  {PA_5,  ADC1,  STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 5, 0)}, // ADC1_IN5
59
+  //{PA_4,  ADC2,  STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 4, 0)}, // ADC2_IN4
60
+  //{PA_5,  ADC1,  STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 5, 0)}, // ADC1_IN5
59 61
   {PA_5,  ADC2,  STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 5, 0)}, // ADC2_IN5
60 62
 #if defined(ARDUINO_BLACK_F407ZE) || defined(ARDUINO_BLACK_F407ZG)
61
-  //  {PA_6,  ADC1,  STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 6, 0)}, // ADC1_IN6
62
-  //  {PA_6,  ADC2,  STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 6, 0)}, // ADC2_IN6
63
-  //  {PA_7,  ADC1,  STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 7, 0)}, // ADC1_IN7
64
-  //  {PA_7,  ADC2,  STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 7, 0)}, // ADC2_IN7
65
-  //  {PB_0,  ADC1,  STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 8, 0)}, // ADC1_IN8
63
+  //{PA_6,  ADC1,  STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 6, 0)}, // ADC1_IN6
64
+  //{PA_6,  ADC2,  STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 6, 0)}, // ADC2_IN6
65
+  //{PA_7,  ADC1,  STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 7, 0)}, // ADC1_IN7
66
+  //{PA_7,  ADC2,  STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 7, 0)}, // ADC2_IN7
67
+  //{PB_0,  ADC1,  STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 8, 0)}, // ADC1_IN8
66 68
 #endif
67 69
   {PB_0,  ADC2,  STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 8, 0)}, // ADC2_IN8
68 70
   {PB_1,  ADC1,  STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 9, 0)}, // ADC1_IN9
69
-  //  {PB_1,  ADC2,  STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 9, 0)}, // ADC2_IN9
70
-  //  {PC_0,  ADC1,  STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 10, 0)}, // ADC1_IN10
71
-  //  {PC_0,  ADC2,  STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 10, 0)}, // ADC2_IN10
71
+  //{PB_1,  ADC2,  STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 9, 0)}, // ADC2_IN9
72
+  //{PC_0,  ADC1,  STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 10, 0)}, // ADC1_IN10
73
+  //{PC_0,  ADC2,  STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 10, 0)}, // ADC2_IN10
72 74
   {PC_0,  ADC3,  STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 10, 0)}, // ADC3_IN10
73 75
   {PC_1,  ADC1,  STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 11, 0)}, // ADC1_IN11
74
-  //  {PC_1,  ADC2,  STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 11, 0)}, // ADC2_IN11
75
-  //  {PC_1,  ADC3,  STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 11, 0)}, // ADC3_IN11
76
-  //  {PC_2,  ADC1,  STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 12, 0)}, // ADC1_IN12
76
+  //{PC_1,  ADC2,  STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 11, 0)}, // ADC2_IN11
77
+  //{PC_1,  ADC3,  STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 11, 0)}, // ADC3_IN11
78
+  //{PC_2,  ADC1,  STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 12, 0)}, // ADC1_IN12
77 79
   {PC_2,  ADC2,  STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 12, 0)}, // ADC2_IN12
78
-  //  {PC_2,  ADC3,  STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 12, 0)}, // ADC3_IN12
79
-  //  {PC_3,  ADC1,  STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 13, 0)}, // ADC1_IN13
80
-  //  {PC_3,  ADC2,  STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 13, 0)}, // ADC2_IN13
80
+  //{PC_2,  ADC3,  STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 12, 0)}, // ADC3_IN12
81
+  //{PC_3,  ADC1,  STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 13, 0)}, // ADC1_IN13
82
+  //{PC_3,  ADC2,  STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 13, 0)}, // ADC2_IN13
81 83
   {PC_3,  ADC3,  STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 13, 0)}, // ADC3_IN13
82
-  //  {PC_4,  ADC1,  STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 14, 0)}, // ADC1_IN14
84
+  //{PC_4,  ADC1,  STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 14, 0)}, // ADC1_IN14
83 85
   {PC_4,  ADC2,  STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 14, 0)}, // ADC2_IN14
84
-  //  {PC_5,  ADC1,  STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 15, 0)}, // ADC1_IN15
86
+  //{PC_5,  ADC1,  STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 15, 0)}, // ADC1_IN15
85 87
   {PC_5,  ADC2,  STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 15, 0)}, // ADC2_IN15
86 88
 #if defined(ARDUINO_BLACK_F407ZE) || defined(ARDUINO_BLACK_F407ZG)
87
-  //  {PF_3,  ADC3,  STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 9, 0)}, // ADC3_IN9
88
-  //  {PF_4,  ADC3,  STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 14, 0)}, // ADC3_IN14
89
-  //  {PF_5,  ADC3,  STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 15, 0)}, // ADC3_IN15
89
+  //{PF_3,  ADC3,  STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 9, 0)}, // ADC3_IN9
90
+  //{PF_4,  ADC3,  STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 14, 0)}, // ADC3_IN14
91
+  //{PF_5,  ADC3,  STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 15, 0)}, // ADC3_IN15
90 92
   {PF_6,  ADC3,  STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 4, 0)}, // ADC3_IN4
91 93
   {PF_7,  ADC3,  STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 5, 0)}, // ADC3_IN5
92 94
   {PF_8,  ADC3,  STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 6, 0)}, // ADC3_IN6
93
-  //  {PF_9,  ADC3,  STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 7, 0)}, // ADC3_IN7
94
-  //  {PF_10, ADC3,  STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 8, 0)}, // ADC3_IN8
95
+  //{PF_9,  ADC3,  STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 7, 0)}, // ADC3_IN7
96
+  //{PF_10, ADC3,  STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 8, 0)}, // ADC3_IN8
95 97
 #endif
96 98
   {NC,    NP,    0}
97 99
 };
@@ -100,7 +102,7 @@ const PinMap PinMap_ADC[] = {
100 102
 //*** DAC ***
101 103
 
102 104
 #ifdef HAL_DAC_MODULE_ENABLED
103
-const PinMap PinMap_DAC[] = {
105
+WEAK const PinMap PinMap_DAC[] = {
104 106
   {PA_4,  DAC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 1, 0)}, // DAC_OUT1
105 107
   {PA_5,  DAC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 2, 0)}, // DAC_OUT2
106 108
   {NC,    NP,    0}
@@ -110,7 +112,7 @@ const PinMap PinMap_DAC[] = {
110 112
 //*** I2C ***
111 113
 
112 114
 #ifdef HAL_I2C_MODULE_ENABLED
113
-const PinMap PinMap_I2C_SDA[] = {
115
+WEAK const PinMap PinMap_I2C_SDA[] = {
114 116
   {PB_7,  I2C1, STM_PIN_DATA(STM_MODE_AF_OD, GPIO_NOPULL, GPIO_AF4_I2C1)},
115 117
   {PB_9,  I2C1, STM_PIN_DATA(STM_MODE_AF_OD, GPIO_NOPULL, GPIO_AF4_I2C1)},
116 118
   {PB_11, I2C2, STM_PIN_DATA(STM_MODE_AF_OD, GPIO_NOPULL, GPIO_AF4_I2C2)},
@@ -123,7 +125,7 @@ const PinMap PinMap_I2C_SDA[] = {
123 125
 #endif
124 126
 
125 127
 #ifdef HAL_I2C_MODULE_ENABLED
126
-const PinMap PinMap_I2C_SCL[] = {
128
+WEAK const PinMap PinMap_I2C_SCL[] = {
127 129
   {PA_8,  I2C3, STM_PIN_DATA(STM_MODE_AF_OD, GPIO_NOPULL, GPIO_AF4_I2C3)},
128 130
   {PB_6,  I2C1, STM_PIN_DATA(STM_MODE_AF_OD, GPIO_NOPULL, GPIO_AF4_I2C1)},
129 131
   {PB_8,  I2C1, STM_PIN_DATA(STM_MODE_AF_OD, GPIO_NOPULL, GPIO_AF4_I2C1)},
@@ -138,61 +140,61 @@ const PinMap PinMap_I2C_SCL[] = {
138 140
 //*** PWM ***
139 141
 
140 142
 #ifdef HAL_TIM_MODULE_ENABLED
141
-const PinMap PinMap_PWM[] = {
143
+WEAK const PinMap PinMap_PWM[] = {
142 144
   {PA_0,  TIM2,   STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM2, 1, 0)}, // TIM2_CH1
143
-  //  {PA_0,  TIM5,   STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM5, 1, 0)}, // TIM5_CH1
145
+  //{PA_0,  TIM5,   STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM5, 1, 0)}, // TIM5_CH1
144 146
   {PA_1,  TIM2,   STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM2, 2, 0)}, // TIM2_CH2
145
-  //  {PA_1,  TIM5,   STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM5, 2, 0)}, // TIM5_CH2
147
+  //{PA_1,  TIM5,   STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM5, 2, 0)}, // TIM5_CH2
146 148
   {PA_2,  TIM2,   STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM2, 3, 0)}, // TIM2_CH3
147
-  //  {PA_2,  TIM5,   STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM5, 3, 0)}, // TIM5_CH3
148
-  //  {PA_2,  TIM9,   STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF3_TIM9, 1, 0)}, // TIM9_CH1
149
+  //{PA_2,  TIM5,   STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM5, 3, 0)}, // TIM5_CH3
150
+  //{PA_2,  TIM9,   STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF3_TIM9, 1, 0)}, // TIM9_CH1
149 151
   {PA_3,  TIM2,   STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM2, 4, 0)}, // TIM2_CH4
150
-  //  {PA_3,  TIM5,   STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM5, 4, 0)}, // TIM5_CH4
151
-  //  {PA_3,  TIM9,   STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF3_TIM9, 2, 0)}, // TIM9_CH2
152
+  //{PA_3,  TIM5,   STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM5, 4, 0)}, // TIM5_CH4
153
+  //{PA_3,  TIM9,   STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF3_TIM9, 2, 0)}, // TIM9_CH2
152 154
   {PA_5,  TIM2,   STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM2, 1, 0)}, // TIM2_CH1
153
-  //  {PA_5,  TIM8,   STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF3_TIM8, 1, 1)}, // TIM8_CH1N
155
+  //{PA_5,  TIM8,   STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF3_TIM8, 1, 1)}, // TIM8_CH1N
154 156
   {PA_6,  TIM3,   STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM3, 1, 0)}, // TIM3_CH1
155
-  //  {PA_6,  TIM13,  STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF9_TIM13, 1, 0)}, // TIM13_CH1
156
-  //  {PA_7,  TIM1,   STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM1, 1, 1)}, // TIM1_CH1N
157
+  //{PA_6,  TIM13,  STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF9_TIM13, 1, 0)}, // TIM13_CH1
158
+  //{PA_7,  TIM1,   STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM1, 1, 1)}, // TIM1_CH1N
157 159
   {PA_7,  TIM3,   STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM3, 2, 0)}, // TIM3_CH2
158
-  //  {PA_7,  TIM8,   STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF3_TIM8, 1, 1)}, // TIM8_CH1N
159
-  //  {PA_7,  TIM14,  STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF9_TIM14, 1, 0)}, // TIM14_CH1
160
+  //{PA_7,  TIM8,   STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF3_TIM8, 1, 1)}, // TIM8_CH1N
161
+  //{PA_7,  TIM14,  STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF9_TIM14, 1, 0)}, // TIM14_CH1
160 162
   {PA_8,  TIM1,   STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM1, 1, 0)}, // TIM1_CH1
161 163
   {PA_9,  TIM1,   STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM1, 2, 0)}, // TIM1_CH2
162 164
   {PA_10, TIM1,   STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM1, 3, 0)}, // TIM1_CH3
163 165
   {PA_11, TIM1,   STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM1, 4, 0)}, // TIM1_CH4
164
-  //  {PA_15, TIM2,   STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM2, 1, 0)}, // TIM2_CH1
165
-  //  {PB_0,  TIM1,   STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM1, 2, 1)}, // TIM1_CH2N
166
+  //{PA_15, TIM2,   STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM2, 1, 0)}, // TIM2_CH1
167
+  //{PB_0,  TIM1,   STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM1, 2, 1)}, // TIM1_CH2N
166 168
   {PB_0,  TIM3,   STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM3, 3, 0)}, // TIM3_CH3
167
-  //  {PB_0,  TIM8,   STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF3_TIM8, 2, 1)}, // TIM8_CH2N
168
-  //  {PB_1,  TIM1,   STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM1, 3, 1)}, // TIM1_CH3N
169
+  //{PB_0,  TIM8,   STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF3_TIM8, 2, 1)}, // TIM8_CH2N
170
+  //{PB_1,  TIM1,   STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM1, 3, 1)}, // TIM1_CH3N
169 171
   {PB_1,  TIM3,   STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM3, 4, 0)}, // TIM3_CH4
170
-  //  {PB_1,  TIM8,   STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF3_TIM8, 3, 1)}, // TIM8_CH3N
171
-  //  {PB_3,  TIM2,   STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM2, 2, 0)}, // TIM2_CH2
172
+  //{PB_1,  TIM8,   STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF3_TIM8, 3, 1)}, // TIM8_CH3N
173
+  //{PB_3,  TIM2,   STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM2, 2, 0)}, // TIM2_CH2
172 174
   {PB_4,  TIM3,   STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM3, 1, 0)}, // TIM3_CH1
173 175
   {PB_5,  TIM3,   STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM3, 2, 0)}, // TIM3_CH2
174 176
   {PB_6,  TIM4,   STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM4, 1, 0)}, // TIM4_CH1
175 177
   {PB_7,  TIM4,   STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM4, 2, 0)}, // TIM4_CH2
176
-  {PB_8,  TIM4,   STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM4, 3, 0)}, // TIM4_CH3
178
+  //{PB_8,  TIM4,   STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM4, 3, 0)}, // TIM4_CH3
177 179
   {PB_8,  TIM10,  STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF3_TIM10, 1, 0)}, // TIM10_CH1
178
-  {PB_9,  TIM4,   STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM4, 4, 0)}, // TIM4_CH4
180
+  //{PB_9,  TIM4,   STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM4, 4, 0)}, // TIM4_CH4
179 181
   {PB_9,  TIM11,  STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF3_TIM11, 1, 0)}, // TIM11_CH1
180 182
   {PB_10, TIM2,   STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM2, 3, 0)}, // TIM2_CH3
181 183
   {PB_11, TIM2,   STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM2, 4, 0)}, // TIM2_CH4
182 184
   {PB_13, TIM1,   STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM1, 1, 1)}, // TIM1_CH1N
183
-  {PB_14, TIM1,   STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM1, 2, 1)}, // TIM1_CH2N
184
-  {PB_14, TIM8,   STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF3_TIM8, 2, 1)}, // TIM8_CH2N
185
+  //{PB_14, TIM1,   STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM1, 2, 1)}, // TIM1_CH2N
186
+  //{PB_14, TIM8,   STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF3_TIM8, 2, 1)}, // TIM8_CH2N
185 187
   {PB_14, TIM12,  STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF9_TIM12, 1, 0)}, // TIM12_CH1
186
-  {PB_15, TIM1,   STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM1, 3, 1)}, // TIM1_CH3N
187
-  {PB_15, TIM8,   STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF3_TIM8, 3, 1)}, // TIM8_CH3N
188
+  //{PB_15, TIM1,   STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM1, 3, 1)}, // TIM1_CH3N
189
+  //{PB_15, TIM8,   STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF3_TIM8, 3, 1)}, // TIM8_CH3N
188 190
   {PB_15, TIM12,  STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF9_TIM12, 2, 0)}, // TIM12_CH2
189
-  {PC_6,  TIM3,   STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM3, 1, 0)}, // TIM3_CH1
191
+  //{PC_6,  TIM3,   STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM3, 1, 0)}, // TIM3_CH1
190 192
   {PC_6,  TIM8,   STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF3_TIM8, 1, 0)}, // TIM8_CH1
191
-  {PC_7,  TIM3,   STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM3, 2, 0)}, // TIM3_CH2
193
+  //{PC_7,  TIM3,   STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM3, 2, 0)}, // TIM3_CH2
192 194
   {PC_7,  TIM8,   STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF3_TIM8, 2, 0)}, // TIM8_CH2
193 195
   {PC_8,  TIM3,   STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM3, 3, 0)}, // TIM3_CH3
194
-  {PC_8,  TIM8,   STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF3_TIM8, 3, 0)}, // TIM8_CH3
195
-  {PC_9,  TIM3,   STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM3, 4, 0)}, // TIM3_CH4
196
+  //{PC_8,  TIM8,   STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF3_TIM8, 3, 0)}, // TIM8_CH3
197
+  //{PC_9,  TIM3,   STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM3, 4, 0)}, // TIM3_CH4
196 198
   {PC_9,  TIM8,   STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF3_TIM8, 4, 0)}, // TIM8_CH4
197 199
   {PD_12, TIM4,   STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM4, 1, 0)}, // TIM4_CH1
198 200
   {PD_13, TIM4,   STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM4, 2, 0)}, // TIM4_CH2
@@ -220,47 +222,47 @@ const PinMap PinMap_PWM[] = {
220 222
 //*** SERIAL ***
221 223
 
222 224
 #ifdef HAL_UART_MODULE_ENABLED
223
-const PinMap PinMap_UART_TX[] = {
225
+WEAK const PinMap PinMap_UART_TX[] = {
224 226
   {PA_0,  UART4,   STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF8_UART4)},
225 227
   {PA_2,  USART2,  STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_USART2)},
226 228
   {PA_9,  USART1,  STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_USART1)},
227 229
   {PB_6,  USART1,  STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_USART1)},
228 230
   {PB_10, USART3,  STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_USART3)},
229 231
   {PC_6,  USART6,  STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF8_USART6)},
230
-  //  {PC_10, UART4,   STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF8_UART4)},
232
+  //{PC_10, UART4,   STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF8_UART4)},
231 233
   {PC_10, USART3,  STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_USART3)},
232 234
   {PC_12, UART5,   STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF8_UART5)},
233 235
   {PD_5,  USART2,  STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_USART2)},
234 236
   {PD_8,  USART3,  STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_USART3)},
235 237
 #if defined(ARDUINO_BLACK_F407ZE) || defined(ARDUINO_BLACK_F407ZG)
236
-  //  {PG_14, USART6,  STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF8_USART6)},
238
+  //{PG_14, USART6,  STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF8_USART6)},
237 239
 #endif
238 240
   {NC,    NP,    0}
239 241
 };
240 242
 #endif
241 243
 
242 244
 #ifdef HAL_UART_MODULE_ENABLED
243
-const PinMap PinMap_UART_RX[] = {
245
+WEAK const PinMap PinMap_UART_RX[] = {
244 246
   {PA_1,  UART4,   STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF8_UART4)},
245 247
   {PA_3,  USART2,  STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_USART2)},
246 248
   {PA_10, USART1,  STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_USART1)},
247 249
   {PB_7,  USART1,  STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_USART1)},
248 250
   {PB_11, USART3,  STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_USART3)},
249 251
   {PC_7,  USART6,  STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF8_USART6)},
250
-  //  {PC_11, UART4,   STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF8_UART4)},
252
+  //{PC_11, UART4,   STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF8_UART4)},
251 253
   {PC_11, USART3,  STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_USART3)},
252 254
   {PD_2,  UART5,   STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF8_UART5)},
253 255
   {PD_6,  USART2,  STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_USART2)},
254 256
   {PD_9,  USART3,  STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_USART3)},
255 257
 #if defined(ARDUINO_BLACK_F407ZE) || defined(ARDUINO_BLACK_F407ZG)
256
-  //  {PG_9,  USART6,  STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF8_USART6)},
258
+  //{PG_9,  USART6,  STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF8_USART6)},
257 259
 #endif
258 260
   {NC,    NP,    0}
259 261
 };
260 262
 #endif
261 263
 
262 264
 #ifdef HAL_UART_MODULE_ENABLED
263
-const PinMap PinMap_UART_RTS[] = {
265
+WEAK const PinMap PinMap_UART_RTS[] = {
264 266
   {PA_1,  USART2,  STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_USART2)},
265 267
   {PA_12, USART1,  STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_USART1)},
266 268
   {PB_14, USART3,  STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_USART3)},
@@ -275,7 +277,7 @@ const PinMap PinMap_UART_RTS[] = {
275 277
 #endif
276 278
 
277 279
 #ifdef HAL_UART_MODULE_ENABLED
278
-const PinMap PinMap_UART_CTS[] = {
280
+WEAK const PinMap PinMap_UART_CTS[] = {
279 281
   {PA_0,  USART2,  STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_USART2)},
280 282
   {PA_11, USART1,  STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_USART1)},
281 283
   {PB_13, USART3,  STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_USART3)},
@@ -292,9 +294,9 @@ const PinMap PinMap_UART_CTS[] = {
292 294
 //*** SPI ***
293 295
 
294 296
 #ifdef HAL_SPI_MODULE_ENABLED
295
-const PinMap PinMap_SPI_MOSI[] = {
297
+WEAK const PinMap PinMap_SPI_MOSI[] = {
296 298
   {PA_7,  SPI1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF5_SPI1)},
297
-  {PB_5,  SPI1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF5_SPI1)},
299
+  //{PB_5,  SPI1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF5_SPI1)},
298 300
   {PB_5,  SPI3, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF6_SPI3)},
299 301
   {PB_15, SPI2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF5_SPI2)},
300 302
   {PC_3,  SPI2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF5_SPI2)},
@@ -304,9 +306,9 @@ const PinMap PinMap_SPI_MOSI[] = {
304 306
 #endif
305 307
 
306 308
 #ifdef HAL_SPI_MODULE_ENABLED
307
-const PinMap PinMap_SPI_MISO[] = {
309
+WEAK const PinMap PinMap_SPI_MISO[] = {
308 310
   {PA_6,  SPI1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF5_SPI1)},
309
-  {PB_4,  SPI1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF5_SPI1)},
311
+  //{PB_4,  SPI1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF5_SPI1)},
310 312
   {PB_4,  SPI3, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF6_SPI3)},
311 313
   {PB_14, SPI2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF5_SPI2)},
312 314
   {PC_2,  SPI2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF5_SPI2)},
@@ -316,9 +318,9 @@ const PinMap PinMap_SPI_MISO[] = {
316 318
 #endif
317 319
 
318 320
 #ifdef HAL_SPI_MODULE_ENABLED
319
-const PinMap PinMap_SPI_SCLK[] = {
321
+WEAK const PinMap PinMap_SPI_SCLK[] = {
320 322
   {PA_5,  SPI1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF5_SPI1)},
321
-  {PB_3,  SPI1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF5_SPI1)},
323
+  //{PB_3,  SPI1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF5_SPI1)},
322 324
   {PB_3,  SPI3, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF6_SPI3)},
323 325
   {PB_10, SPI2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF5_SPI2)},
324 326
   {PB_13, SPI2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF5_SPI2)},
@@ -328,10 +330,10 @@ const PinMap PinMap_SPI_SCLK[] = {
328 330
 #endif
329 331
 
330 332
 #ifdef HAL_SPI_MODULE_ENABLED
331
-const PinMap PinMap_SPI_SSEL[] = {
333
+WEAK const PinMap PinMap_SPI_SSEL[] = {
332 334
   {PA_4,  SPI1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF5_SPI1)},
333
-  {PA_4,  SPI3, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF6_SPI3)},
334
-  {PA_15, SPI1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF5_SPI1)},
335
+  //{PA_4,  SPI3, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF6_SPI3)},
336
+  //{PA_15, SPI1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF5_SPI1)},
335 337
   {PA_15, SPI3, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF6_SPI3)},
336 338
   {PB_9,  SPI2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF5_SPI2)},
337 339
   {PB_12, SPI2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF5_SPI2)},
@@ -342,7 +344,7 @@ const PinMap PinMap_SPI_SSEL[] = {
342 344
 //*** CAN ***
343 345
 
344 346
 #ifdef HAL_CAN_MODULE_ENABLED
345
-const PinMap PinMap_CAN_RD[] = {
347
+WEAK const PinMap PinMap_CAN_RD[] = {
346 348
   {PA_11, CAN1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_NOPULL, GPIO_AF9_CAN1)},
347 349
   {PB_5,  CAN2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_NOPULL, GPIO_AF9_CAN2)},
348 350
   {PB_8,  CAN1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_NOPULL, GPIO_AF9_CAN1)},
@@ -353,7 +355,7 @@ const PinMap PinMap_CAN_RD[] = {
353 355
 #endif
354 356
 
355 357
 #ifdef HAL_CAN_MODULE_ENABLED
356
-const PinMap PinMap_CAN_TD[] = {
358
+WEAK const PinMap PinMap_CAN_TD[] = {
357 359
   {PA_12, CAN1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_NOPULL, GPIO_AF9_CAN1)},
358 360
   {PB_6,  CAN2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_NOPULL, GPIO_AF9_CAN2)},
359 361
   {PB_9,  CAN1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_NOPULL, GPIO_AF9_CAN1)},
@@ -366,7 +368,7 @@ const PinMap PinMap_CAN_TD[] = {
366 368
 //*** ETHERNET ***
367 369
 
368 370
 #ifdef HAL_ETH_MODULE_ENABLED
369
-const PinMap PinMap_Ethernet[] = {
371
+WEAK const PinMap PinMap_Ethernet[] = {
370 372
   {PA_0,  ETH, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF11_ETH)}, // ETH_CRS
371 373
   {PA_1,  ETH, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF11_ETH)}, // ETH_REF_CLK|ETH_RX_CLK
372 374
   {PA_2,  ETH, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF11_ETH)}, // ETH_MDIO
@@ -401,10 +403,10 @@ const PinMap PinMap_Ethernet[] = {
401 403
 //*** USB ***
402 404
 
403 405
 #ifdef HAL_PCD_MODULE_ENABLED
404
-const PinMap PinMap_USB_OTG_FS[] = {
405
-  //  {PA_8,  USB_OTG_FS, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF10_OTG_FS)}, // USB_OTG_FS_SOF
406
-  //  {PA_9,  USB_OTG_FS, STM_PIN_DATA(STM_MODE_INPUT, GPIO_NOPULL, GPIO_AF_NONE)}, // USB_OTG_FS_VBUS
407
-  //  {PA_10, USB_OTG_FS, STM_PIN_DATA(STM_MODE_AF_OD, GPIO_PULLUP, GPIO_AF10_OTG_FS)}, // USB_OTG_FS_ID
406
+WEAK const PinMap PinMap_USB_OTG_FS[] = {
407
+  //{PA_8,  USB_OTG_FS, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF10_OTG_FS)}, // USB_OTG_FS_SOF
408
+  //{PA_9,  USB_OTG_FS, STM_PIN_DATA(STM_MODE_INPUT, GPIO_NOPULL, GPIO_AF_NONE)}, // USB_OTG_FS_VBUS
409
+  //{PA_10, USB_OTG_FS, STM_PIN_DATA(STM_MODE_AF_OD, GPIO_PULLUP, GPIO_AF10_OTG_FS)}, // USB_OTG_FS_ID
408 410
   {PA_11, USB_OTG_FS, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF10_OTG_FS)}, // USB_OTG_FS_DM
409 411
   {PA_12, USB_OTG_FS, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF10_OTG_FS)}, // USB_OTG_FS_DP
410 412
   {NC,    NP,    0}
@@ -412,7 +414,7 @@ const PinMap PinMap_USB_OTG_FS[] = {
412 414
 #endif
413 415
 
414 416
 #ifdef HAL_PCD_MODULE_ENABLED
415
-const PinMap PinMap_USB_OTG_HS[] = {
417
+WEAK const PinMap PinMap_USB_OTG_HS[] = {
416 418
 #ifdef USE_USB_HS_IN_FS
417 419
   {PA_4,  USB_OTG_HS, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF12_OTG_HS_FS)}, // USB_OTG_HS_SOF
418 420
   {PB_12, USB_OTG_HS, STM_PIN_DATA(STM_MODE_AF_OD, GPIO_PULLUP, GPIO_AF12_OTG_HS_FS)}, // USB_OTG_HS_ID
@@ -436,3 +438,21 @@ const PinMap PinMap_USB_OTG_HS[] = {
436 438
   {NC,    NP,    0}
437 439
 };
438 440
 #endif
441
+
442
+//*** SD ***
443
+
444
+#ifdef HAL_SD_MODULE_ENABLED
445
+WEAK const PinMap PinMap_SD[] = {
446
+  //{PB_8,  SDIO, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF12_SDIO)}, // SDIO_D4
447
+  //{PB_9,  SDIO, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF12_SDIO)}, // SDIO_D5
448
+  //{PC_6,  SDIO, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF12_SDIO)}, // SDIO_D6
449
+  //{PC_7,  SDIO, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF12_SDIO)}, // SDIO_D7
450
+  {PC_8,  SDIO, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF12_SDIO)}, // SDIO_D0
451
+  {PC_9,  SDIO, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF12_SDIO)}, // SDIO_D1
452
+  {PC_10, SDIO, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF12_SDIO)}, // SDIO_D2
453
+  {PC_11, SDIO, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF12_SDIO)}, // SDIO_D3
454
+  {PC_12, SDIO, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_NOPULL, GPIO_AF12_SDIO)}, // SDIO_CK
455
+  {PD_2,  SDIO, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_NOPULL, GPIO_AF12_SDIO)}, // SDIO_CMD
456
+  {NC,    NP,    0}
457
+};
458
+#endif

buildroot/share/PlatformIO/variants/MARLIN_F407VE/stm32f4xx_hal_conf.h → buildroot/share/PlatformIO/variants/MARLIN_F407VE/hal_conf_custom.h Datei anzeigen

@@ -17,8 +17,8 @@
17 17
   */
18 18
 
19 19
 /* Define to prevent recursive inclusion -------------------------------------*/
20
-#ifndef __STM32F4xx_HAL_CONF_H
21
-#define __STM32F4xx_HAL_CONF_H
20
+#ifndef __STM32F4xx_HAL_CONF_CUSTOM
21
+#define __STM32F4xx_HAL_CONF_CUSTOM
22 22
 
23 23
 #ifdef __cplusplus
24 24
 extern "C" {
@@ -73,7 +73,9 @@ extern "C" {
73 73
 /* #define HAL_SMARTCARD_MODULE_ENABLED   */
74 74
 /* #define HAL_WWDG_MODULE_ENABLED   */
75 75
 #define HAL_CORTEX_MODULE_ENABLED
76
-#define HAL_PCD_MODULE_ENABLED
76
+#ifndef HAL_PCD_MODULE_ENABLED
77
+  #define HAL_PCD_MODULE_ENABLED //Since STM32 v3.10700.191028 this is automatically added if any type of USB is enabled (as in Arduino IDE)
78
+#endif
77 79
 /* #define HAL_HCD_MODULE_ENABLED   */
78 80
 /* #define HAL_FMPI2C_MODULE_ENABLED   */
79 81
 /* #define HAL_SPDIFRX_MODULE_ENABLED   */
@@ -82,69 +84,81 @@ extern "C" {
82 84
 /* #define HAL_MMC_MODULE_ENABLED   */
83 85
 
84 86
 /* ########################## HSE/HSI Values adaptation ##################### */
85
- /**
87
+/**
86 88
   * @brief Adjust the value of External High Speed oscillator (HSE) used in your application.
87 89
   *        This value is used by the RCC HAL module to compute the system frequency
88 90
   *        (when HSE is used as system clock source, directly or through the PLL).
89 91
   */
90 92
 #ifndef HSE_VALUE
91
-#define HSE_VALUE    ((uint32_t)8000000U) /*!< Value of the External oscillator in Hz */
93
+#define HSE_VALUE              8000000U /*!< Value of the External oscillator in Hz */
92 94
 #endif /* HSE_VALUE */
93 95
 
94 96
 #ifndef HSE_STARTUP_TIMEOUT
95
-#define HSE_STARTUP_TIMEOUT    ((uint32_t)100U)   /*!< Time out for HSE start up, in ms */
97
+#define HSE_STARTUP_TIMEOUT    100U      /*!< Time out for HSE start up, in ms */
96 98
 #endif /* HSE_STARTUP_TIMEOUT */
97 99
 
98
- /**
100
+/**
99 101
   * @brief Internal High Speed oscillator (HSI) value.
100 102
   *        This value is used by the RCC HAL module to compute the system frequency
101 103
   *        (when HSI is used as system clock source, directly or through the PLL).
102 104
   */
103 105
 #ifndef HSI_VALUE
104
-#define HSI_VALUE    ((uint32_t)16000000U) /*!< Value of the Internal oscillator in Hz*/
106
+#define HSI_VALUE              16000000U /*!< Value of the Internal oscillator in Hz */
105 107
 #endif /* HSI_VALUE */
106 108
 
107
- /**
109
+/**
108 110
   * @brief Internal Low Speed oscillator (LSI) value.
109 111
   */
110 112
 #ifndef LSI_VALUE
111
-#define LSI_VALUE  ((uint32_t)32000U)       /*!< LSI Typical Value in Hz*/
113
+#define LSI_VALUE               32000U    /*!< LSI Typical Value in Hz */
112 114
 #endif /* LSI_VALUE */                      /*!< Value of the Internal Low Speed oscillator in Hz
113 115
 The real value may vary depending on the variations
114
-in voltage and temperature.*/
115
- /**
116
+in voltage and temperature. */
117
+/**
116 118
   * @brief External Low Speed oscillator (LSE) value.
117 119
   */
118 120
 #ifndef LSE_VALUE
119
-#define LSE_VALUE  ((uint32_t)32768U)    /*!< Value of the External Low Speed oscillator in Hz */
121
+#define LSE_VALUE               32768U    /*!< Value of the External Low Speed oscillator in Hz */
120 122
 #endif /* LSE_VALUE */
121 123
 
122 124
 #ifndef LSE_STARTUP_TIMEOUT
123
-#define LSE_STARTUP_TIMEOUT    ((uint32_t)5000U)   /*!< Time out for LSE start up, in ms */
125
+#define LSE_STARTUP_TIMEOUT    5000U     /*!< Time out for LSE start up, in ms */
124 126
 #endif /* LSE_STARTUP_TIMEOUT */
125 127
 
126
- /**
128
+/**
127 129
   * @brief External clock source for I2S peripheral
128 130
   *        This value is used by the I2S HAL module to compute the I2S clock source
129 131
   *        frequency, this source is inserted directly through I2S_CKIN pad.
130 132
   */
131 133
 #ifndef EXTERNAL_CLOCK_VALUE
132
-#define EXTERNAL_CLOCK_VALUE    ((uint32_t)12288000U) /*!< Value of the External audio frequency in Hz*/
134
+#define EXTERNAL_CLOCK_VALUE     12288000U /*!< Value of the External oscillator in Hz*/
133 135
 #endif /* EXTERNAL_CLOCK_VALUE */
134 136
 
135 137
 /* Tip: To avoid modifying this file each time you need to use different HSE,
136 138
    ===  you can define the HSE value in your toolchain compiler preprocessor. */
137 139
 
138 140
 /* ########################### System Configuration ######################### */
139
- /**
141
+/**
140 142
   * @brief This is the HAL system configuration section
141 143
   */
142
-#define  VDD_VALUE          ((uint32_t)3300U) /*!< Value of VDD in mv */
143
-#define  TICK_INT_PRIORITY            ((uint32_t)0U)   /*!< tick interrupt priority */
144
+#if !defined (VDD_VALUE)
145
+#define  VDD_VALUE                    3300U /*!< Value of VDD in mv */
146
+#endif
147
+#if !defined (TICK_INT_PRIORITY)
148
+#define  TICK_INT_PRIORITY            0x00U /*!< tick interrupt priority */
149
+#endif
150
+#if !defined (USE_RTOS)
144 151
 #define  USE_RTOS                     0U
152
+#endif
153
+#if !defined (PREFETCH_ENABLE)
145 154
 #define  PREFETCH_ENABLE              1U
155
+#endif
156
+#if !defined (INSTRUCTION_CACHE_ENABLE)
146 157
 #define  INSTRUCTION_CACHE_ENABLE     1U
158
+#endif
159
+#if !defined (DATA_CACHE_ENABLE)
147 160
 #define  DATA_CACHE_ENABLE            1U
161
+#endif
148 162
 
149 163
 #define  USE_HAL_ADC_REGISTER_CALLBACKS         0U /* ADC register callback disabled       */
150 164
 #define  USE_HAL_CAN_REGISTER_CALLBACKS         0U /* CAN register callback disabled       */
@@ -186,7 +200,7 @@ in voltage and temperature.*/
186 200
 #define  USE_HAL_WWDG_REGISTER_CALLBACKS        0U /* WWDG register callback disabled      */
187 201
 
188 202
 /* ########################## Assert Selection ############################## */
189
- /**
203
+/**
190 204
   * @brief Uncomment the line below to expanse the "assert_param" macro in the
191 205
   *        HAL drivers code
192 206
   */
@@ -215,32 +229,32 @@ in voltage and temperature.*/
215 229
 /* DP83848_PHY_ADDRESS Address*/
216 230
 #define DP83848_PHY_ADDRESS           0x01U
217 231
 /* PHY Reset delay these values are based on a 1 ms Systick interrupt*/
218
-#define PHY_RESET_DELAY                 ((uint32_t)0x000000FFU)
232
+#define PHY_RESET_DELAY                 0x000000FFU
219 233
 /* PHY Configuration delay */
220
-#define PHY_CONFIG_DELAY                ((uint32_t)0x00000FFFU)
234
+#define PHY_CONFIG_DELAY                0x00000FFFU
221 235
 
222
-#define PHY_READ_TO                     ((uint32_t)0x0000FFFFU)
223
-#define PHY_WRITE_TO                    ((uint32_t)0x0000FFFFU)
236
+#define PHY_READ_TO                     0x0000FFFFU
237
+#define PHY_WRITE_TO                    0x0000FFFFU
224 238
 
225 239
 /* Section 3: Common PHY Registers */
226 240
 
227
-#define PHY_BCR                         ((uint16_t)0x0000U)    /*!< Transceiver Basic Control Register   */
228
-#define PHY_BSR                         ((uint16_t)0x0001U)    /*!< Transceiver Basic Status Register    */
241
+#define PHY_BCR                         ((uint16_t)0x0000)  /*!< Transceiver Basic Control Register   */
242
+#define PHY_BSR                         ((uint16_t)0x0001)  /*!< Transceiver Basic Status Register    */
229 243
 
230
-#define PHY_RESET                       ((uint16_t)0x8000U)  /*!< PHY Reset */
231
-#define PHY_LOOPBACK                    ((uint16_t)0x4000U)  /*!< Select loop-back mode */
232
-#define PHY_FULLDUPLEX_100M             ((uint16_t)0x2100U)  /*!< Set the full-duplex mode at 100 Mb/s */
233
-#define PHY_HALFDUPLEX_100M             ((uint16_t)0x2000U)  /*!< Set the half-duplex mode at 100 Mb/s */
234
-#define PHY_FULLDUPLEX_10M              ((uint16_t)0x0100U)  /*!< Set the full-duplex mode at 10 Mb/s  */
235
-#define PHY_HALFDUPLEX_10M              ((uint16_t)0x0000U)  /*!< Set the half-duplex mode at 10 Mb/s  */
236
-#define PHY_AUTONEGOTIATION             ((uint16_t)0x1000U)  /*!< Enable auto-negotiation function     */
237
-#define PHY_RESTART_AUTONEGOTIATION     ((uint16_t)0x0200U)  /*!< Restart auto-negotiation function    */
238
-#define PHY_POWERDOWN                   ((uint16_t)0x0800U)  /*!< Select the power down mode           */
239
-#define PHY_ISOLATE                     ((uint16_t)0x0400U)  /*!< Isolate PHY from MII                 */
244
+#define PHY_RESET                       ((uint16_t)0x8000)  /*!< PHY Reset */
245
+#define PHY_LOOPBACK                    ((uint16_t)0x4000)  /*!< Select loop-back mode */
246
+#define PHY_FULLDUPLEX_100M             ((uint16_t)0x2100)  /*!< Set the full-duplex mode at 100 Mb/s */
247
+#define PHY_HALFDUPLEX_100M             ((uint16_t)0x2000)  /*!< Set the half-duplex mode at 100 Mb/s */
248
+#define PHY_FULLDUPLEX_10M              ((uint16_t)0x0100)  /*!< Set the full-duplex mode at 10 Mb/s  */
249
+#define PHY_HALFDUPLEX_10M              ((uint16_t)0x0000)  /*!< Set the half-duplex mode at 10 Mb/s  */
250
+#define PHY_AUTONEGOTIATION             ((uint16_t)0x1000)  /*!< Enable auto-negotiation function     */
251
+#define PHY_RESTART_AUTONEGOTIATION     ((uint16_t)0x0200)  /*!< Restart auto-negotiation function    */
252
+#define PHY_POWERDOWN                   ((uint16_t)0x0800)  /*!< Select the power down mode           */
253
+#define PHY_ISOLATE                     ((uint16_t)0x0400)  /*!< Isolate PHY from MII                 */
240 254
 
241
-#define PHY_AUTONEGO_COMPLETE           ((uint16_t)0x0020U)  /*!< Auto-Negotiation process completed   */
242
-#define PHY_LINKED_STATUS               ((uint16_t)0x0004U)  /*!< Valid link established               */
243
-#define PHY_JABBER_DETECTION            ((uint16_t)0x0002U)  /*!< Jabber condition detected            */
255
+#define PHY_AUTONEGO_COMPLETE           ((uint16_t)0x0020)  /*!< Auto-Negotiation process completed   */
256
+#define PHY_LINKED_STATUS               ((uint16_t)0x0004)  /*!< Valid link established               */
257
+#define PHY_JABBER_DETECTION            ((uint16_t)0x0002)  /*!< Jabber condition detected            */
244 258
 
245 259
 /* Section 4: Extended PHY Registers */
246 260
 #define PHY_SR                          ((uint16_t)0x10U)    /*!< PHY status register Offset                      */
@@ -251,14 +265,15 @@ in voltage and temperature.*/
251 265
 /* ################## SPI peripheral configuration ########################## */
252 266
 
253 267
 /* CRC FEATURE: Use to activate CRC feature inside HAL SPI Driver
254
-* Activated: CRC code is present inside driver
255
-* Deactivated: CRC code cleaned from driver
256
-*/
257
-
268
+ * Activated: CRC code is present inside driver
269
+ * Deactivated: CRC code cleaned from driver
270
+ */
271
+#ifndef USE_SPI_CRC
258 272
 #define USE_SPI_CRC                     0U
273
+#endif
259 274
 
260 275
 /* Includes ------------------------------------------------------------------*/
261
- /**
276
+/**
262 277
   * @brief Include module's header file
263 278
   */
264 279
 
@@ -456,9 +471,9 @@ in voltage and temperature.*/
456 471
 
457 472
 /* Exported macro ------------------------------------------------------------*/
458 473
 #ifdef USE_FULL_ASSERT
459
- /**
474
+/**
460 475
   * @brief  The assert_param macro is used for function's parameters check.
461
-  * @param  expr: If expr is false, it calls assert_failed function
476
+  * @param  expr If expr is false, it calls assert_failed function
462 477
   *         which reports the name of the source file and the source
463 478
   *         line number of the call that failed.
464 479
   *         If expr is true, it returns no value.
@@ -475,7 +490,7 @@ void assert_failed(uint8_t *file, uint32_t line);
475 490
 }
476 491
 #endif
477 492
 
478
-#endif /* __STM32F4xx_HAL_CONF_H */
493
+#endif /* __STM32F4xx_HAL_CONF_CUSTOM_H */
479 494
 
480 495
 
481 496
 /************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/

+ 36
- 16
buildroot/share/PlatformIO/variants/MARLIN_F407VE/ldscript.ld Datei anzeigen

@@ -1,10 +1,11 @@
1 1
 /*
2 2
 *****************************************************************************
3 3
 **
4
-**  File        : LinkerScript.ld
4
+
5
+**  File        : lscript.ld
5 6
 **
6
-**  Abstract    : Linker script for STM32F407VETx Device with
7
-**                512KByte FLASH, 128KByte RAM
7
+**  Abstract    : Linker script for STM32F407(VZ)(EG)Tx Device with
8
+**                512/1024KByte FLASH, 128KByte RAM
8 9
 **
9 10
 **                Set heap size, stack size and stack location according
10 11
 **                to application requirements.
@@ -17,13 +18,32 @@
17 18
 **  Distribution: The file is distributed as is, without any warranty
18 19
 **                of any kind.
19 20
 **
20
-**  (c)Copyright Ac6.
21
-**  You may use this file as-is or modify it according to the needs of your
22
-**  project. Distribution of this file (unmodified or modified) is not
23
-**  permitted. Ac6 permit registered System Workbench for MCU users the
24
-**  rights to distribute the assembled, compiled & linked contents of this
25
-**  file as part of an application binary file, provided that it is built
26
-**  using the System Workbench for MCU toolchain.
21
+*****************************************************************************
22
+** @attention
23
+**
24
+** <h2><center>&copy; COPYRIGHT(c) 2014 Ac6</center></h2>
25
+**
26
+** Redistribution and use in source and binary forms, with or without modification,
27
+** are permitted provided that the following conditions are met:
28
+**   1. Redistributions of source code must retain the above copyright notice,
29
+**      this list of conditions and the following disclaimer.
30
+**   2. Redistributions in binary form must reproduce the above copyright notice,
31
+**      this list of conditions and the following disclaimer in the documentation
32
+**      and/or other materials provided with the distribution.
33
+**   3. Neither the name of Ac6 nor the names of its contributors
34
+**      may be used to endorse or promote products derived from this software
35
+**      without specific prior written permission.
36
+**
37
+** THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
38
+** AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
39
+** IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
40
+** DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE
41
+** FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL
42
+** DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR
43
+** SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
44
+** CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY,
45
+** OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE
46
+** OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
27 47
 **
28 48
 *****************************************************************************
29 49
 */
@@ -32,7 +52,7 @@
32 52
 ENTRY(Reset_Handler)
33 53
 
34 54
 /* Highest address of the user mode stack */
35
-_estack = 0x20020000;    /* end of RAM */
55
+_estack = 0x20000000 + LD_MAX_DATA_SIZE;    /* end of RAM */
36 56
 /* Generate a link error if heap and stack don't fit into RAM */
37 57
 _Min_Heap_Size = 0x200;      /* required amount of heap  */
38 58
 _Min_Stack_Size = 0x400; /* required amount of stack */
@@ -40,9 +60,9 @@ _Min_Stack_Size = 0x400; /* required amount of stack */
40 60
 /* Specify the memory areas */
41 61
 MEMORY
42 62
 {
43
-RAM (xrw)      : ORIGIN = 0x20000000, LENGTH = 128K
63
+RAM (xrw)      : ORIGIN = 0x20000000, LENGTH = LD_MAX_DATA_SIZE
44 64
 CCMRAM (rw)      : ORIGIN = 0x10000000, LENGTH = 64K
45
-FLASH (rx)      : ORIGIN = 0x8000000, LENGTH = 512K
65
+FLASH (rx)      : ORIGIN = 0x8000000 + LD_FLASH_OFFSET, LENGTH = LD_MAX_SIZE - LD_FLASH_OFFSET
46 66
 }
47 67
 
48 68
 /* Define output sections */
@@ -57,7 +77,7 @@ SECTIONS
57 77
   } >FLASH
58 78
 
59 79
   /* The program code and other data goes into FLASH */
60
-  .text ALIGN(8):
80
+  .text ALIGN(4):
61 81
   {
62 82
     . = ALIGN(4);
63 83
     *(.text)           /* .text sections (code) */
@@ -164,12 +184,12 @@ SECTIONS
164 184
   /* User_heap_stack section, used to check that there is enough RAM left */
165 185
   ._user_heap_stack :
166 186
   {
167
-    . = ALIGN(8);
187
+    . = ALIGN(4);
168 188
     PROVIDE ( end = . );
169 189
     PROVIDE ( _end = . );
170 190
     . = . + _Min_Heap_Size;
171 191
     . = . + _Min_Stack_Size;
172
-    . = ALIGN(8);
192
+    . = ALIGN(4);
173 193
   } >RAM
174 194
 
175 195
   /* Remove information from the standard libraries */

+ 80
- 4
buildroot/share/PlatformIO/variants/MARLIN_F407VE/variant.cpp Datei anzeigen

@@ -28,12 +28,13 @@
28 28
  *******************************************************************************
29 29
  */
30 30
 
31
-#include "variant.h"
31
+#include "pins_arduino.h"
32 32
 
33 33
 #ifdef __cplusplus
34 34
 extern "C" {
35 35
 #endif
36 36
 
37
+#if defined(ARDUINO_BLACK_F407VE) || defined(ARDUINO_BLACK_F407VG)
37 38
 // Pin number
38 39
 // This array allows to wrap Arduino pin number(Dx or x)
39 40
 // to STM32 PinName (PX_n)
@@ -93,23 +94,98 @@ const PinName digitalPin[] = {
93 94
   PB_13,  PB_14,
94 95
   PB_4,
95 96
 };
97
+#endif // ARDUINO_BLACK_F407VE || ARDUINO_BLACK_F407VG
98
+
99
+#if defined(ARDUINO_BLACK_F407ZE) || defined(ARDUINO_BLACK_F407ZG)
100
+const PinName digitalPin[] = {
101
+  // Left Side
102
+  //Ext   //Int
103
+  //GND   //5V
104
+  //GND   //3V3
105
+  PB_12,  PB_13,
106
+  PB_14,  PB_15,
107
+  PD_8,   PD_9,
108
+  PD_10,  PD_11,
109
+  PD_12,  PD_13,
110
+  PD_14,  PD_15,
111
+  PG_2,   PG_3,
112
+  PG_4,   PG_5,
113
+  PG_6,   PG_7,
114
+  PG_8,   PC_6,
115
+  PC_7,   PC_8,
116
+  PC_9,   PA_8,
117
+  PA_9,   PA_10,
118
+  PA_11,  PA_12,   // PA_11: USB_DM, PA_12: USB_DP
119
+  PA_13,  PA_14,
120
+  PA_15,  PC_10,
121
+  PC_11,  PC_12,
122
+  PD_0,   PD_1,
123
+  PD_2,   PD_3,
124
+  PD_4,   PD_5,
125
+  PD_6,   PD_7,
126
+  PG_9,   PG_10,
127
+  PG_11,  PG_12,
128
+  PG_13,  PG_14,
129
+  PG_15,  PB_3,
130
+  PB_4,   PB_5,
131
+  PB_6,   PB_7,
132
+  PB_8,   PB_9,
133
+
134
+  // Right Side
135
+  //Int   //Ext
136
+  //3V3   //3V3
137
+  //BOOT1 //BOOT0
138
+  //GND   //GND
139
+  //VREF+ //GND
140
+  PB_10,  PB_11,
141
+  PE_14,  PE_15,
142
+  PE_12,  PE_13,
143
+  PE_10,  PE_11,
144
+  PE_8,   PE_9,
145
+  PG_1,   PE_7,
146
+  PF_15,  PG_0,
147
+  PF_13,  PF_14,
148
+  PF_11,  PF_12,
149
+  PB_2,   // PB1 PB2 Inverted to allow contiguous analog pins
150
+  PB_1,
151
+  PC_5,   PB_0,
152
+  PA_7,   PC_4,
153
+  PA_5,   PA_6,
154
+  PA_3,   PA_4,
155
+  PA_1,   PA_2,
156
+  PC_3,   PA_0,   // PA_0(WK_UP): BUT K_UP)
157
+  PC_1,   PC_2,
158
+  /*PF_10,*/PC_0,   // PF_10: Moved to allow contiguous analog pins
159
+  PF_8, /*PF_9,*/ // PF_9: Moved to allow contiguous analog pins
160
+  PF_6,   PF_7,
161
+  PF_10,  PF_9,   // PF_10: LED D2, PF_9: LED D1 (active low)
162
+  PF_4,   PF_5,
163
+  PF_2,   PF_3,
164
+  PF_0,   PF_1,
165
+  PE_6,   PC_13,
166
+  PE_4,   PE_5,   // PE_4: BUT K0, PE_5: BUT K1
167
+  PE_2,   PE_3,
168
+  PE_0,   PE_1,
169
+};
170
+#endif // ARDUINO_BLACK_F407ZE || ARDUINO_BLACK_F407ZG
96 171
 
97 172
 #ifdef __cplusplus
98 173
 }
99 174
 #endif
100 175
 
101
-// ------------------------
176
+// ----------------------------------------------------------------------------
102 177
 
103 178
 #ifdef __cplusplus
104 179
 extern "C" {
105 180
 #endif
106 181
 
107
- /**
182
+/**
108 183
   * @brief  System Clock Configuration
109 184
   * @param  None
110 185
   * @retval None
111 186
   */
112
-WEAK void SystemClock_Config() {
187
+WEAK void SystemClock_Config(void)
188
+{
113 189
 
114 190
   RCC_OscInitTypeDef RCC_OscInitStruct;
115 191
   RCC_ClkInitTypeDef RCC_ClkInitStruct;

+ 144
- 6
buildroot/share/PlatformIO/variants/MARLIN_F407VE/variant.h Datei anzeigen

@@ -27,12 +27,12 @@
27 27
  * OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
28 28
  *******************************************************************************
29 29
  */
30
-#pragma once
31 30
 
31
+#ifndef _VARIANT_ARDUINO_STM32_
32
+#define _VARIANT_ARDUINO_STM32_
32 33
 /*----------------------------------------------------------------------------
33 34
  *        Headers
34 35
  *----------------------------------------------------------------------------*/
35
-#include <PeripheralPins.h>
36 36
 
37 37
 #ifdef __cplusplus
38 38
 extern "C" {
@@ -41,7 +41,7 @@ extern "C" {
41 41
 /*----------------------------------------------------------------------------
42 42
  *        Pins
43 43
  *----------------------------------------------------------------------------*/
44
-extern const PinName digitalPin[];
44
+#if defined(ARDUINO_BLACK_F407VE) || defined(ARDUINO_BLACK_F407VG)
45 45
 // Right Side
46 46
 #define PE1  0
47 47
 #define PE0  1
@@ -133,9 +133,9 @@ extern const PinName digitalPin[];
133 133
 //#define DACC_RESOLUTION         12
134 134
 
135 135
 // PWM resolution
136
-#define PWM_RESOLUTION          8
137
-#define PWM_FREQUENCY           20000
138
-#define PWM_MAX_DUTY_CYCLE      255
136
+//#define PWM_RESOLUTION          8
137
+//#define PWM_FREQUENCY           20000
138
+//#define PWM_MAX_DUTY_CYCLE      255
139 139
 
140 140
 // On-board LED pin number
141 141
 #define LED_D2                  PA6
@@ -144,6 +144,138 @@ extern const PinName digitalPin[];
144 144
 // Board specific button
145 145
 #define BTN_K_UP                PA0
146 146
 
147
+#endif // ARDUINO_BLACK_F407VE || ARDUINO_BLACK_F407VG
148
+
149
+#if defined(ARDUINO_BLACK_F407ZE) || defined(ARDUINO_BLACK_F407ZG)
150
+// Left Side
151
+#define PB12 0
152
+#define PB13 1
153
+#define PB14 2
154
+#define PB15 3
155
+#define PD8  4
156
+#define PD9  5
157
+#define PD10 6
158
+#define PD11 7
159
+#define PD12 8
160
+#define PD13 9
161
+#define PD14 10
162
+#define PD15 11
163
+#define PG2  12
164
+#define PG3  13
165
+#define PG4  14
166
+#define PG5  15
167
+#define PG6  16
168
+#define PG7  17
169
+#define PG8  18
170
+#define PC6  19
171
+#define PC7  20
172
+#define PC8  21
173
+#define PC9  22
174
+#define PA8  23
175
+#define PA9  24
176
+#define PA10 25
177
+#define PA11 26 // USB_DM
178
+#define PA12 27 // USB_DP
179
+#define PA13 28
180
+#define PA14 29
181
+#define PA15 30
182
+#define PC10 31
183
+#define PC11 32
184
+#define PC12 33
185
+#define PD0  34
186
+#define PD1  35
187
+#define PD2  36
188
+#define PD3  37
189
+#define PD4  38
190
+#define PD5  39
191
+#define PD6  40
192
+#define PD7  41
193
+#define PG9  42
194
+#define PG10 43
195
+#define PG11 44
196
+#define PG12 45
197
+#define PG13 46
198
+#define PG14 47
199
+#define PG15 48
200
+#define PB3  49
201
+#define PB4  50
202
+#define PB5  51
203
+#define PB6  52
204
+#define PB7  53
205
+#define PB8  54
206
+#define PB9  55
207
+
208
+// Right Side
209
+#define PB10 56
210
+#define PB11 57
211
+#define PE14 58
212
+#define PE15 59
213
+#define PE12 60
214
+#define PE13 61
215
+#define PE10 62
216
+#define PE11 63
217
+#define PE8  64
218
+#define PE9  65
219
+#define PG1  66
220
+#define PE7  67
221
+#define PF15 68
222
+#define PG0  69
223
+#define PF13 70
224
+#define PF14 71
225
+#define PF11 72
226
+#define PF12 73
227
+#define PB2  74
228
+#define PB1  75 // A0
229
+#define PC5  76 // A1
230
+#define PB0  77 // A2
231
+#define PA7  78 // A3
232
+#define PC4  79 // A4
233
+#define PA5  80 // A5
234
+#define PA6  81 // A6
235
+#define PA3  82 // A7
236
+#define PA4  83 // A8
237
+#define PA1  84 // A9
238
+#define PA2  85 // A10
239
+#define PC3  86 // A11
240
+#define PA0  87 // A12/PA_0(WK_UP): BUT K_UP)
241
+#define PC1  88 // A13
242
+#define PC2  89 // A14
243
+#define PC0  90 // A15
244
+#define PF8  91 // A16
245
+#define PF6  92 // A17
246
+#define PF7  93 // A18
247
+#define PF9  94 // LED D1 (active low)
248
+#define PF10 95 // LED D2 (active low)
249
+#define PF4  96
250
+#define PF5  97
251
+#define PF2  98
252
+#define PF3  99
253
+#define PF0  100
254
+#define PF1  101
255
+#define PE6  102
256
+#define PC13 103
257
+#define PE4  104 // BUT K0
258
+#define PE5  105 // BUT K1
259
+#define PE2  106
260
+#define PE3  107
261
+#define PE0  108
262
+#define PE1  109
263
+
264
+// This must be a literal
265
+#define NUM_DIGITAL_PINS        110
266
+// This must be a literal with a value less than or equal to MAX_ANALOG_INPUTS
267
+#define NUM_ANALOG_INPUTS       19
268
+#define NUM_ANALOG_FIRST        75
269
+
270
+// On-board LED pin number
271
+#define LED_D2                  PF10
272
+#define LED_D1                  PF9
273
+
274
+// Board specific button
275
+#define BTN_WK_UP                PA0
276
+
277
+#endif // ARDUINO_BLACK_F407ZE || ARDUINO_BLACK_F407ZG
278
+
147 279
 #define LED_BUILTIN             LED_D2
148 280
 #define LED_GREEN               LED_D2
149 281
 
@@ -187,6 +319,10 @@ extern const PinName digitalPin[];
187 319
 #define PIN_SERIAL_RX           PA10
188 320
 #define PIN_SERIAL_TX           PA9
189 321
 
322
+/* Extra HAL modules */
323
+#define HAL_DAC_MODULE_ENABLED
324
+#define HAL_SD_MODULE_ENABLED
325
+
190 326
 #ifdef __cplusplus
191 327
 } // extern "C"
192 328
 #endif
@@ -213,3 +349,5 @@ extern const PinName digitalPin[];
213 349
 #define SERIAL_PORT_MONITOR     Serial
214 350
 #define SERIAL_PORT_HARDWARE    Serial1
215 351
 #endif
352
+
353
+#endif /* _VARIANT_ARDUINO_STM32_ */

+ 34
- 25
platformio.ini Datei anzeigen

@@ -352,12 +352,15 @@ monitor_speed = 250000
352 352
 # ARMED (STM32)
353 353
 #
354 354
 [env:ARMED]
355
-platform    = ststm32@5.6.0
355
+platform    = ststm32@>=5.7.0
356 356
 framework   = arduino
357 357
 board       = armed_v1
358
-build_flags = ${common.build_flags} -DUSBCON -DUSBD_VID=0x0483 '-DUSB_MANUFACTURER="Unknown"' '-DUSB_PRODUCT="ARMED_V1"' -DHAL_PCD_MODULE_ENABLED -DUSBD_USE_CDC -O2 -ffreestanding -fsigned-char -fno-move-loop-invariants -fno-strict-aliasing -std=gnu11 -std=gnu++11
358
+build_flags =
359
+  ${common.build_flags} -DUSBCON -DUSBD_VID=0x0483 '-DUSB_MANUFACTURER="Unknown"' '-DUSB_PRODUCT="ARMED_V1"' -DUSBD_USE_CDC
360
+  -O2 -ffreestanding -fsigned-char -fno-move-loop-invariants -fno-strict-aliasing -std=gnu11 -std=gnu++11
361
+  -IMarlin/src/HAL/HAL_STM32
359 362
 lib_deps    = ${common.lib_deps}
360
-lib_ignore  = Adafruit NeoPixel
363
+lib_ignore  = Adafruit NeoPixel, SoftwareSerial
361 364
 src_filter  = ${common.default_src_filter} +<src/HAL/HAL_STM32>
362 365
 monitor_speed = 250000
363 366
 
@@ -460,38 +463,44 @@ monitor_speed = 250000
460 463
 # Shield - https://github.com/jmz52/Hardware
461 464
 #
462 465
 [env:STM32F407VE_black]
463
-platform      = ststm32@5.4.3
464
-framework     = arduino
465
-board         = blackSTM32F407VET6
466
-extra_scripts = pre:buildroot/share/PlatformIO/scripts/black_stm32f407vet6.py
467
-build_flags   = ${common.build_flags}
468
-  -DSTM32F4 -DUSBCON -DUSBD_USE_CDC -DUSBD_VID=0x0483 -DUSB_PRODUCT=\"BLACK_F407VE\"
469
-lib_deps      = ${common.lib_deps}
470
-lib_ignore    = Adafruit NeoPixel, TMCStepper, SailfishLCD, SailfishRGB_LED, SlowSoftI2CMaster
471
-src_filter    = ${common.default_src_filter} +<src/HAL/HAL_STM32>
472
-monitor_speed = 250000
466
+platform          = ststm32@>=5.7.0
467
+framework         = arduino
468
+platform_packages = framework-arduinoststm32@>=3.10700.191028
469
+board             = blackSTM32F407VET6
470
+extra_scripts     = pre:buildroot/share/PlatformIO/scripts/generic_create_variant.py
471
+build_flags       = ${common.build_flags}
472
+ -DTARGET_STM32F4 -DARDUINO_BLACK_F407VE
473
+ -DUSBCON -DUSBD_USE_CDC -DUSBD_VID=0x0483 -DUSB_PRODUCT=\"BLACK_F407VE\"
474
+  -IMarlin/src/HAL/HAL_STM32
475
+lib_deps          = ${common.lib_deps}
476
+lib_ignore        = Adafruit NeoPixel, TMCStepper, SailfishLCD, SailfishRGB_LED, SlowSoftI2CMaster, SoftwareSerial
477
+src_filter        = ${common.default_src_filter} +<src/HAL/HAL_STM32>
478
+monitor_speed     = 250000
473 479
 
474 480
 #
475 481
 # Bigtreetech SKR Pro (STM32F407ZGT6 ARM Cortex-M4)
476 482
 #
477 483
 [env:BIGTREE_SKR_PRO]
478
-platform      = ststm32@5.6.0
479
-framework     = arduino
480
-board         = BigTree_SKR_Pro
481
-extra_scripts = pre:buildroot/share/PlatformIO/scripts/generic_create_variant.py
482
-build_flags   = ${common.build_flags}
484
+platform          = ststm32@>=5.7.0
485
+framework         = arduino
486
+platform_packages = framework-arduinoststm32@>=3.10700.191028
487
+board             = BigTree_SKR_Pro
488
+extra_scripts     = pre:buildroot/share/PlatformIO/scripts/generic_create_variant.py
489
+build_flags       = ${common.build_flags}
483 490
   -DUSBCON -DUSBD_USE_CDC -DUSBD_VID=0x0483 -DUSB_PRODUCT=\"STM32F407ZG\"
484
-  -DTARGET_STM32F4 -DSTM32F407_5ZX -DVECT_TAB_OFFSET=0x8000 -DHAVE_HWSERIAL6 -DSS_TIMER=4
485
-lib_deps      =
491
+  -DTARGET_STM32F4 -DSTM32F407_5ZX -DVECT_TAB_OFFSET=0x8000
492
+  -DHAVE_HWSERIAL6
493
+  -IMarlin/src/HAL/HAL_STM32
494
+lib_deps          =
486 495
   U8glib-HAL=https://github.com/MarlinFirmware/U8glib-HAL/archive/bugfix.zip
487
-  LiquidCrystal@1.3.4
496
+  LiquidCrystal
488 497
   TMCStepper@>=0.5.2,<1.0.0
489 498
   Adafruit NeoPixel
490 499
   LiquidTWI2=https://github.com/lincomatic/LiquidTWI2/archive/master.zip
491 500
   Arduino-L6470=https://github.com/ameyer/Arduino-L6470/archive/dev.zip
492
-  SoftwareSerialM=https://github.com/sjasonsmith/SoftwareSerialM/archive/SKR_PRO.zip
493
-src_filter    = ${common.default_src_filter} +<src/HAL/HAL_STM32>
494
-monitor_speed = 250000
501
+lib_ignore        = SoftwareSerial, SoftwareSerialM
502
+src_filter        = ${common.default_src_filter} +<src/HAL/HAL_STM32>
503
+monitor_speed     = 250000
495 504
 
496 505
 #
497 506
 # BIGTREE_SKR_BTT002 (STM32F407VET6 ARM Cortex-M4)
@@ -531,7 +540,7 @@ monitor_speed = 250000
531 540
 # Malyan M200 (STM32F103CB)
532 541
 #
533 542
 [env:STM32F103CB_malyan]
534
-platform    = ststm32@5.6.0
543
+platform    = ststm32@>=5.7.0
535 544
 framework   = arduino
536 545
 board       = malyanM200
537 546
 build_flags = !python Marlin/src/HAL/HAL_STM32F1/build_flags.py -DMCU_STM32F103CB -D __STM32F1__=1 -std=c++1y -D MOTHERBOARD="BOARD_MALYAN_M200" -DSERIAL_USB -ffunction-sections -fdata-sections -Wl,--gc-sections

Laden…
Abbrechen
Speichern