Pārlūkot izejas kodu

Bring STM32F4/F7 together

Scott Lahteine 6 gadus atpakaļ
vecāks
revīzija
ad1c061e7b
49 mainītis faili ar 198 papildinājumiem un 1906 dzēšanām
  1. 2
    4
      Marlin/src/HAL/HAL.h
  2. 1
    1
      Marlin/src/HAL/HAL_STM32/persistent_store_impl.cpp
  3. 2
    4
      Marlin/src/HAL/HAL_STM32/pinsDebug_STM32GENERIC.h
  4. 2
    2
      Marlin/src/HAL/HAL_STM32F1/persistent_store_eeprom.cpp
  5. 0
    111
      Marlin/src/HAL/HAL_STM32F4/EmulatedEeprom.cpp
  6. 0
    53
      Marlin/src/HAL/HAL_STM32F4/HAL_Servo_STM32F4.cpp
  7. 0
    37
      Marlin/src/HAL/HAL_STM32F4/SanityCheck.h
  8. 0
    153
      Marlin/src/HAL/HAL_STM32F4/fastio_STM32F4.h
  9. 0
    69
      Marlin/src/HAL/HAL_STM32F4/persistent_store_eeprom.cpp
  10. 0
    27
      Marlin/src/HAL/HAL_STM32F4/pinsDebug.h
  11. 0
    525
      Marlin/src/HAL/HAL_STM32F7/EEPROM_Emul/eeprom_emul.cpp
  12. 0
    109
      Marlin/src/HAL/HAL_STM32F7/EEPROM_Emul/eeprom_emul.h
  13. 0
    107
      Marlin/src/HAL/HAL_STM32F7/HAL.cpp
  14. 0
    208
      Marlin/src/HAL/HAL_STM32F7/HAL.h
  15. 0
    37
      Marlin/src/HAL/HAL_STM32F7/HAL_Servo_STM32F7.h
  16. 0
    160
      Marlin/src/HAL/HAL_STM32F7/HAL_spi_STM32F7.cpp
  17. 0
    64
      Marlin/src/HAL/HAL_STM32F7/endstop_interrupts.h
  18. 0
    27
      Marlin/src/HAL/HAL_STM32F7/spi_pins.h
  19. 0
    52
      Marlin/src/HAL/HAL_STM32F7/watchdog_STM32F7.cpp
  20. 23
    10
      Marlin/src/HAL/HAL_STM32_F4_F7/EmulatedEeprom.cpp
  21. 7
    12
      Marlin/src/HAL/HAL_STM32_F4_F7/HAL.cpp
  22. 15
    11
      Marlin/src/HAL/HAL_STM32_F4_F7/HAL.h
  23. 4
    4
      Marlin/src/HAL/HAL_STM32_F4_F7/HAL_Servo_STM32_F4_F7.cpp
  24. 6
    3
      Marlin/src/HAL/HAL_STM32_F4_F7/HAL_Servo_STM32_F4_F7.h
  25. 4
    11
      Marlin/src/HAL/HAL_STM32_F4_F7/HAL_spi_STM32_F4_F7.cpp
  26. 8
    7
      Marlin/src/HAL/HAL_STM32_F4_F7/HAL_timers_STM32_F4_F7.h
  27. 6
    0
      Marlin/src/HAL/HAL_STM32_F4_F7/README.md
  28. 2
    2
      Marlin/src/HAL/HAL_STM32_F4_F7/STM32F4/HAL_timers_STM32F4.cpp
  29. 0
    0
      Marlin/src/HAL/HAL_STM32_F4_F7/STM32F4/HAL_timers_STM32F4.h
  30. 0
    0
      Marlin/src/HAL/HAL_STM32_F4_F7/STM32F4/README.md
  31. 5
    6
      Marlin/src/HAL/HAL_STM32_F4_F7/STM32F7/HAL_timers_STM32F7.cpp
  32. 1
    1
      Marlin/src/HAL/HAL_STM32_F4_F7/STM32F7/HAL_timers_STM32F7.h
  33. 3
    4
      Marlin/src/HAL/HAL_STM32_F4_F7/STM32F7/README.md
  34. 15
    15
      Marlin/src/HAL/HAL_STM32_F4_F7/STM32F7/TMC2660.cpp
  35. 0
    1
      Marlin/src/HAL/HAL_STM32_F4_F7/STM32F7/TMC2660.h
  36. 2
    2
      Marlin/src/HAL/HAL_STM32_F4_F7/SanityCheck.h
  37. 2
    2
      Marlin/src/HAL/HAL_STM32_F4_F7/eeprom_emul.cpp
  38. 12
    5
      Marlin/src/HAL/HAL_STM32_F4_F7/eeprom_emul.h
  39. 0
    0
      Marlin/src/HAL/HAL_STM32_F4_F7/endstop_interrupts.h
  40. 41
    37
      Marlin/src/HAL/HAL_STM32_F4_F7/fastio_STM32_F4_F7.h
  41. 4
    4
      Marlin/src/HAL/HAL_STM32_F4_F7/persistent_store_eeprom.cpp
  42. 1
    1
      Marlin/src/HAL/HAL_STM32_F4_F7/pinsDebug.h
  43. 0
    0
      Marlin/src/HAL/HAL_STM32_F4_F7/spi_pins.h
  44. 8
    9
      Marlin/src/HAL/HAL_STM32_F4_F7/watchdog_STM32_F4_F7.cpp
  45. 0
    0
      Marlin/src/HAL/HAL_STM32_F4_F7/watchdog_STM32_F4_F7.h
  46. 2
    2
      Marlin/src/HAL/HAL_TEENSY31_32/HAL_timers_Teensy.h
  47. 2
    2
      Marlin/src/module/stepper_indirection.cpp
  48. 2
    2
      Marlin/src/module/stepper_indirection.h
  49. 16
    3
      platformio.ini

+ 2
- 4
Marlin/src/HAL/HAL.h Parādīt failu

@@ -33,10 +33,8 @@
33 33
   #define HAL_PLATFORM HAL_LPC1768
34 34
 #elif defined(__STM32F1__) || defined(TARGET_STM32F1)
35 35
   #define HAL_PLATFORM HAL_STM32F1
36
-#elif defined(STM32GENERIC) && defined(STM32F4)
37
-  #define HAL_PLATFORM HAL_STM32F4
38
-#elif defined(STM32GENERIC) && defined(STM32F7)
39
-  #define HAL_PLATFORM HAL_STM32F7
36
+#elif defined(STM32GENERIC) && (defined(STM32F4) || defined(STM32F7))
37
+  #define HAL_PLATFORM HAL_STM32_F4_F7
40 38
 #elif defined(ARDUINO_ARCH_STM32)
41 39
   #define HAL_PLATFORM HAL_STM32
42 40
 #elif defined(ARDUINO_ARCH_ESP32)

+ 1
- 1
Marlin/src/HAL/HAL_STM32/persistent_store_impl.cpp Parādīt failu

@@ -83,7 +83,7 @@ bool PersistentStore::write_data(int &pos, const uint8_t *value, size_t size, ui
83 83
   return false;
84 84
 }
85 85
 
86
-bool PersistentStore::read_data(int &pos, uint8_t* value, size_t size, uint16_t *crc, const bool writing) {
86
+bool PersistentStore::read_data(int &pos, uint8_t* value, size_t size, uint16_t *crc, const bool writing/*=true*/) {
87 87
   do {
88 88
     // Read from either external EEPROM, program flash or Backup SRAM
89 89
     const uint8_t c = (

+ 2
- 4
Marlin/src/HAL/HAL_STM32/pinsDebug_STM32GENERIC.h Parādīt failu

@@ -30,10 +30,8 @@
30 30
 
31 31
 #ifdef __STM32F1__
32 32
   #include "../HAL_STM32F1/fastio_STM32F1.h"
33
-#elif defined(STM32F4)
34
-  #include "../HAL_STM32F4/fastio_STM32F4.h"
35
-#elif defined(STM32F7)
36
-  #include "../HAL_STM32F7/fastio_STM32F7.h"
33
+#elif defined(STM32F4) || defined(STM32F7)
34
+  #include "../HAL_STM32_F4_F7/fastio_STM32_F4_F7.h"
37 35
 #endif
38 36
 
39 37
 extern const stm32_pin_info PIN_MAP[BOARD_NR_GPIO_PINS];

+ 2
- 2
Marlin/src/HAL/HAL_STM32F1/persistent_store_eeprom.cpp Parādīt failu

@@ -49,10 +49,10 @@ bool PersistentStore::write_data(int &pos, const uint8_t *value, size_t size, ui
49 49
   return false;
50 50
 }
51 51
 
52
-bool PersistentStore::read_data(int &pos, uint8_t* value, size_t size, uint16_t *crc, const bool set/*=true*/) {
52
+bool PersistentStore::read_data(int &pos, uint8_t* value, size_t size, uint16_t *crc, const bool writing/*=true*/) {
53 53
   do {
54 54
     uint8_t c = eeprom_read_byte((uint8_t*)pos);
55
-    if (set && value) *value = c;
55
+    if (writing && value) *value = c;
56 56
     crc16(crc, &c, 1);
57 57
     pos++;
58 58
     value++;

+ 0
- 111
Marlin/src/HAL/HAL_STM32F4/EmulatedEeprom.cpp Parādīt failu

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

+ 0
- 53
Marlin/src/HAL/HAL_STM32F4/HAL_Servo_STM32F4.cpp Parādīt failu

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

+ 0
- 37
Marlin/src/HAL/HAL_STM32F4/SanityCheck.h Parādīt failu

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

+ 0
- 153
Marlin/src/HAL/HAL_STM32F4/fastio_STM32F4.h Parādīt failu

@@ -1,153 +0,0 @@
1
-/**
2
- * Marlin 3D Printer Firmware
3
- * Copyright (c) 2019 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
4
- *
5
- * Based on Sprinter and grbl.
6
- * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm
7
- * Copyright (c) 2017 Victor Perez
8
- *
9
- * This program is free software: you can redistribute it and/or modify
10
- * it under the terms of the GNU General Public License as published by
11
- * the Free Software Foundation, either version 3 of the License, or
12
- * (at your option) any later version.
13
- *
14
- * This program is distributed in the hope that it will be useful,
15
- * but WITHOUT ANY WARRANTY; without even the implied warranty of
16
- * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the
17
- * GNU General Public License for more details.
18
- *
19
- * You should have received a copy of the GNU General Public License
20
- * along with this program.  If not, see <http://www.gnu.org/licenses/>.
21
- *
22
- */
23
-#pragma once
24
-
25
-/**
26
- * Fast I/O interfaces for STM32F4
27
- * These use GPIO functions instead of Direct Port Manipulation, as on AVR.
28
- */
29
-
30
-#undef _BV
31
-#define _BV(b) (1 << (b))
32
-
33
-#define READ(IO)                digitalRead(IO)
34
-#define WRITE(IO,V)             digitalWrite(IO,V)
35
-
36
-#define _GET_MODE(IO)
37
-#define _SET_MODE(IO,M)         pinMode(IO, M)
38
-#define _SET_OUTPUT(IO)         pinMode(IO, OUTPUT)                               /*!< Output Push Pull Mode & GPIO_NOPULL   */
39
-
40
-#define OUT_WRITE(IO,V)         do{ _SET_OUTPUT(IO); WRITE(IO,V); }while(0)
41
-
42
-#define SET_INPUT(IO)           _SET_MODE(IO, INPUT)                              /*!< Input Floating Mode                   */
43
-#define SET_INPUT_PULLUP(IO)    _SET_MODE(IO, INPUT_PULLUP)                       /*!< Input with Pull-up activation         */
44
-#define SET_INPUT_PULLDOWN(IO)  _SET_MODE(IO, INPUT_PULLDOWN)                     /*!< Input with Pull-down activation       */
45
-#define SET_OUTPUT(IO)          OUT_WRITE(IO, LOW)
46
-#define SET_PWM(IO)             pinMode(IO, PWM)
47
-
48
-#define TOGGLE(IO)              OUT_WRITE(IO, !READ(IO))
49
-
50
-#define IS_INPUT(IO)
51
-#define IS_OUTPUT(IO)
52
-
53
-#define PWM_PIN(P)              true
54
-
55
-// digitalRead/Write wrappers
56
-#define extDigitalRead(IO)    digitalRead(IO)
57
-#define extDigitalWrite(IO,V) digitalWrite(IO,V)
58
-
59
-//
60
-// Pins Definitions
61
-//
62
-#define PORTA 0
63
-#define PORTB 1
64
-#define PORTC 2
65
-#define PORTD 3
66
-#define PORTE 4
67
-
68
-#define _STM32_PIN(P,PN) ((PORT##P * 16) + PN)
69
-
70
-#define PA0  _STM32_PIN(A,  0)
71
-#define PA1  _STM32_PIN(A,  1)
72
-#define PA2  _STM32_PIN(A,  2)
73
-#define PA3  _STM32_PIN(A,  3)
74
-#define PA4  _STM32_PIN(A,  4)
75
-#define PA5  _STM32_PIN(A,  5)
76
-#define PA6  _STM32_PIN(A,  6)
77
-#define PA7  _STM32_PIN(A,  7)
78
-#define PA8  _STM32_PIN(A,  8)
79
-#define PA9  _STM32_PIN(A,  9)
80
-#define PA10 _STM32_PIN(A, 10)
81
-#define PA11 _STM32_PIN(A, 11)
82
-#define PA12 _STM32_PIN(A, 12)
83
-#define PA13 _STM32_PIN(A, 13)
84
-#define PA14 _STM32_PIN(A, 14)
85
-#define PA15 _STM32_PIN(A, 15)
86
-
87
-#define PB0  _STM32_PIN(B,  0)
88
-#define PB1  _STM32_PIN(B,  1)
89
-#define PB2  _STM32_PIN(B,  2)
90
-#define PB3  _STM32_PIN(B,  3)
91
-#define PB4  _STM32_PIN(B,  4)
92
-#define PB5  _STM32_PIN(B,  5)
93
-#define PB6  _STM32_PIN(B,  6)
94
-#define PB7  _STM32_PIN(B,  7)
95
-#define PB8  _STM32_PIN(B,  8)
96
-#define PB9  _STM32_PIN(B,  9)
97
-#define PB10 _STM32_PIN(B, 10)
98
-#define PB11 _STM32_PIN(B, 11)
99
-#define PB12 _STM32_PIN(B, 12)
100
-#define PB13 _STM32_PIN(B, 13)
101
-#define PB14 _STM32_PIN(B, 14)
102
-#define PB15 _STM32_PIN(B, 15)
103
-
104
-#define PC0  _STM32_PIN(C,  0)
105
-#define PC1  _STM32_PIN(C,  1)
106
-#define PC2  _STM32_PIN(C,  2)
107
-#define PC3  _STM32_PIN(C,  3)
108
-#define PC4  _STM32_PIN(C,  4)
109
-#define PC5  _STM32_PIN(C,  5)
110
-#define PC6  _STM32_PIN(C,  6)
111
-#define PC7  _STM32_PIN(C,  7)
112
-#define PC8  _STM32_PIN(C,  8)
113
-#define PC9  _STM32_PIN(C,  9)
114
-#define PC10 _STM32_PIN(C, 10)
115
-#define PC11 _STM32_PIN(C, 11)
116
-#define PC12 _STM32_PIN(C, 12)
117
-#define PC13 _STM32_PIN(C, 13)
118
-#define PC14 _STM32_PIN(C, 14)
119
-#define PC15 _STM32_PIN(C, 15)
120
-
121
-#define PD0  _STM32_PIN(D,  0)
122
-#define PD1  _STM32_PIN(D,  1)
123
-#define PD2  _STM32_PIN(D,  2)
124
-#define PD3  _STM32_PIN(D,  3)
125
-#define PD4  _STM32_PIN(D,  4)
126
-#define PD5  _STM32_PIN(D,  5)
127
-#define PD6  _STM32_PIN(D,  6)
128
-#define PD7  _STM32_PIN(D,  7)
129
-#define PD8  _STM32_PIN(D,  8)
130
-#define PD9  _STM32_PIN(D,  9)
131
-#define PD10 _STM32_PIN(D, 10)
132
-#define PD11 _STM32_PIN(D, 11)
133
-#define PD12 _STM32_PIN(D, 12)
134
-#define PD13 _STM32_PIN(D, 13)
135
-#define PD14 _STM32_PIN(D, 14)
136
-#define PD15 _STM32_PIN(D, 15)
137
-
138
-#define PE0  _STM32_PIN(E,  0)
139
-#define PE1  _STM32_PIN(E,  1)
140
-#define PE2  _STM32_PIN(E,  2)
141
-#define PE3  _STM32_PIN(E,  3)
142
-#define PE4  _STM32_PIN(E,  4)
143
-#define PE5  _STM32_PIN(E,  5)
144
-#define PE6  _STM32_PIN(E,  6)
145
-#define PE7  _STM32_PIN(E,  7)
146
-#define PE8  _STM32_PIN(E,  8)
147
-#define PE9  _STM32_PIN(E,  9)
148
-#define PE10 _STM32_PIN(E, 10)
149
-#define PE11 _STM32_PIN(E, 11)
150
-#define PE12 _STM32_PIN(E, 12)
151
-#define PE13 _STM32_PIN(E, 13)
152
-#define PE14 _STM32_PIN(E, 14)
153
-#define PE15 _STM32_PIN(E, 15)

+ 0
- 69
Marlin/src/HAL/HAL_STM32F4/persistent_store_eeprom.cpp Parādīt failu

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

+ 0
- 27
Marlin/src/HAL/HAL_STM32F4/pinsDebug.h Parādīt failu

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

+ 0
- 525
Marlin/src/HAL/HAL_STM32F7/EEPROM_Emul/eeprom_emul.cpp Parādīt failu

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

+ 0
- 109
Marlin/src/HAL/HAL_STM32F7/EEPROM_Emul/eeprom_emul.h Parādīt failu

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

+ 0
- 107
Marlin/src/HAL/HAL_STM32F7/HAL.cpp Parādīt failu

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

+ 0
- 208
Marlin/src/HAL/HAL_STM32F7/HAL.h Parādīt failu

@@ -1,208 +0,0 @@
1
-/**
2
- * Marlin 3D Printer Firmware
3
- *
4
- * Copyright (c) 2019 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
5
- * Copyright (c) 2016 Bob Cousins bobcousins42@googlemail.com
6
- * Copyright (c) 2015-2016 Nico Tonnhofer wurstnase.reprap@gmail.com
7
- * Copyright (c) 2017 Victor Perez
8
- *
9
- * This program is free software: you can redistribute it and/or modify
10
- * it under the terms of the GNU General Public License as published by
11
- * the Free Software Foundation, either version 3 of the License, or
12
- * (at your option) any later version.
13
- *
14
- * This program is distributed in the hope that it will be useful,
15
- * but WITHOUT ANY WARRANTY; without even the implied warranty of
16
- * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the
17
- * GNU General Public License for more details.
18
- *
19
- * You should have received a copy of the GNU General Public License
20
- * along with this program.  If not, see <http://www.gnu.org/licenses/>.
21
- *
22
- */
23
-#pragma once
24
-
25
-#define CPU_32_BIT
26
-
27
-#ifndef vsnprintf_P
28
-  #define vsnprintf_P vsnprintf
29
-#endif
30
-
31
-#include <stdint.h>
32
-
33
-#include "../shared/Marduino.h"
34
-#include "../shared/math_32bit.h"
35
-#include "../shared/HAL_SPI.h"
36
-
37
-#include "fastio_STM32F7.h"
38
-#include "watchdog_STM32F7.h"
39
-
40
-#include "HAL_timers_STM32F7.h"
41
-
42
-#include "../../inc/MarlinConfigPre.h"
43
-
44
-// ------------------------
45
-// Defines
46
-// ------------------------
47
-
48
-//Serial override
49
-//extern HalSerial usb_serial;
50
-
51
-#if !WITHIN(SERIAL_PORT, -1, 6)
52
-  #error "SERIAL_PORT must be from -1 to 6"
53
-#endif
54
-#if SERIAL_PORT == -1
55
-  #define MYSERIAL0 SerialUSB
56
-#elif SERIAL_PORT == 1
57
-  #define MYSERIAL0 SerialUART1
58
-#elif SERIAL_PORT == 2
59
-  #define MYSERIAL0 SerialUART2
60
-#elif SERIAL_PORT == 3
61
-  #define MYSERIAL0 SerialUART3
62
-#elif SERIAL_PORT == 4
63
-  #define MYSERIAL0 SerialUART4
64
-#elif SERIAL_PORT == 5
65
-  #define MYSERIAL0 SerialUART5
66
-#elif SERIAL_PORT == 6
67
-  #define MYSERIAL0 SerialUART6
68
-#endif
69
-
70
-#ifdef SERIAL_PORT_2
71
-  #if !WITHIN(SERIAL_PORT_2, -1, 6)
72
-    #error "SERIAL_PORT_2 must be from -1 to 6"
73
-  #elif SERIAL_PORT_2 == SERIAL_PORT
74
-    #error "SERIAL_PORT_2 must be different than SERIAL_PORT"
75
-  #endif
76
-  #define NUM_SERIAL 2
77
-  #if SERIAL_PORT_2 == -1
78
-    #define MYSERIAL1 SerialUSB
79
-  #elif SERIAL_PORT_2 == 1
80
-    #define MYSERIAL1 SerialUART1
81
-  #elif SERIAL_PORT_2 == 2
82
-    #define MYSERIAL1 SerialUART2
83
-  #elif SERIAL_PORT_2 == 3
84
-    #define MYSERIAL1 SerialUART3
85
-  #elif SERIAL_PORT_2 == 4
86
-    #define MYSERIAL1 SerialUART4
87
-  #elif SERIAL_PORT_2 == 5
88
-    #define MYSERIAL1 SerialUART5
89
-  #elif SERIAL_PORT_2 == 6
90
-    #define MYSERIAL1 SerialUART6
91
-  #endif
92
-#else
93
-  #define NUM_SERIAL 1
94
-#endif
95
-
96
-#define _BV(b) (1 << (b))
97
-
98
-/**
99
- * TODO: review this to return 1 for pins that are not analog input
100
- */
101
-#ifndef analogInputToDigitalPin
102
-  #define analogInputToDigitalPin(p) (p)
103
-#endif
104
-
105
-#define CRITICAL_SECTION_START  uint32_t primask = __get_PRIMASK(); __disable_irq()
106
-#define CRITICAL_SECTION_END    if (!primask) __enable_irq()
107
-#define ISRS_ENABLED() (!__get_PRIMASK())
108
-#define ENABLE_ISRS()  __enable_irq()
109
-#define DISABLE_ISRS() __disable_irq()
110
-#define cli() __disable_irq()
111
-#define sei() __enable_irq()
112
-
113
-// On AVR this is in math.h?
114
-#define square(x) ((x)*(x))
115
-
116
-#ifndef strncpy_P
117
-  #define strncpy_P(dest, src, num) strncpy((dest), (src), (num))
118
-#endif
119
-
120
-// Fix bug in pgm_read_ptr
121
-#undef pgm_read_ptr
122
-#define pgm_read_ptr(addr) (*(addr))
123
-
124
-// ------------------------
125
-// Types
126
-// ------------------------
127
-
128
-typedef int8_t pin_t;
129
-
130
-// ------------------------
131
-// Public Variables
132
-// ------------------------
133
-
134
-/** result of last ADC conversion */
135
-extern uint16_t HAL_adc_result;
136
-
137
-// ------------------------
138
-// Public functions
139
-// ------------------------
140
-
141
-// Memory related
142
-#define __bss_end __bss_end__
143
-
144
-inline void HAL_init(void) { }
145
-
146
-/** clear reset reason */
147
-void HAL_clear_reset_source (void);
148
-
149
-/** reset reason */
150
-uint8_t HAL_get_reset_source(void);
151
-
152
-void _delay_ms(const int delay);
153
-
154
-/*
155
-extern "C" {
156
-  int freeMemory(void);
157
-}
158
-*/
159
-
160
-extern "C" char* _sbrk(int incr);
161
-/*
162
-static int freeMemory() {
163
-  volatile int top;
164
-  top = (int)((char*)&top - reinterpret_cast<char*>(_sbrk(0)));
165
-  return top;
166
-}
167
-*/
168
-static int freeMemory() {
169
-  volatile char top;
170
-  return &top - reinterpret_cast<char*>(_sbrk(0));
171
-}
172
-
173
-// SPI: Extended functions which take a channel number (hardware SPI only)
174
-/** Write single byte to specified SPI channel */
175
-void spiSend(uint32_t chan, byte b);
176
-/** Write buffer to specified SPI channel */
177
-void spiSend(uint32_t chan, const uint8_t* buf, size_t n);
178
-/** Read single byte from specified SPI channel */
179
-uint8_t spiRec(uint32_t chan);
180
-
181
-
182
-// EEPROM
183
-
184
-/**
185
- * TODO: Write all this eeprom stuff. Can emulate eeprom in flash as last resort.
186
- * Wire library should work for i2c eeproms.
187
- */
188
-void eeprom_write_byte(uint8_t *pos, unsigned char value);
189
-uint8_t eeprom_read_byte(uint8_t *pos);
190
-void eeprom_read_block (void *__dst, const void *__src, size_t __n);
191
-void eeprom_update_block (const void *__src, void *__dst, size_t __n);
192
-
193
-// ADC
194
-
195
-#define HAL_ANALOG_SELECT(pin) pinMode(pin, INPUT)
196
-
197
-inline void HAL_adc_init(void) {}
198
-
199
-#define HAL_START_ADC(pin)  HAL_adc_start_conversion(pin)
200
-#define HAL_READ_ADC()      HAL_adc_result
201
-#define HAL_ADC_READY()     true
202
-
203
-void HAL_adc_start_conversion(const uint8_t adc_pin);
204
-uint16_t HAL_adc_get_result(void);
205
-
206
-#define GET_PIN_MAP_PIN(index) index
207
-#define GET_PIN_MAP_INDEX(pin) pin
208
-#define PARSED_PIN_INDEX(code, dval) parser.intval(code, dval)

+ 0
- 37
Marlin/src/HAL/HAL_STM32F7/HAL_Servo_STM32F7.h Parādīt failu

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

+ 0
- 160
Marlin/src/HAL/HAL_STM32F7/HAL_spi_STM32F7.cpp Parādīt failu

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

+ 0
- 64
Marlin/src/HAL/HAL_STM32F7/endstop_interrupts.h Parādīt failu

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

+ 0
- 27
Marlin/src/HAL/HAL_STM32F7/spi_pins.h Parādīt failu

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

+ 0
- 52
Marlin/src/HAL/HAL_STM32F7/watchdog_STM32F7.cpp Parādīt failu

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

Marlin/src/HAL/HAL_STM32F7/EmulatedEeprom.cpp → Marlin/src/HAL/HAL_STM32_F4_F7/EmulatedEeprom.cpp Parādīt failu

@@ -17,29 +17,43 @@
17 17
  *
18 18
  */
19 19
 
20
-#ifdef STM32F7
20
+#if defined(STM32GENERIC) && (defined(STM32F4) || defined(STM32F7))
21 21
 
22 22
 /**
23 23
  * Description: Functions for a Flash emulated EEPROM
24 24
  * Not platform dependent.
25 25
  */
26 26
 
27
+// Include configs and pins to get all EEPROM flags
27 28
 #include "../../inc/MarlinConfig.h"
28 29
 
30
+#ifdef STM32F7
31
+  #define HAS_EMULATED_EEPROM 1
32
+#else
33
+  #define HAS_EMULATED_EEPROM NONE(I2C_EEPROM, SPI_EEPROM)
34
+#endif
35
+
36
+#if HAS_EMULATED_EEPROM && ENABLED(EEPROM_SETTINGS)
37
+
29 38
 // ------------------------
30 39
 // Includes
31 40
 // ------------------------
32 41
 
33 42
 #include "HAL.h"
34
-#include "EEPROM_Emul/eeprom_emul.h"
43
+#include "eeprom_emul.h"
35 44
 
36 45
 // ------------------------
37 46
 // Local defines
38 47
 // ------------------------
39 48
 
40 49
 // FLASH_FLAG_PGSERR (Programming Sequence Error) was renamed to
41
-// FLASH_FLAG_ERSERR (Erasing Sequence Error) in STM32F7
42
-#define FLASH_FLAG_PGSERR FLASH_FLAG_ERSERR
50
+// FLASH_FLAG_ERSERR (Erasing Sequence Error) in STM32F4/7
51
+
52
+#ifdef STM32F7
53
+  #define FLASH_FLAG_PGSERR FLASH_FLAG_ERSERR
54
+#else
55
+  //#define FLASH_FLAG_PGSERR FLASH_FLAG_ERSERR
56
+#endif
43 57
 
44 58
 // ------------------------
45 59
 // Private Variables
@@ -67,13 +81,12 @@ void eeprom_init() {
67 81
 }
68 82
 
69 83
 void eeprom_write_byte(uint8_t *pos, unsigned char value) {
70
-  uint16_t eeprom_address = unsigned(pos);
71
-
72 84
   eeprom_init();
73 85
 
74 86
   HAL_FLASH_Unlock();
75 87
   __HAL_FLASH_CLEAR_FLAG(FLASH_FLAG_EOP | FLASH_FLAG_OPERR | FLASH_FLAG_WRPERR |FLASH_FLAG_PGAERR | FLASH_FLAG_PGPERR | FLASH_FLAG_PGSERR);
76 88
 
89
+  uint16_t eeprom_address = unsigned(pos);
77 90
   if (EE_WriteVariable(eeprom_address, uint16_t(value)) != EE_OK)
78 91
     for (;;) HAL_Delay(1); // Spin forever until watchdog reset
79 92
 
@@ -91,11 +104,10 @@ uint8_t eeprom_read_byte(uint8_t *pos) {
91 104
 }
92 105
 
93 106
 void eeprom_read_block(void *__dst, const void *__src, size_t __n) {
94
-  uint16_t data = 0xFF;
95
-  uint16_t eeprom_address = unsigned(__src);
96
-
97 107
   eeprom_init();
98 108
 
109
+  uint16_t data = 0xFF;
110
+  uint16_t eeprom_address = unsigned(__src);
99 111
   for (uint8_t c = 0; c < __n; c++) {
100 112
     EE_ReadVariable(eeprom_address+c, &data);
101 113
     *((uint8_t*)__dst + c) = data;
@@ -106,4 +118,5 @@ void eeprom_update_block(const void *__src, void *__dst, size_t __n) {
106 118
 
107 119
 }
108 120
 
109
-#endif // STM32F7
121
+#endif // EEPROM_SETTINGS
122
+#endif // STM32GENERIC && (STM32F4 || STM32F7)

Marlin/src/HAL/HAL_STM32F4/HAL.cpp → Marlin/src/HAL/HAL_STM32_F4_F7/HAL.cpp Parādīt failu

@@ -21,7 +21,7 @@
21 21
  *
22 22
  */
23 23
 
24
-#if defined(STM32GENERIC) && defined(STM32F4)
24
+#if defined(STM32GENERIC) && (defined(STM32F4) || defined(STM32F7))
25 25
 
26 26
 #include "HAL.h"
27 27
 
@@ -49,10 +49,9 @@ void HAL_clear_reset_source(void) { __HAL_RCC_CLEAR_RESET_FLAGS(); }
49 49
 
50 50
 uint8_t HAL_get_reset_source(void) {
51 51
   if (__HAL_RCC_GET_FLAG(RCC_FLAG_IWDGRST) != RESET) return RST_WATCHDOG;
52
-
53
-  if (__HAL_RCC_GET_FLAG(RCC_FLAG_SFTRST) != RESET)  return RST_SOFTWARE;
54
-  if (__HAL_RCC_GET_FLAG(RCC_FLAG_PINRST) != RESET)  return RST_EXTERNAL;
55
-  if (__HAL_RCC_GET_FLAG(RCC_FLAG_PORRST) != RESET)  return RST_POWER_ON;
52
+  if (__HAL_RCC_GET_FLAG(RCC_FLAG_SFTRST)  != RESET) return RST_SOFTWARE;
53
+  if (__HAL_RCC_GET_FLAG(RCC_FLAG_PINRST)  != RESET) return RST_EXTERNAL;
54
+  if (__HAL_RCC_GET_FLAG(RCC_FLAG_PORRST)  != RESET) return RST_POWER_ON;
56 55
   return 0;
57 56
 }
58 57
 
@@ -90,12 +89,8 @@ extern "C" {
90 89
 // ADC
91 90
 // ------------------------
92 91
 
93
-void HAL_adc_start_conversion(const uint8_t adc_pin) {
94
-  HAL_adc_result = analogRead(adc_pin);
95
-}
92
+void HAL_adc_start_conversion(const uint8_t adc_pin) { HAL_adc_result = analogRead(adc_pin); }
96 93
 
97
-uint16_t HAL_adc_get_result(void) {
98
-  return HAL_adc_result;
99
-}
94
+uint16_t HAL_adc_get_result(void) { return HAL_adc_result; }
100 95
 
101
-#endif // // STM32GENERIC && STM32F4
96
+#endif // STM32GENERIC && (STM32F4 || STM32F7)

Marlin/src/HAL/HAL_STM32F4/HAL.h → Marlin/src/HAL/HAL_STM32_F4_F7/HAL.h Parādīt failu

@@ -27,15 +27,17 @@
27 27
 #include "../shared/Marduino.h"
28 28
 #include "../shared/math_32bit.h"
29 29
 #include "../shared/HAL_SPI.h"
30
-#include "fastio_STM32F4.h"
31
-#include "watchdog_STM32F4.h"
32
-#include "HAL_timers_STM32F4.h"
30
+
31
+#include "fastio_STM32_F4_F7.h"
32
+#include "watchdog_STM32_F4_F7.h"
33
+
34
+#include "HAL_timers_STM32_F4_F7.h"
33 35
 
34 36
 #include "../../inc/MarlinConfigPre.h"
35 37
 
36 38
 #include <stdint.h>
37 39
 
38
-#ifdef USBCON
40
+#ifdef defined(STM32F4) && USBCON
39 41
   #include <USBSerial.h>
40 42
 #endif
41 43
 
@@ -46,7 +48,7 @@
46 48
 //Serial override
47 49
 //extern HalSerial usb_serial;
48 50
 
49
-#if SERIAL_PORT == 0
51
+#if defined(STM32F4) && SERIAL_PORT == 0
50 52
   #error "Serial port 0 does not exist"
51 53
 #endif
52 54
 
@@ -70,10 +72,9 @@
70 72
 #endif
71 73
 
72 74
 #ifdef SERIAL_PORT_2
73
-  #if SERIAL_PORT_2 == 0
75
+  #if defined(STM32F4) && SERIAL_PORT_2 == 0
74 76
     #error "Serial port 0 does not exist"
75 77
   #endif
76
-
77 78
   #if !WITHIN(SERIAL_PORT_2, -1, 6)
78 79
     #error "SERIAL_PORT_2 must be from -1 to 6"
79 80
   #elif SERIAL_PORT_2 == SERIAL_PORT
@@ -99,7 +100,6 @@
99 100
   #define NUM_SERIAL 1
100 101
 #endif
101 102
 
102
-#undef _BV
103 103
 #define _BV(b) (1 << (b))
104 104
 
105 105
 /**
@@ -134,7 +134,9 @@
134 134
 
135 135
 typedef int8_t pin_t;
136 136
 
137
-#define HAL_SERVO_LIB libServo
137
+#ifdef STM32F4
138
+  #define HAL_SERVO_LIB libServo
139
+#endif
138 140
 
139 141
 // ------------------------
140 142
 // Public Variables
@@ -224,5 +226,7 @@ uint16_t HAL_adc_get_result(void);
224 226
 #define GET_PIN_MAP_INDEX(pin) pin
225 227
 #define PARSED_PIN_INDEX(code, dval) parser.intval(code, dval)
226 228
 
227
-#define JTAG_DISABLE() afio_cfg_debug_ports(AFIO_DEBUG_SW_ONLY)
228
-#define JTAGSWD_DISABLE() afio_cfg_debug_ports(AFIO_DEBUG_NONE)
229
+#ifdef STM32F4
230
+  #define JTAG_DISABLE() afio_cfg_debug_ports(AFIO_DEBUG_SW_ONLY)
231
+  #define JTAGSWD_DISABLE() afio_cfg_debug_ports(AFIO_DEBUG_NONE)
232
+#endif

Marlin/src/HAL/HAL_STM32F7/HAL_Servo_STM32F7.cpp → Marlin/src/HAL/HAL_STM32_F4_F7/HAL_Servo_STM32_F4_F7.cpp Parādīt failu

@@ -21,13 +21,13 @@
21 21
  *
22 22
  */
23 23
 
24
-#ifdef STM32F7
24
+#if defined(STM32GENERIC) && (defined(STM32F4) || defined(STM32F7))
25 25
 
26 26
 #include "../../inc/MarlinConfig.h"
27 27
 
28 28
 #if HAS_SERVOS
29 29
 
30
-#include "HAL_Servo_STM32F7.h"
30
+#include "HAL_Servo_STM32_F4_F7.h"
31 31
 
32 32
 int8_t libServo::attach(const int pin) {
33 33
   if (this->servoIndex >= MAX_SERVOS) return -1;
@@ -49,6 +49,6 @@ void libServo::move(const int value) {
49 49
     #endif
50 50
   }
51 51
 }
52
-#endif // HAS_SERVOS
53 52
 
54
-#endif // STM32F7
53
+#endif // HAS_SERVOS
54
+#endif // STM32GENERIC && (STM32F4 || STM32F7)

Marlin/src/HAL/HAL_STM32F4/HAL_Servo_STM32F4.h → Marlin/src/HAL/HAL_STM32_F4_F7/HAL_Servo_STM32_F4_F7.h Parādīt failu

@@ -22,7 +22,11 @@
22 22
  */
23 23
 #pragma once
24 24
 
25
-#include <Servo.h>
25
+//#ifdef STM32F7
26
+//  #include <../../libraries/Servo/src/Servo.h>
27
+//#else
28
+  #include <Servo.h>
29
+//#endif
26 30
 
27 31
 // Inherit and expand on the official library
28 32
 class libServo : public Servo {
@@ -31,7 +35,6 @@ class libServo : public Servo {
31 35
     int8_t attach(const int pin, const int min, const int max);
32 36
     void move(const int value);
33 37
   private:
34
-    uint16_t min_ticks;
35
-    uint16_t max_ticks;
38
+    uint16_t min_ticks, max_ticks;
36 39
     uint8_t servoIndex;               // index into the channel data for this servo
37 40
 };

Marlin/src/HAL/HAL_STM32F4/HAL_spi_STM32F4.cpp → Marlin/src/HAL/HAL_STM32_F4_F7/HAL_spi_STM32_F4_F7.cpp Parādīt failu

@@ -27,10 +27,10 @@
27 27
  */
28 28
 
29 29
 /**
30
- * Adapted to the STM32F4 HAL
30
+ * Adapted to the Marlin STM32F4/7 HAL
31 31
  */
32 32
 
33
-#if defined(STM32GENERIC) && defined(STM32F4)
33
+#if defined(STM32GENERIC) && (defined(STM32F4) || defined(STM32F7))
34 34
 
35 35
 #include "HAL.h"
36 36
 #include "../shared/HAL_SPI.h"
@@ -50,12 +50,10 @@ static SPISettings spiConfig;
50 50
 // ------------------------
51 51
 
52 52
 #if ENABLED(SOFTWARE_SPI)
53
-
54 53
   // ------------------------
55 54
   // Software SPI
56 55
   // ------------------------
57
-  #error "Software SPI not supported for STM32F4. Use hardware SPI."
58
-
56
+  #error "Software SPI not supported for STM32F4/7. Use Hardware SPI."
59 57
 #else
60 58
 
61 59
 // ------------------------
@@ -123,13 +121,11 @@ uint8_t spiRec(void) {
123 121
  */
124 122
 void spiRead(uint8_t* buf, uint16_t nbyte) {
125 123
   SPI.beginTransaction(spiConfig);
126
-
127 124
   #ifdef STM32GENERIC
128 125
     SPI.dmaTransfer(0, const_cast<uint8_t*>(buf), nbyte);
129 126
   #else
130 127
     SPI.transfer((uint8_t*)buf, nbyte);
131 128
   #endif
132
-
133 129
   SPI.endTransaction();
134 130
 }
135 131
 
@@ -157,16 +153,13 @@ void spiSend(uint8_t b) {
157 153
 void spiSendBlock(uint8_t token, const uint8_t* buf) {
158 154
   SPI.beginTransaction(spiConfig);
159 155
   SPI.transfer(token);
160
-
161 156
   #ifdef STM32GENERIC
162 157
     SPI.dmaSend(const_cast<uint8_t*>(buf), 512);
163 158
   #else
164 159
     SPI.transfer((uint8_t*)buf, nullptr, 512);
165 160
   #endif
166
-
167 161
   SPI.endTransaction();
168 162
 }
169 163
 
170 164
 #endif // SOFTWARE_SPI
171
-
172
-#endif // STM32GENERIC && STM32F4
165
+#endif // STM32GENERIC && (STM32F4 || STM32F7)

Marlin/src/HAL/HAL_STM32F7/watchdog_STM32F7.h → Marlin/src/HAL/HAL_STM32_F4_F7/HAL_timers_STM32_F4_F7.h Parādīt failu

@@ -1,9 +1,9 @@
1 1
 /**
2 2
  * Marlin 3D Printer Firmware
3
- * Copyright (c) 2019 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
4 3
  *
5
- * Based on Sprinter and grbl.
6
- * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm
4
+ * Copyright (c) 2019 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
5
+ * Copyright (c) 2016 Bob Cousins bobcousins42@googlemail.com
6
+ * Copyright (c) 2017 Victor Perez
7 7
  *
8 8
  * This program is free software: you can redistribute it and/or modify
9 9
  * it under the terms of the GNU General Public License as published by
@@ -21,7 +21,8 @@
21 21
  */
22 22
 #pragma once
23 23
 
24
-extern IWDG_HandleTypeDef hiwdg;
25
-
26
-void watchdog_init();
27
-void watchdog_reset();
24
+#ifdef STM32F4
25
+  #include "STM32F4/HAL_timers_STM32F4.h"
26
+#else
27
+  #include "STM32F7/HAL_timers_STM32F7.h"
28
+#endif

+ 6
- 0
Marlin/src/HAL/HAL_STM32_F4_F7/README.md Parādīt failu

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

Marlin/src/HAL/HAL_STM32F4/HAL_timers_STM32F4.cpp → Marlin/src/HAL/HAL_STM32_F4_F7/STM32F4/HAL_timers_STM32F4.cpp Parādīt failu

@@ -22,8 +22,7 @@
22 22
 
23 23
 #if defined(STM32GENERIC) && defined(STM32F4)
24 24
 
25
-#include "HAL.h"
26
-
25
+#include "../HAL.h"
27 26
 #include "HAL_timers_STM32F4.h"
28 27
 
29 28
 // ------------------------
@@ -35,6 +34,7 @@
35 34
 #define TEMP_TIMER_IRQ_ID TIM7_IRQn
36 35
 
37 36
 //#define PRESCALER 1
37
+
38 38
 // ------------------------
39 39
 // Private Variables
40 40
 // ------------------------

Marlin/src/HAL/HAL_STM32F4/HAL_timers_STM32F4.h → Marlin/src/HAL/HAL_STM32_F4_F7/STM32F4/HAL_timers_STM32F4.h Parādīt failu


Marlin/src/HAL/HAL_STM32F4/README.md → Marlin/src/HAL/HAL_STM32_F4_F7/STM32F4/README.md Parādīt failu


Marlin/src/HAL/HAL_STM32F7/HAL_timers_STM32F7.cpp → Marlin/src/HAL/HAL_STM32_F4_F7/STM32F7/HAL_timers_STM32F7.cpp Parādīt failu

@@ -20,10 +20,9 @@
20 20
  *
21 21
  */
22 22
 
23
-#ifdef STM32F7
24
-
25
-#include "HAL.h"
23
+#if defined(STM32GENERIC) && defined(STM32F7)
26 24
 
25
+#include "../HAL.h"
27 26
 #include "HAL_timers_STM32F7.h"
28 27
 
29 28
 // ------------------------
@@ -33,6 +32,7 @@
33 32
 #define NUM_HARDWARE_TIMERS 2
34 33
 
35 34
 //#define PRESCALER 1
35
+
36 36
 // ------------------------
37 37
 // Private Variables
38 38
 // ------------------------
@@ -43,8 +43,7 @@ tTimerConfig timerConfig[NUM_HARDWARE_TIMERS];
43 43
 // Public functions
44 44
 // ------------------------
45 45
 
46
-
47
-bool timers_initialized[NUM_HARDWARE_TIMERS] = {false};
46
+bool timers_initialized[NUM_HARDWARE_TIMERS] = { false };
48 47
 
49 48
 void HAL_timer_start(const uint8_t timer_num, const uint32_t frequency) {
50 49
 
@@ -128,4 +127,4 @@ bool HAL_timer_interrupt_enabled(const uint8_t timer_num) {
128 127
   return NVIC->ISER[IRQ_Id >> 5] & _BV32(IRQ_Id & 0x1F);
129 128
 }
130 129
 
131
-#endif // STM32F7
130
+#endif // STM32GENERIC && STM32F7

Marlin/src/HAL/HAL_STM32F7/HAL_timers_STM32F7.h → Marlin/src/HAL/HAL_STM32_F4_F7/STM32F7/HAL_timers_STM32F7.h Parādīt failu


Marlin/src/HAL/HAL_STM32F7/README.md → Marlin/src/HAL/HAL_STM32_F4_F7/STM32F7/README.md Parādīt failu

@@ -4,7 +4,7 @@
4 4
 
5 5
 https://github.com/danieleff/STM32GENERIC
6 6
 
7
-but i have not committed the changes needed for the Borg there yet, so please use:
7
+but I haven't committed the changes needed for the Borg there yet, so please use:
8 8
 
9 9
 https://github.com/Spawn32/STM32GENERIC
10 10
 
@@ -15,9 +15,9 @@ Download the latest GNU ARM Embedded Toolchain:
15 15
 
16 16
 https://developer.arm.com/open-source/gnu-toolchain/gnu-rm/downloads
17 17
 
18
-(The one in Arduino dosen't support STM32F7).
18
+(The one in Arduino doesn't support STM32F7).
19 19
 
20
-Change compiler.path in platform.txt to point to that you downloaded.
20
+Change compiler.path in platform.txt to point to the one you downloaded.
21 21
 
22 22
 # This HAL is in development.
23 23
 # Currently only tested on "The Borg".
@@ -25,4 +25,3 @@ Change compiler.path in platform.txt to point to that you downloaded.
25 25
 You will also need the latest Arduino 1.9.0-beta or newer.
26 26
 
27 27
 This HAL is a modified version of Chris Barr's Picoprint STM32F4 HAL, so shouldn't be to hard to get it to work on a F4.
28
-

Marlin/src/HAL/HAL_STM32F7/TMC2660.cpp → Marlin/src/HAL/HAL_STM32_F4_F7/STM32F7/TMC2660.cpp Parādīt failu

@@ -25,22 +25,22 @@
25 25
  *
26 26
  */
27 27
 
28
-//#include <Arduino.h>
28
+#if defined(STM32GENERIC) && defined(STM32F7)
29 29
 
30
-#ifdef STM32F7
30
+#include "../../../inc/MarlinConfigPre.h"
31
+
32
+#if HAS_DRIVER(TMC2660)
31 33
 
32 34
 #include <stdbool.h>
33 35
 #include <SPI.h>
34 36
 #include "TMC2660.h"
35 37
 
36
-#include "HAL.h"
37
-#include "../../core/serial.h"
38
-#include "../../inc/MarlinConfig.h"
39
-#include "../../Marlin.h"
40
-#include "../../module/stepper_indirection.h"
41
-#include "../../module/printcounter.h"
42
-#include "../../libs/duration_t.h"
43
-#include "../../libs/hex_print_routines.h"
38
+#include "../../../inc/MarlinConfig.h"
39
+#include "../../../Marlin.h"
40
+#include "../../../module/stepper_indirection.h"
41
+#include "../../../module/printcounter.h"
42
+#include "../../../libs/duration_t.h"
43
+#include "../../../libs/hex_print_routines.h"
44 44
 
45 45
 //some default values used in initialization
46 46
 #define DEFAULT_MICROSTEPPING_VALUE 32
@@ -630,19 +630,19 @@ uint16_t TMC26XStepper::getCoolStepLowerSgThreshold() {
630 630
 }
631 631
 
632 632
 uint16_t TMC26XStepper::getCoolStepUpperSgThreshold() {
633
-  return (uint8_t)((cool_step_register_value & SE_MAX_PATTERN) >> 8) << 5;
633
+  return uint8_t((cool_step_register_value & SE_MAX_PATTERN) >> 8) << 5;
634 634
 }
635 635
 
636 636
 uint8_t TMC26XStepper::getCoolStepCurrentIncrementSize() {
637
-  return (uint8_t)((cool_step_register_value & CURRENT_DOWN_STEP_SPEED_PATTERN) >> 13);
637
+  return uint8_t((cool_step_register_value & CURRENT_DOWN_STEP_SPEED_PATTERN) >> 13);
638 638
 }
639 639
 
640 640
 uint8_t TMC26XStepper::getCoolStepNumberOfSGReadings() {
641
-  return (uint8_t)((cool_step_register_value & SE_CURRENT_STEP_WIDTH_PATTERN) >> 5);
641
+  return uint8_t((cool_step_register_value & SE_CURRENT_STEP_WIDTH_PATTERN) >> 5);
642 642
 }
643 643
 
644 644
 uint8_t TMC26XStepper::getCoolStepLowerCurrentLimit() {
645
-  return (uint8_t)((cool_step_register_value & MINIMUM_CURRENT_FOURTH) >> 15);
645
+  return uint8_t((cool_step_register_value & MINIMUM_CURRENT_FOURTH) >> 15);
646 646
 }
647 647
 
648 648
 void TMC26XStepper::setEnabled(boolean enabled) {
@@ -895,4 +895,4 @@ inline void TMC26XStepper::send262(uint32_t datagram) {
895 895
   driver_status_result = i_datagram;
896 896
 }
897 897
 
898
-#endif // STM32F7
898
+#endif // STM32GENERIC && STM32F7

Marlin/src/HAL/HAL_STM32F7/TMC2660.h → Marlin/src/HAL/HAL_STM32_F4_F7/STM32F7/TMC2660.h Parādīt failu

@@ -140,7 +140,6 @@ class TMC26XStepper {
140 140
      */
141 141
     void un_start();
142 142
 
143
-
144 143
     /*!
145 144
      * \brief Set the rotation speed in RPM.
146 145
      * \param whatSpeed the desired speed in RPM.

Marlin/src/HAL/HAL_STM32F7/SanityCheck.h → Marlin/src/HAL/HAL_STM32_F4_F7/SanityCheck.h Parādīt failu

@@ -22,14 +22,14 @@
22 22
 #pragma once
23 23
 
24 24
 /**
25
- * Test STM32F7-specific configuration values for errors at compile-time.
25
+ * Test STM32F4/7-specific configuration values for errors at compile-time.
26 26
  */
27 27
 //#if ENABLED(SPINDLE_LASER_PWM) && !(SPINDLE_LASER_PWM_PIN == 4 || SPINDLE_LASER_PWM_PIN == 6 || SPINDLE_LASER_PWM_PIN == 11)
28 28
 //  #error "SPINDLE_LASER_PWM_PIN must use SERVO0, SERVO1 or SERVO3 connector"
29 29
 //#endif
30 30
 
31 31
 #if ENABLED(EMERGENCY_PARSER)
32
-  #error "EMERGENCY_PARSER is not yet implemented for STM32F7. Disable EMERGENCY_PARSER to continue."
32
+  #error "EMERGENCY_PARSER is not yet implemented for STM32F4/7. Disable EMERGENCY_PARSER to continue."
33 33
 #endif
34 34
 
35 35
 #if ENABLED(FAST_PWM_FAN)

Marlin/src/HAL/HAL_STM32F4/EEPROM_Emul/eeprom_emul.cpp → Marlin/src/HAL/HAL_STM32_F4_F7/eeprom_emul.cpp Parādīt failu

@@ -47,7 +47,7 @@
47 47
 /** @addtogroup EEPROM_Emulation
48 48
   * @{
49 49
   */
50
-#if defined(STM32GENERIC) && defined(STM32F4)
50
+#if defined(STM32GENERIC) && (defined(STM32F4) || defined(STM32F7))
51 51
 
52 52
 /* Includes ------------------------------------------------------------------*/
53 53
 #include "eeprom_emul.h"
@@ -516,7 +516,7 @@ static uint16_t EE_PageTransfer(uint16_t VirtAddress, uint16_t Data) {
516 516
   return HAL_FLASH_Program(TYPEPROGRAM_HALFWORD, NewPageAddress, VALID_PAGE);
517 517
 }
518 518
 
519
-#endif // STM32GENERIC && STM32F4
519
+#endif // STM32GENERIC && (STM32F4 || STM32F7)
520 520
 
521 521
 /**
522 522
  * @}

Marlin/src/HAL/HAL_STM32F4/EEPROM_Emul/eeprom_emul.h → Marlin/src/HAL/HAL_STM32_F4_F7/eeprom_emul.h Parādīt failu

@@ -8,7 +8,7 @@
8 8
  ******************************************************************************
9 9
  * @attention
10 10
  *
11
- * <h2><center>&copy; Copyright � 2016 STMicroelectronics International N.V.
11
+ * Copyright © 2016 STMicroelectronics International N.V.
12 12
  * All rights reserved.</center></h2>
13 13
  *
14 14
  * Redistribution and use in source and binary forms, with or without
@@ -48,8 +48,9 @@
48 48
 // ------------------------
49 49
 // Includes
50 50
 // ------------------------
51
-#include "../../../inc/MarlinConfig.h"
52
-#include "../HAL.h"
51
+
52
+#include "../../inc/MarlinConfig.h"
53
+#include "HAL.h"
53 54
 
54 55
 /* Exported constants --------------------------------------------------------*/
55 56
 /* EEPROM emulation firmware error codes */
@@ -66,8 +67,14 @@
66 67
 #define VOLTAGE_RANGE         uint8_t(VOLTAGE_RANGE_3)
67 68
 
68 69
 /* EEPROM start address in Flash */
69
-#define EEPROM_START_ADDRESS  uint32_t(0x08078000) /* EEPROM emulation start address:
70
-                                                      after 480KByte of used Flash memory */
70
+#ifdef STM32F7
71
+  #define EEPROM_START_ADDRESS  uint32_t(0x08100000) /* EEPROM emulation start address:
72
+                                                        from sector2 : after 16KByte of used
73
+                                                        Flash memory */
74
+#else
75
+  #define EEPROM_START_ADDRESS  uint32_t(0x08078000) /* EEPROM emulation start address:
76
+                                                        after 480KByte of used Flash memory */
77
+#endif
71 78
 
72 79
 /* Pages 0 and 1 base and end addresses */
73 80
 #define PAGE0_BASE_ADDRESS    uint32_t(EEPROM_START_ADDRESS + 0x0000)

Marlin/src/HAL/HAL_STM32F4/endstop_interrupts.h → Marlin/src/HAL/HAL_STM32_F4_F7/endstop_interrupts.h Parādīt failu


Marlin/src/HAL/HAL_STM32F7/fastio_STM32F7.h → Marlin/src/HAL/HAL_STM32_F4_F7/fastio_STM32_F4_F7.h Parādīt failu

@@ -23,7 +23,7 @@
23 23
 #pragma once
24 24
 
25 25
 /**
26
- * Fast I/O interfaces for STM32F7
26
+ * Fast I/O interfaces for STM32F4/7
27 27
  * These use GPIO functions instead of Direct Port Manipulation, as on AVR.
28 28
  */
29 29
 
@@ -63,10 +63,8 @@
63 63
 #define PORTC 2
64 64
 #define PORTD 3
65 65
 #define PORTE 4
66
-#define PORTF 5
67
-#define PORTG 6
68 66
 
69
-#define _STM32_PIN(_PORT,_PIN) ((PORT##_PORT * 16) + _PIN)
67
+#define _STM32_PIN(P,PN) ((PORT##P * 16) + PN)
70 68
 
71 69
 #define PA0  _STM32_PIN(A,  0)
72 70
 #define PA1  _STM32_PIN(A,  1)
@@ -153,36 +151,42 @@
153 151
 #define PE14 _STM32_PIN(E, 14)
154 152
 #define PE15 _STM32_PIN(E, 15)
155 153
 
156
-#define PF0  _STM32_PIN(F,  0)
157
-#define PF1  _STM32_PIN(F,  1)
158
-#define PF2  _STM32_PIN(F,  2)
159
-#define PF3  _STM32_PIN(F,  3)
160
-#define PF4  _STM32_PIN(F,  4)
161
-#define PF5  _STM32_PIN(F,  5)
162
-#define PF6  _STM32_PIN(F,  6)
163
-#define PF7  _STM32_PIN(F,  7)
164
-#define PF8  _STM32_PIN(F,  8)
165
-#define PF9  _STM32_PIN(F,  9)
166
-#define PF10 _STM32_PIN(F, 10)
167
-#define PF11 _STM32_PIN(F, 11)
168
-#define PF12 _STM32_PIN(F, 12)
169
-#define PF13 _STM32_PIN(F, 13)
170
-#define PF14 _STM32_PIN(F, 14)
171
-#define PF15 _STM32_PIN(F, 15)
172
-
173
-#define PG0  _STM32_PIN(G,  0)
174
-#define PG1  _STM32_PIN(G,  1)
175
-#define PG2  _STM32_PIN(G,  2)
176
-#define PG3  _STM32_PIN(G,  3)
177
-#define PG4  _STM32_PIN(G,  4)
178
-#define PG5  _STM32_PIN(G,  5)
179
-#define PG6  _STM32_PIN(G,  6)
180
-#define PG7  _STM32_PIN(G,  7)
181
-#define PG8  _STM32_PIN(G,  8)
182
-#define PG9  _STM32_PIN(G,  9)
183
-#define PG10 _STM32_PIN(G, 10)
184
-#define PG11 _STM32_PIN(G, 11)
185
-#define PG12 _STM32_PIN(G, 12)
186
-#define PG13 _STM32_PIN(G, 13)
187
-#define PG14 _STM32_PIN(G, 14)
188
-#define PG15 _STM32_PIN(G, 15)
154
+#ifdef STM32F7
155
+  #define PORTF 5
156
+  #define PORTG 6
157
+
158
+  #define PF0  _STM32_PIN(F,  0)
159
+  #define PF1  _STM32_PIN(F,  1)
160
+  #define PF2  _STM32_PIN(F,  2)
161
+  #define PF3  _STM32_PIN(F,  3)
162
+  #define PF4  _STM32_PIN(F,  4)
163
+  #define PF5  _STM32_PIN(F,  5)
164
+  #define PF6  _STM32_PIN(F,  6)
165
+  #define PF7  _STM32_PIN(F,  7)
166
+  #define PF8  _STM32_PIN(F,  8)
167
+  #define PF9  _STM32_PIN(F,  9)
168
+  #define PF10 _STM32_PIN(F, 10)
169
+  #define PF11 _STM32_PIN(F, 11)
170
+  #define PF12 _STM32_PIN(F, 12)
171
+  #define PF13 _STM32_PIN(F, 13)
172
+  #define PF14 _STM32_PIN(F, 14)
173
+  #define PF15 _STM32_PIN(F, 15)
174
+
175
+  #define PG0  _STM32_PIN(G,  0)
176
+  #define PG1  _STM32_PIN(G,  1)
177
+  #define PG2  _STM32_PIN(G,  2)
178
+  #define PG3  _STM32_PIN(G,  3)
179
+  #define PG4  _STM32_PIN(G,  4)
180
+  #define PG5  _STM32_PIN(G,  5)
181
+  #define PG6  _STM32_PIN(G,  6)
182
+  #define PG7  _STM32_PIN(G,  7)
183
+  #define PG8  _STM32_PIN(G,  8)
184
+  #define PG9  _STM32_PIN(G,  9)
185
+  #define PG10 _STM32_PIN(G, 10)
186
+  #define PG11 _STM32_PIN(G, 11)
187
+  #define PG12 _STM32_PIN(G, 12)
188
+  #define PG13 _STM32_PIN(G, 13)
189
+  #define PG14 _STM32_PIN(G, 14)
190
+  #define PG15 _STM32_PIN(G, 15)
191
+
192
+#endif // STM32GENERIC && STM32F7

Marlin/src/HAL/HAL_STM32F7/persistent_store_eeprom.cpp → Marlin/src/HAL/HAL_STM32_F4_F7/persistent_store_eeprom.cpp Parādīt failu

@@ -21,7 +21,7 @@
21 21
  *
22 22
  */
23 23
 
24
-#ifdef STM32F7
24
+#if defined(STM32GENERIC) && (defined(STM32F4) || defined(STM32F7))
25 25
 
26 26
 #include "../../inc/MarlinConfigPre.h"
27 27
 
@@ -52,10 +52,10 @@ bool PersistentStore::write_data(int &pos, const uint8_t *value, size_t size, ui
52 52
   return false;
53 53
 }
54 54
 
55
-bool PersistentStore::read_data(int &pos, uint8_t* value, size_t size, uint16_t *crc) {
55
+bool PersistentStore::read_data(int &pos, uint8_t* value, size_t size, uint16_t *crc, const bool writing/*=true*/) {
56 56
   do {
57 57
     uint8_t c = eeprom_read_byte((uint8_t*)pos);
58
-    *value = c;
58
+    if (writing) *value = c;
59 59
     crc16(crc, &c, 1);
60 60
     pos++;
61 61
     value++;
@@ -66,4 +66,4 @@ bool PersistentStore::read_data(int &pos, uint8_t* value, size_t size, uint16_t
66 66
 size_t PersistentStore::capacity() { return E2END + 1; }
67 67
 
68 68
 #endif // EEPROM_SETTINGS
69
-#endif // STM32F7
69
+#endif // STM32GENERIC && (STM32F4 || STM32F7)

Marlin/src/HAL/HAL_STM32F7/pinsDebug.h → Marlin/src/HAL/HAL_STM32_F4_F7/pinsDebug.h Parādīt failu

@@ -23,5 +23,5 @@
23 23
 #elif defined(BOARD_NR_GPIO_PINS)   // Only in STM32GENERIC (Maple)
24 24
   #include "../HAL_STM32/pinsDebug_STM32GENERIC.h"
25 25
 #else
26
-  #error "M43 not supported for this board"
26
+  #error "M43 Pins Debugging not supported for this board."
27 27
 #endif

Marlin/src/HAL/HAL_STM32F4/spi_pins.h → Marlin/src/HAL/HAL_STM32_F4_F7/spi_pins.h Parādīt failu


Marlin/src/HAL/HAL_STM32F4/watchdog_STM32F4.cpp → Marlin/src/HAL/HAL_STM32_F4_F7/watchdog_STM32_F4_F7.cpp Parādīt failu

@@ -20,13 +20,13 @@
20 20
  *
21 21
  */
22 22
 
23
-#if defined(STM32GENERIC) && defined(STM32F4)
23
+#if defined(STM32GENERIC) && (defined(STM32F4) || defined(STM32F7))
24 24
 
25 25
 #include "../../inc/MarlinConfig.h"
26 26
 
27 27
 #if ENABLED(USE_WATCHDOG)
28 28
 
29
-  #include "watchdog_STM32F4.h"
29
+  #include "watchdog_STM32_F4_F7.h"
30 30
 
31 31
   IWDG_HandleTypeDef hiwdg;
32 32
 
@@ -37,6 +37,11 @@
37 37
     if (HAL_IWDG_Init(&hiwdg) != HAL_OK) {
38 38
       //Error_Handler();
39 39
     }
40
+    else {
41
+      #if PIN_EXISTS(LED) && !ENABLED(PINS_DEBUGGING)
42
+        TOGGLE(LED_PIN);  // heartbeat indicator
43
+      #endif
44
+    }
40 45
   }
41 46
 
42 47
   void watchdog_reset() {
@@ -45,13 +50,7 @@
45 50
       /* Refresh Error */
46 51
       //Error_Handler();
47 52
     }
48
-    else {
49
-      #if PIN_EXISTS(LED)
50
-        TOGGLE(LED_PIN);  // heartbeat indicator
51
-      #endif
52
-    }
53 53
   }
54 54
 
55 55
 #endif // USE_WATCHDOG
56
-
57
-#endif // STM32GENERIC && STM32F4
56
+#endif // STM32GENERIC && (STM32F4 || STM32F7)

Marlin/src/HAL/HAL_STM32F4/watchdog_STM32F4.h → Marlin/src/HAL/HAL_STM32_F4_F7/watchdog_STM32_F4_F7.h Parādīt failu


+ 2
- 2
Marlin/src/HAL/HAL_TEENSY31_32/HAL_timers_Teensy.h Parādīt failu

@@ -44,8 +44,8 @@ typedef uint32_t hal_timer_t;
44 44
 #define FTM0_TIMER_PRESCALE_BITS 0b011
45 45
 #define FTM1_TIMER_PRESCALE_BITS 0b010
46 46
 
47
-#define FTM0_TIMER_RATE (F_BUS / FTM0_TIMER_PRESCALE) // 60MHz / 8 = 7500kHz
48
-#define FTM1_TIMER_RATE (F_BUS / FTM1_TIMER_PRESCALE) // 60MHz / 4 = 15MHz
47
+#define FTM0_TIMER_RATE (F_BUS / (FTM0_TIMER_PRESCALE)) // 60MHz / 8 = 7500kHz
48
+#define FTM1_TIMER_RATE (F_BUS / (FTM1_TIMER_PRESCALE)) // 60MHz / 4 = 15MHz
49 49
 
50 50
 #define HAL_TIMER_RATE         (FTM0_TIMER_RATE)
51 51
 

+ 2
- 2
Marlin/src/module/stepper_indirection.cpp Parādīt failu

@@ -45,8 +45,8 @@
45 45
 #if HAS_DRIVER(TMC26X)
46 46
   #include <SPI.h>
47 47
 
48
-  #ifdef STM32F7
49
-    #include "../HAL/HAL_STM32F7/TMC2660.h"
48
+  #if defined(STM32GENERIC) && defined(STM32F7)
49
+    #include "../HAL/HAL_STM32_F4_F7/STM32F7/TMC2660.h"
50 50
   #else
51 51
     #include <TMC26XStepper.h>
52 52
   #endif

+ 2
- 2
Marlin/src/module/stepper_indirection.h Parādīt failu

@@ -35,8 +35,8 @@
35 35
 // TMC26X drivers have STEP/DIR on normal pins, but ENABLE via SPI
36 36
 #if HAS_DRIVER(TMC26X)
37 37
   #include <SPI.h>
38
-  #ifdef STM32F7
39
-    #include "../HAL/HAL_STM32F7/TMC2660.h"
38
+  #if defined(STM32GENERIC) && defined(STM32F7)
39
+    #include "../HAL/HAL_STM32_F4_F7/STM32F7/TMC2660.h"
40 40
   #else
41 41
     #include <TMC26XStepper.h>
42 42
   #endif

+ 16
- 3
platformio.ini Parādīt failu

@@ -329,7 +329,7 @@ upload_protocol = stlink
329 329
 debug_tool = stlink
330 330
 
331 331
 #
332
-# STM32F4
332
+# STM32F4 with STM32GENERIC
333 333
 #
334 334
 [env:STM32F4]
335 335
 platform      = ststm32
@@ -338,7 +338,20 @@ board         = disco_f407vg
338 338
 build_flags   = ${common.build_flags} -DUSE_STM32GENERIC -DSTM32GENERIC -DMENU_USB_SERIAL -DMENU_SERIAL=SerialUSB
339 339
 lib_deps      = ${common.lib_deps}
340 340
 lib_ignore    = Adafruit NeoPixel, c1921b4, TMCStepper
341
-src_filter    = ${common.default_src_filter} +<src/HAL/HAL_STM32F4>
341
+src_filter    = ${common.default_src_filter} +<src/HAL/HAL_STM32_F4_F7> -<src/HAL/HAL_STM32_F4_F7/*> +<src/HAL/HAL_STM32_F4_F7/STM32F4>
342
+monitor_speed = 250000
343
+
344
+#
345
+# STM32F7 with STM32GENERIC
346
+#
347
+[env:STM32F7]
348
+platform      = ststm32
349
+framework     = arduino
350
+board         = disco_f765vg
351
+build_flags   = ${common.build_flags} -DUSE_STM32GENERIC -DSTM32GENERIC -DMENU_USB_SERIAL -DMENU_SERIAL=SerialUSB
352
+lib_deps      = ${common.lib_deps}
353
+lib_ignore    = Adafruit NeoPixel, c1921b4, TMCStepper
354
+src_filter    = ${common.default_src_filter} +<src/HAL/HAL_STM32_F4_F7> -<src/HAL/HAL_STM32_F4_F7/*> +<src/HAL/HAL_STM32_F4_F7/STM32F7>
342 355
 monitor_speed = 250000
343 356
 
344 357
 #
@@ -467,7 +480,7 @@ board = BigTree_SKR_Pro
467 480
 extra_scripts = pre:buildroot/share/PlatformIO/scripts/generic_create_variant.py
468 481
 build_flags = ${common.build_flags}
469 482
   -DUSBCON -DUSBD_USE_CDC -DUSBD_VID=0x0483 -DUSB_PRODUCT=\"STM32F407ZG\"
470
-  -DTARGET_STM32F4 -DSTM32F407_5ZX -DVECT_TAB_OFFSET=0x8000  
483
+  -DTARGET_STM32F4 -DSTM32F407_5ZX -DVECT_TAB_OFFSET=0x8000
471 484
 lib_deps = ${common.lib_deps}
472 485
 lib_ignore = Adafruit NeoPixel, c1921b4, TMC26XStepper, SailfishLCD, SailfishRGB_LED, SlowSoftI2CMaster
473 486
 src_filter = ${common.default_src_filter} +<src/HAL/HAL_STM32>

Notiek ielāde…
Atcelt
Saglabāt