Browse Source

Retire HAL for STM32F4 / F7 (#20153)

vanilla_fb_2.0.x
Jason Smith 4 years ago
committed by Scott Lahteine
parent
commit
e2c57f6d47
  1. 21
      .github/workflows/test-builds.yml
  2. 258
      Marlin/src/HAL/STM32/pinsDebug.h
  3. 125
      Marlin/src/HAL/STM32/pinsDebug_STM32GENERIC.h
  4. 273
      Marlin/src/HAL/STM32/pinsDebug_STM32duino.h
  5. 104
      Marlin/src/HAL/STM32F1/pinsDebug.h
  6. 95
      Marlin/src/HAL/STM32_F4_F7/HAL.cpp
  7. 203
      Marlin/src/HAL/STM32_F4_F7/HAL.h
  8. 164
      Marlin/src/HAL/STM32_F4_F7/HAL_SPI.cpp
  9. 6
      Marlin/src/HAL/STM32_F4_F7/README.md
  10. 12
      Marlin/src/HAL/STM32_F4_F7/STM32F4/README.md
  11. 113
      Marlin/src/HAL/STM32_F4_F7/STM32F4/timers.cpp
  12. 134
      Marlin/src/HAL/STM32_F4_F7/STM32F4/timers.h
  13. 27
      Marlin/src/HAL/STM32_F4_F7/STM32F7/README.md
  14. 898
      Marlin/src/HAL/STM32_F4_F7/STM32F7/TMC2660.cpp
  15. 593
      Marlin/src/HAL/STM32_F4_F7/STM32F7/TMC2660.h
  16. 127
      Marlin/src/HAL/STM32_F4_F7/STM32F7/timers.cpp
  17. 107
      Marlin/src/HAL/STM32_F4_F7/STM32F7/timers.h
  18. 51
      Marlin/src/HAL/STM32_F4_F7/Servo.cpp
  19. 41
      Marlin/src/HAL/STM32_F4_F7/Servo.h
  20. 535
      Marlin/src/HAL/STM32_F4_F7/eeprom_emul.cpp
  21. 114
      Marlin/src/HAL/STM32_F4_F7/eeprom_emul.h
  22. 111
      Marlin/src/HAL/STM32_F4_F7/eeprom_flash.cpp
  23. 77
      Marlin/src/HAL/STM32_F4_F7/eeprom_wired.cpp
  24. 49
      Marlin/src/HAL/STM32_F4_F7/endstop_interrupts.h
  25. 310
      Marlin/src/HAL/STM32_F4_F7/fastio.h
  26. 26
      Marlin/src/HAL/STM32_F4_F7/inc/Conditionals_LCD.h
  27. 22
      Marlin/src/HAL/STM32_F4_F7/inc/Conditionals_adv.h
  28. 29
      Marlin/src/HAL/STM32_F4_F7/inc/Conditionals_post.h
  29. 41
      Marlin/src/HAL/STM32_F4_F7/inc/SanityCheck.h
  30. 27
      Marlin/src/HAL/STM32_F4_F7/pinsDebug.h
  31. 35
      Marlin/src/HAL/STM32_F4_F7/spi_pins.h
  32. 28
      Marlin/src/HAL/STM32_F4_F7/timers.h
  33. 57
      Marlin/src/HAL/STM32_F4_F7/watchdog.cpp
  34. 27
      Marlin/src/HAL/STM32_F4_F7/watchdog.h
  35. 2
      Marlin/src/HAL/platforms.h
  36. 11
      Marlin/src/HAL/shared/backtrace/unwmemaccess.cpp
  37. 2
      Marlin/src/HAL/shared/servo.h
  38. 50
      Marlin/src/core/boards.h
  39. 4
      Marlin/src/core/macros.h
  40. 6
      Marlin/src/module/stepper/TMC26X.h
  41. 18
      Marlin/src/pins/pins.h
  42. 4
      Marlin/src/pins/stm32f1/pins_BEAST.h
  43. 197
      Marlin/src/pins/stm32f4/pins_GENERIC_STM32F4.h
  44. 183
      Marlin/src/pins/stm32f7/pins_THE_BORG.h
  45. 2
      buildroot/tests/BIGTREE_SKR_PRO-tests
  46. 2
      buildroot/tests/REMRAM_V1-tests
  47. 1
      buildroot/tests/STM32F103RC_btt-tests
  48. 16
      buildroot/tests/STM32F4-tests
  49. 17
      platformio.ini

21
.github/workflows/test-builds.yml

@ -54,7 +54,7 @@ jobs:
- sanguino1284p - sanguino1284p
- sanguino644p - sanguino644p
# Extended STM32 Environments # STM32F1 (Maple) Environments
- STM32F103RC_btt - STM32F103RC_btt
- STM32F103RC_btt_USB - STM32F103RC_btt_USB
@ -64,38 +64,37 @@ jobs:
- STM32F103RC_meeb - STM32F103RC_meeb
- jgaurora_a5s_a1 - jgaurora_a5s_a1
- STM32F103VE_longer - STM32F103VE_longer
- mks_robin
- mks_robin_lite
- mks_robin_pro
- STM32F103RET6_creality
- mks_robin_nano35
# STM32 (ST) Environments
- STM32F407VE_black - STM32F407VE_black
- STM32F401VE_STEVAL - STM32F401VE_STEVAL
- BIGTREE_BTT002 - BIGTREE_BTT002
- BIGTREE_SKR_PRO - BIGTREE_SKR_PRO
- BIGTREE_GTR_V1_0 - BIGTREE_GTR_V1_0
- mks_robin
- mks_robin_stm32 - mks_robin_stm32
- ARMED - ARMED
- FYSETC_S6 - FYSETC_S6
- STM32F070CB_malyan - STM32F070CB_malyan
- STM32F070RB_malyan - STM32F070RB_malyan
- malyan_M300 - malyan_M300
- mks_robin_lite
- FLYF407ZG - FLYF407ZG
- rumba32 - rumba32
- mks_robin_pro
- STM32F103RET6_creality
- LERDGEX - LERDGEX
- mks_robin_nano35
- mks_robin_nano35_stm32 - mks_robin_nano35_stm32
- NUCLEO_F767ZI - NUCLEO_F767ZI
- REMRAM_V1
# Put lengthy tests last # Put lengthy tests last
- LPC1768 - LPC1768
- LPC1769 - LPC1769
# STM32 with non-STM framework. both broken for now. they should use HAL_STM32 which is working.
#- STM32F4
#- STM32F7
# Non-working environment tests # Non-working environment tests
#- at90usb1286_cdc #- at90usb1286_cdc
#- STM32F103CB_malyan #- STM32F103CB_malyan

258
Marlin/src/HAL/STM32/pinsDebug.h

@ -18,17 +18,257 @@
*/ */
#pragma once #pragma once
#if !(defined(NUM_DIGITAL_PINS) || defined(BOARD_NR_GPIO_PINS)) #include <Arduino.h>
#error "M43 not supported for this board"
#ifndef NUM_DIGITAL_PINS
// Only in ST's Arduino core (STM32duino, STM32Core)
#error "Expected NUM_DIGITAL_PINS not found"
#endif #endif
// Strange - STM32F4 comes to HAL_STM32 rather than HAL_STM32F4 for these files /**
#ifdef STM32F4 * Life gets complicated if you want an easy to use 'M43 I' output (in port/pin order)
#ifdef NUM_DIGITAL_PINS // Only in ST's Arduino core (STM32duino, STM32Core) * because the variants in this platform do not always define all the I/O port/pins
#include "pinsDebug_STM32duino.h" * that a CPU has.
#elif defined(BOARD_NR_GPIO_PINS) // Only in STM32GENERIC (Maple) *
#include "pinsDebug_STM32GENERIC.h" * VARIABLES:
* Ard_num - Arduino pin number - defined by the platform. It is used by digitalRead and
* digitalWrite commands and by M42.
* - does not contain port/pin info
* - is not in port/pin order
* - typically a variant will only assign Ard_num to port/pins that are actually used
* Index - M43 counter - only used to get Ard_num
* x - a parameter/argument used to search the pin_array to try to find a signal name
* associated with a Ard_num
* Port_pin - port number and pin number for use with CPU registers and printing reports
*
* Since M43 uses digitalRead and digitalWrite commands, only the Port_pins with an Ard_num
* are accessed and/or displayed.
*
* Three arrays are used.
*
* digitalPin[] is provided by the platform. It consists of the Port_pin numbers in
* Arduino pin number order.
*
* pin_array is a structure generated by the pins/pinsDebug.h header file. It is generated by
* the preprocessor. Only the signals associated with enabled options are in this table.
* It contains:
* - name of the signal
* - the Ard_num assigned by the pins_YOUR_BOARD.h file using the platform defines.
* EXAMPLE: "#define KILL_PIN PB1" results in Ard_num of 57. 57 is then used as the
* argument to digitalPinToPinName(IO) to get the Port_pin number
* - if it is a digital or analog signal. PWMs are considered digital here.
*
* pin_xref is a structure generated by this header file. It is generated by the
* preprocessor. It is in port/pin order. It contains just the port/pin numbers defined by the
* platform for this variant.
* - Ard_num
* - printable version of Port_pin
*
* Routines with an "x" as a parameter/argument are used to search the pin_array to try to
* find a signal name associated with a port/pin.
*
* NOTE - the Arduino pin number is what is used by the M42 command, NOT the port/pin for that
* signal. The Arduino pin number is listed by the M43 I command.
*/
////////////////////////////////////////////////////////
//
// make a list of the Arduino pin numbers in the Port/Pin order
//
#define _PIN_ADD_2(NAME_ALPHA, ARDUINO_NUM) { {NAME_ALPHA}, ARDUINO_NUM },
#define _PIN_ADD(NAME_ALPHA, ARDUINO_NUM) { NAME_ALPHA, ARDUINO_NUM },
#define PIN_ADD(NAME) _PIN_ADD(#NAME, NAME)
typedef struct {
char Port_pin_alpha[5];
pin_t Ard_num;
} XrefInfo;
const XrefInfo pin_xref[] PROGMEM = {
#include "pins_Xref.h"
};
////////////////////////////////////////////////////////////
#define MODE_PIN_INPUT 0 // Input mode (reset state)
#define MODE_PIN_OUTPUT 1 // General purpose output mode
#define MODE_PIN_ALT 2 // Alternate function mode
#define MODE_PIN_ANALOG 3 // Analog mode
#define PIN_NUM(P) (P & 0x000F)
#define PIN_NUM_ALPHA_LEFT(P) (((P & 0x000F) < 10) ? ('0' + (P & 0x000F)) : '1')
#define PIN_NUM_ALPHA_RIGHT(P) (((P & 0x000F) > 9) ? ('0' + (P & 0x000F) - 10) : 0 )
#define PORT_NUM(P) ((P >> 4) & 0x0007)
#define PORT_ALPHA(P) ('A' + (P >> 4))
/**
* Translation of routines & variables used by pinsDebug.h
*/
#define NUMBER_PINS_TOTAL NUM_DIGITAL_PINS
#define VALID_PIN(ANUM) ((ANUM) >= 0 && (ANUM) < NUMBER_PINS_TOTAL)
#define digitalRead_mod(Ard_num) extDigitalRead(Ard_num) // must use Arduino pin numbers when doing reads
#define PRINT_PIN(Q)
#define PRINT_PORT(ANUM) port_print(ANUM)
#define DIGITAL_PIN_TO_ANALOG_PIN(ANUM) -1 // will report analog pin number in the print port routine
#define GET_PIN_MAP_PIN_M43(Index) pin_xref[Index].Ard_num
// x is a variable used to search pin_array
#define GET_ARRAY_IS_DIGITAL(x) ((bool) pin_array[x].is_digital)
#define GET_ARRAY_PIN(x) ((pin_t) pin_array[x].pin)
#define PRINT_ARRAY_NAME(x) do{ sprintf_P(buffer, PSTR("%-" STRINGIFY(MAX_NAME_LENGTH) "s"), pin_array[x].name); SERIAL_ECHO(buffer); }while(0)
#define MULTI_NAME_PAD 33 // space needed to be pretty if not first name assigned to a pin
#ifndef M43_NEVER_TOUCH
#define _M43_NEVER_TOUCH(Index) (Index >= 9 && Index <= 12) // SERIAL/USB pins: PA9(TX) PA10(RX) PA11(USB_DM) PA12(USB_DP)
#ifdef KILL_PIN
#define M43_NEVER_TOUCH(Index) m43_never_touch(Index)
bool m43_never_touch(const pin_t Index) {
static pin_t M43_kill_index = -1;
if (M43_kill_index < 0)
for (M43_kill_index = 0; M43_kill_index < NUMBER_PINS_TOTAL; M43_kill_index++)
if (KILL_PIN == GET_PIN_MAP_PIN_M43(M43_kill_index)) break;
return _M43_NEVER_TOUCH(Index) || Index == M43_kill_index; // KILL_PIN and SERIAL/USB
}
#else #else
#error "M43 not supported for this board" #define M43_NEVER_TOUCH(Index) _M43_NEVER_TOUCH(Index)
#endif #endif
#endif #endif
uint8_t get_pin_mode(const pin_t Ard_num) {
uint32_t mode_all = 0;
const PinName dp = digitalPinToPinName(Ard_num);
switch (PORT_ALPHA(dp)) {
case 'A' : mode_all = GPIOA->MODER; break;
case 'B' : mode_all = GPIOB->MODER; break;
case 'C' : mode_all = GPIOC->MODER; break;
case 'D' : mode_all = GPIOD->MODER; break;
#ifdef PE_0
case 'E' : mode_all = GPIOE->MODER; break;
#elif defined(PF_0)
case 'F' : mode_all = GPIOF->MODER; break;
#elif defined(PG_0)
case 'G' : mode_all = GPIOG->MODER; break;
#elif defined(PH_0)
case 'H' : mode_all = GPIOH->MODER; break;
#elif defined(PI_0)
case 'I' : mode_all = GPIOI->MODER; break;
#elif defined(PJ_0)
case 'J' : mode_all = GPIOJ->MODER; break;
#elif defined(PK_0)
case 'K' : mode_all = GPIOK->MODER; break;
#elif defined(PL_0)
case 'L' : mode_all = GPIOL->MODER; break;
#endif
}
return (mode_all >> (2 * uint8_t(PIN_NUM(dp)))) & 0x03;
}
bool GET_PINMODE(const pin_t Ard_num) {
const uint8_t pin_mode = get_pin_mode(Ard_num);
return pin_mode == MODE_PIN_OUTPUT || pin_mode == MODE_PIN_ALT; // assume all alt definitions are PWM
}
int8_t digital_pin_to_analog_pin(pin_t Ard_num) {
Ard_num -= NUM_ANALOG_FIRST;
return (Ard_num >= 0 && Ard_num < NUM_ANALOG_INPUTS) ? Ard_num : -1;
}
bool IS_ANALOG(const pin_t Ard_num) {
return get_pin_mode(Ard_num) == MODE_PIN_ANALOG;
}
bool is_digital(const pin_t x) {
const uint8_t pin_mode = get_pin_mode(pin_array[x].pin);
return pin_mode == MODE_PIN_INPUT || pin_mode == MODE_PIN_OUTPUT;
}
void port_print(const pin_t Ard_num) {
char buffer[16];
pin_t Index;
for (Index = 0; Index < NUMBER_PINS_TOTAL; Index++)
if (Ard_num == GET_PIN_MAP_PIN_M43(Index)) break;
const char * ppa = pin_xref[Index].Port_pin_alpha;
sprintf_P(buffer, PSTR("%s"), ppa);
SERIAL_ECHO(buffer);
if (ppa[3] == '\0') SERIAL_CHAR(' ');
// print analog pin number
const int8_t Port_pin = digital_pin_to_analog_pin(Ard_num);
if (Port_pin >= 0) {
sprintf_P(buffer, PSTR(" (A%d) "), Port_pin);
SERIAL_ECHO(buffer);
if (Port_pin < 10) SERIAL_CHAR(' ');
}
else
SERIAL_ECHO_SP(7);
// Print number to be used with M42
sprintf_P(buffer, PSTR(" M42 P%d "), Ard_num);
SERIAL_ECHO(buffer);
if (Ard_num < 10) SERIAL_CHAR(' ');
if (Ard_num < 100) SERIAL_CHAR(' ');
}
bool pwm_status(const pin_t Ard_num) {
return get_pin_mode(Ard_num) == MODE_PIN_ALT;
}
void pwm_details(const pin_t Ard_num) {
if (pwm_status(Ard_num)) {
uint32_t alt_all = 0;
const PinName dp = digitalPinToPinName(Ard_num);
pin_t pin_number = uint8_t(PIN_NUM(dp));
const bool over_7 = pin_number >= 8;
const uint8_t ind = over_7 ? 1 : 0;
switch (PORT_ALPHA(dp)) { // get alt function
case 'A' : alt_all = GPIOA->AFR[ind]; break;
case 'B' : alt_all = GPIOB->AFR[ind]; break;
case 'C' : alt_all = GPIOC->AFR[ind]; break;
case 'D' : alt_all = GPIOD->AFR[ind]; break;
#ifdef PE_0
case 'E' : alt_all = GPIOE->AFR[ind]; break;
#elif defined (PF_0)
case 'F' : alt_all = GPIOF->AFR[ind]; break;
#elif defined (PG_0)
case 'G' : alt_all = GPIOG->AFR[ind]; break;
#elif defined (PH_0)
case 'H' : alt_all = GPIOH->AFR[ind]; break;
#elif defined (PI_0)
case 'I' : alt_all = GPIOI->AFR[ind]; break;
#elif defined (PJ_0)
case 'J' : alt_all = GPIOJ->AFR[ind]; break;
#elif defined (PK_0)
case 'K' : alt_all = GPIOK->AFR[ind]; break;
#elif defined (PL_0)
case 'L' : alt_all = GPIOL->AFR[ind]; break;
#endif
}
if (over_7) pin_number -= 8;
uint8_t alt_func = (alt_all >> (4 * pin_number)) & 0x0F;
SERIAL_ECHOPAIR("Alt Function: ", alt_func);
if (alt_func < 10) SERIAL_CHAR(' ');
SERIAL_ECHOPGM(" - ");
switch (alt_func) {
case 0 : SERIAL_ECHOPGM("system (misc. I/O)"); break;
case 1 : SERIAL_ECHOPGM("TIM1/TIM2 (probably PWM)"); break;
case 2 : SERIAL_ECHOPGM("TIM3..5 (probably PWM)"); break;
case 3 : SERIAL_ECHOPGM("TIM8..11 (probably PWM)"); break;
case 4 : SERIAL_ECHOPGM("I2C1..3"); break;
case 5 : SERIAL_ECHOPGM("SPI1/SPI2"); break;
case 6 : SERIAL_ECHOPGM("SPI3"); break;
case 7 : SERIAL_ECHOPGM("USART1..3"); break;
case 8 : SERIAL_ECHOPGM("USART4..6"); break;
case 9 : SERIAL_ECHOPGM("CAN1/CAN2, TIM12..14 (probably PWM)"); break;
case 10 : SERIAL_ECHOPGM("OTG"); break;
case 11 : SERIAL_ECHOPGM("ETH"); break;
case 12 : SERIAL_ECHOPGM("FSMC, SDIO, OTG"); break;
case 13 : SERIAL_ECHOPGM("DCMI"); break;
case 14 : SERIAL_ECHOPGM("unused (shouldn't see this)"); break;
case 15 : SERIAL_ECHOPGM("EVENTOUT"); break;
}
}
} // pwm_details

125
Marlin/src/HAL/STM32/pinsDebug_STM32GENERIC.h

@ -1,125 +0,0 @@
/**
* Marlin 3D Printer Firmware
* Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
*
* This program is free software: you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation, either version 3 of the License, or
* (at your option) any later version.
*
* This program is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with this program. If not, see <https://www.gnu.org/licenses/>.
*
*/
#pragma once
/**
* Support routines for STM32GENERIC (Maple)
*/
/**
* Translation of routines & variables used by pinsDebug.h
*/
#ifdef BOARD_NR_GPIO_PINS // Only in STM32GENERIC (Maple)
#ifdef __STM32F1__
#include "../STM32F1/fastio.h"
#elif defined(STM32F4) || defined(STM32F7)
#include "../STM32_F4_F7/fastio.h"
#else
#include "fastio.h"
#endif
extern const stm32_pin_info PIN_MAP[BOARD_NR_GPIO_PINS];
#define NUM_DIGITAL_PINS BOARD_NR_GPIO_PINS
#define NUMBER_PINS_TOTAL BOARD_NR_GPIO_PINS
#define VALID_PIN(pin) (pin >= 0 && pin < BOARD_NR_GPIO_PINS)
#define GET_ARRAY_PIN(p) pin_t(pin_array[p].pin)
#define pwm_status(pin) PWM_PIN(pin)
#define digitalRead_mod(p) extDigitalRead(p)
#define PRINT_PIN(p) do{ sprintf_P(buffer, PSTR("%3hd "), int16_t(p)); SERIAL_ECHO(buffer); }while(0)
#define PRINT_PORT(p) print_port(p)
#define PRINT_ARRAY_NAME(x) do{ sprintf_P(buffer, PSTR("%-" STRINGIFY(MAX_NAME_LENGTH) "s"), pin_array[x].name); SERIAL_ECHO(buffer); }while(0)
#define MULTI_NAME_PAD 21 // space needed to be pretty if not first name assigned to a pin
// pins that will cause hang/reset/disconnect in M43 Toggle and Watch utilities
#ifndef M43_NEVER_TOUCH
#define M43_NEVER_TOUCH(Q) (Q >= 9 && Q <= 12) // SERIAL/USB pins PA9(TX) PA10(RX)
#endif
static inline int8_t get_pin_mode(pin_t pin) {
return VALID_PIN(pin) ? _GET_MODE(pin) : -1;
}
static inline pin_t DIGITAL_PIN_TO_ANALOG_PIN(pin_t pin) {
if (!VALID_PIN(pin)) return -1;
int8_t adc_channel = int8_t(PIN_MAP[pin].adc_channel);
#ifdef NUM_ANALOG_INPUTS
if (adc_channel >= NUM_ANALOG_INPUTS) adc_channel = ADCx;
#endif
return pin_t(adc_channel);
}
static inline bool IS_ANALOG(pin_t pin) {
if (!VALID_PIN(pin)) return false;
if (PIN_MAP[pin].adc_channel != ADCx) {
#ifdef NUM_ANALOG_INPUTS
if (PIN_MAP[pin].adc_channel >= NUM_ANALOG_INPUTS) return false;
#endif
return _GET_MODE(pin) == GPIO_INPUT_ANALOG && !M43_NEVER_TOUCH(pin);
}
return false;
}
static inline bool GET_PINMODE(const pin_t pin) {
return VALID_PIN(pin) && !IS_INPUT(pin);
}
static inline bool GET_ARRAY_IS_DIGITAL(const int16_t array_pin) {
const pin_t pin = GET_ARRAY_PIN(array_pin);
return (!IS_ANALOG(pin)
#ifdef NUM_ANALOG_INPUTS
|| PIN_MAP[pin].adc_channel >= NUM_ANALOG_INPUTS
#endif
);
}
#include "../../inc/MarlinConfig.h" // Allow pins/pins.h to set density
static inline void pwm_details(const pin_t pin) {
if (PWM_PIN(pin)) {
timer_dev * const tdev = PIN_MAP[pin].timer_device;
const uint8_t channel = PIN_MAP[pin].timer_channel;
const char num = (
#if EITHER(STM32_HIGH_DENSITY, STM32_XL_DENSITY)
tdev == &timer8 ? '8' :
tdev == &timer5 ? '5' :
#endif
tdev == &timer4 ? '4' :
tdev == &timer3 ? '3' :
tdev == &timer2 ? '2' :
tdev == &timer1 ? '1' : '?'
);
char buffer[10];
sprintf_P(buffer, PSTR(" TIM%c CH%c"), num, ('0' + channel));
SERIAL_ECHO(buffer);
}
}
static inline void print_port(pin_t pin) {
const char port = 'A' + char(pin >> 4); // pin div 16
const int16_t gbit = PIN_MAP[pin].gpio_bit;
char buffer[8];
sprintf_P(buffer, PSTR("P%c%hd "), port, gbit);
if (gbit < 10) SERIAL_CHAR(' ');
SERIAL_ECHO(buffer);
}
#endif // BOARD_NR_GPIO_PINS

273
Marlin/src/HAL/STM32/pinsDebug_STM32duino.h

@ -1,273 +0,0 @@
/**
* Marlin 3D Printer Firmware
* Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
*
* This program is free software: you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation, either version 3 of the License, or
* (at your option) any later version.
*
* This program is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with this program. If not, see <https://www.gnu.org/licenses/>.
*
*/
#pragma once
#include <Arduino.h>
#ifdef NUM_DIGITAL_PINS // Only in ST's Arduino core (STM32duino, STM32Core)
/**
* Life gets complicated if you want an easy to use 'M43 I' output (in port/pin order)
* because the variants in this platform do not always define all the I/O port/pins
* that a CPU has.
*
* VARIABLES:
* Ard_num - Arduino pin number - defined by the platform. It is used by digitalRead and
* digitalWrite commands and by M42.
* - does not contain port/pin info
* - is not in port/pin order
* - typically a variant will only assign Ard_num to port/pins that are actually used
* Index - M43 counter - only used to get Ard_num
* x - a parameter/argument used to search the pin_array to try to find a signal name
* associated with a Ard_num
* Port_pin - port number and pin number for use with CPU registers and printing reports
*
* Since M43 uses digitalRead and digitalWrite commands, only the Port_pins with an Ard_num
* are accessed and/or displayed.
*
* Three arrays are used.
*
* digitalPin[] is provided by the platform. It consists of the Port_pin numbers in
* Arduino pin number order.
*
* pin_array is a structure generated by the pins/pinsDebug.h header file. It is generated by
* the preprocessor. Only the signals associated with enabled options are in this table.
* It contains:
* - name of the signal
* - the Ard_num assigned by the pins_YOUR_BOARD.h file using the platform defines.
* EXAMPLE: "#define KILL_PIN PB1" results in Ard_num of 57. 57 is then used as the
* argument to digitalPinToPinName(IO) to get the Port_pin number
* - if it is a digital or analog signal. PWMs are considered digital here.
*
* pin_xref is a structure generated by this header file. It is generated by the
* preprocessor. It is in port/pin order. It contains just the port/pin numbers defined by the
* platform for this variant.
* - Ard_num
* - printable version of Port_pin
*
* Routines with an "x" as a parameter/argument are used to search the pin_array to try to
* find a signal name associated with a port/pin.
*
* NOTE - the Arduino pin number is what is used by the M42 command, NOT the port/pin for that
* signal. The Arduino pin number is listed by the M43 I command.
*/
////////////////////////////////////////////////////////
//
// make a list of the Arduino pin numbers in the Port/Pin order
//
#define _PIN_ADD_2(NAME_ALPHA, ARDUINO_NUM) { {NAME_ALPHA}, ARDUINO_NUM },
#define _PIN_ADD(NAME_ALPHA, ARDUINO_NUM) { NAME_ALPHA, ARDUINO_NUM },
#define PIN_ADD(NAME) _PIN_ADD(#NAME, NAME)
typedef struct {
char Port_pin_alpha[5];
pin_t Ard_num;
} XrefInfo;
const XrefInfo pin_xref[] PROGMEM = {
#include "pins_Xref.h"
};
////////////////////////////////////////////////////////////
#define MODE_PIN_INPUT 0 // Input mode (reset state)
#define MODE_PIN_OUTPUT 1 // General purpose output mode
#define MODE_PIN_ALT 2 // Alternate function mode
#define MODE_PIN_ANALOG 3 // Analog mode
#define PIN_NUM(P) (P & 0x000F)
#define PIN_NUM_ALPHA_LEFT(P) (((P & 0x000F) < 10) ? ('0' + (P & 0x000F)) : '1')
#define PIN_NUM_ALPHA_RIGHT(P) (((P & 0x000F) > 9) ? ('0' + (P & 0x000F) - 10) : 0 )
#define PORT_NUM(P) ((P >> 4) & 0x0007)
#define PORT_ALPHA(P) ('A' + (P >> 4))
/**
* Translation of routines & variables used by pinsDebug.h
*/
#define NUMBER_PINS_TOTAL NUM_DIGITAL_PINS
#define VALID_PIN(ANUM) ((ANUM) >= 0 && (ANUM) < NUMBER_PINS_TOTAL)
#define digitalRead_mod(Ard_num) extDigitalRead(Ard_num) // must use Arduino pin numbers when doing reads
#define PRINT_PIN(Q)
#define PRINT_PORT(ANUM) port_print(ANUM)
#define DIGITAL_PIN_TO_ANALOG_PIN(ANUM) -1 // will report analog pin number in the print port routine
#define GET_PIN_MAP_PIN_M43(Index) pin_xref[Index].Ard_num
// x is a variable used to search pin_array
#define GET_ARRAY_IS_DIGITAL(x) ((bool) pin_array[x].is_digital)
#define GET_ARRAY_PIN(x) ((pin_t) pin_array[x].pin)
#define PRINT_ARRAY_NAME(x) do{ sprintf_P(buffer, PSTR("%-" STRINGIFY(MAX_NAME_LENGTH) "s"), pin_array[x].name); SERIAL_ECHO(buffer); }while(0)
#define MULTI_NAME_PAD 33 // space needed to be pretty if not first name assigned to a pin
#ifndef M43_NEVER_TOUCH
#define _M43_NEVER_TOUCH(Index) (Index >= 9 && Index <= 12) // SERIAL/USB pins: PA9(TX) PA10(RX) PA11(USB_DM) PA12(USB_DP)
#ifdef KILL_PIN
#define M43_NEVER_TOUCH(Index) m43_never_touch(Index)
bool m43_never_touch(const pin_t Index) {
static pin_t M43_kill_index = -1;
if (M43_kill_index < 0)
for (M43_kill_index = 0; M43_kill_index < NUMBER_PINS_TOTAL; M43_kill_index++)
if (KILL_PIN == GET_PIN_MAP_PIN_M43(M43_kill_index)) break;
return _M43_NEVER_TOUCH(Index) || Index == M43_kill_index; // KILL_PIN and SERIAL/USB
}
#else
#define M43_NEVER_TOUCH(Index) _M43_NEVER_TOUCH(Index)
#endif
#endif
uint8_t get_pin_mode(const pin_t Ard_num) {
uint32_t mode_all = 0;
const PinName dp = digitalPinToPinName(Ard_num);
switch (PORT_ALPHA(dp)) {
case 'A' : mode_all = GPIOA->MODER; break;
case 'B' : mode_all = GPIOB->MODER; break;
case 'C' : mode_all = GPIOC->MODER; break;
case 'D' : mode_all = GPIOD->MODER; break;
#ifdef PE_0
case 'E' : mode_all = GPIOE->MODER; break;
#elif defined(PF_0)
case 'F' : mode_all = GPIOF->MODER; break;
#elif defined(PG_0)
case 'G' : mode_all = GPIOG->MODER; break;
#elif defined(PH_0)
case 'H' : mode_all = GPIOH->MODER; break;
#elif defined(PI_0)
case 'I' : mode_all = GPIOI->MODER; break;
#elif defined(PJ_0)
case 'J' : mode_all = GPIOJ->MODER; break;
#elif defined(PK_0)
case 'K' : mode_all = GPIOK->MODER; break;
#elif defined(PL_0)
case 'L' : mode_all = GPIOL->MODER; break;
#endif
}
return (mode_all >> (2 * uint8_t(PIN_NUM(dp)))) & 0x03;
}
bool GET_PINMODE(const pin_t Ard_num) {
const uint8_t pin_mode = get_pin_mode(Ard_num);
return pin_mode == MODE_PIN_OUTPUT || pin_mode == MODE_PIN_ALT; // assume all alt definitions are PWM
}
int8_t digital_pin_to_analog_pin(pin_t Ard_num) {
Ard_num -= NUM_ANALOG_FIRST;
return (Ard_num >= 0 && Ard_num < NUM_ANALOG_INPUTS) ? Ard_num : -1;
}
bool IS_ANALOG(const pin_t Ard_num) {
return get_pin_mode(Ard_num) == MODE_PIN_ANALOG;
}
bool is_digital(const pin_t x) {
const uint8_t pin_mode = get_pin_mode(pin_array[x].pin);
return pin_mode == MODE_PIN_INPUT || pin_mode == MODE_PIN_OUTPUT;
}
void port_print(const pin_t Ard_num) {
char buffer[16];
pin_t Index;
for (Index = 0; Index < NUMBER_PINS_TOTAL; Index++)
if (Ard_num == GET_PIN_MAP_PIN_M43(Index)) break;
const char * ppa = pin_xref[Index].Port_pin_alpha;
sprintf_P(buffer, PSTR("%s"), ppa);
SERIAL_ECHO(buffer);
if (ppa[3] == '\0') SERIAL_CHAR(' ');
// print analog pin number
const int8_t Port_pin = digital_pin_to_analog_pin(Ard_num);
if (Port_pin >= 0) {
sprintf_P(buffer, PSTR(" (A%d) "), Port_pin);
SERIAL_ECHO(buffer);
if (Port_pin < 10) SERIAL_CHAR(' ');
}
else
SERIAL_ECHO_SP(7);
// Print number to be used with M42
sprintf_P(buffer, PSTR(" M42 P%d "), Ard_num);
SERIAL_ECHO(buffer);
if (Ard_num < 10) SERIAL_CHAR(' ');
if (Ard_num < 100) SERIAL_CHAR(' ');
}
bool pwm_status(const pin_t Ard_num) {
return get_pin_mode(Ard_num) == MODE_PIN_ALT;
}
void pwm_details(const pin_t Ard_num) {
if (pwm_status(Ard_num)) {
uint32_t alt_all = 0;
const PinName dp = digitalPinToPinName(Ard_num);
pin_t pin_number = uint8_t(PIN_NUM(dp));
const bool over_7 = pin_number >= 8;
const uint8_t ind = over_7 ? 1 : 0;
switch (PORT_ALPHA(dp)) { // get alt function
case 'A' : alt_all = GPIOA->AFR[ind]; break;
case 'B' : alt_all = GPIOB->AFR[ind]; break;
case 'C' : alt_all = GPIOC->AFR[ind]; break;
case 'D' : alt_all = GPIOD->AFR[ind]; break;
#ifdef PE_0
case 'E' : alt_all = GPIOE->AFR[ind]; break;
#elif defined (PF_0)
case 'F' : alt_all = GPIOF->AFR[ind]; break;
#elif defined (PG_0)
case 'G' : alt_all = GPIOG->AFR[ind]; break;
#elif defined (PH_0)
case 'H' : alt_all = GPIOH->AFR[ind]; break;
#elif defined (PI_0)
case 'I' : alt_all = GPIOI->AFR[ind]; break;
#elif defined (PJ_0)
case 'J' : alt_all = GPIOJ->AFR[ind]; break;
#elif defined (PK_0)
case 'K' : alt_all = GPIOK->AFR[ind]; break;
#elif defined (PL_0)
case 'L' : alt_all = GPIOL->AFR[ind]; break;
#endif
}
if (over_7) pin_number -= 8;
uint8_t alt_func = (alt_all >> (4 * pin_number)) & 0x0F;
SERIAL_ECHOPAIR("Alt Function: ", alt_func);
if (alt_func < 10) SERIAL_CHAR(' ');
SERIAL_ECHOPGM(" - ");
switch (alt_func) {
case 0 : SERIAL_ECHOPGM("system (misc. I/O)"); break;
case 1 : SERIAL_ECHOPGM("TIM1/TIM2 (probably PWM)"); break;
case 2 : SERIAL_ECHOPGM("TIM3..5 (probably PWM)"); break;
case 3 : SERIAL_ECHOPGM("TIM8..11 (probably PWM)"); break;
case 4 : SERIAL_ECHOPGM("I2C1..3"); break;
case 5 : SERIAL_ECHOPGM("SPI1/SPI2"); break;
case 6 : SERIAL_ECHOPGM("SPI3"); break;
case 7 : SERIAL_ECHOPGM("USART1..3"); break;
case 8 : SERIAL_ECHOPGM("USART4..6"); break;
case 9 : SERIAL_ECHOPGM("CAN1/CAN2, TIM12..14 (probably PWM)"); break;
case 10 : SERIAL_ECHOPGM("OTG"); break;
case 11 : SERIAL_ECHOPGM("ETH"); break;
case 12 : SERIAL_ECHOPGM("FSMC, SDIO, OTG"); break;
case 13 : SERIAL_ECHOPGM("DCMI"); break;
case 14 : SERIAL_ECHOPGM("unused (shouldn't see this)"); break;
case 15 : SERIAL_ECHOPGM("EVENTOUT"); break;
}
}
} // pwm_details
#endif // NUM_DIGITAL_PINS

104
Marlin/src/HAL/STM32F1/pinsDebug.h

@ -18,10 +18,102 @@
*/ */
#pragma once #pragma once
#ifdef NUM_DIGITAL_PINS // Only in ST's Arduino core (STM32duino, STM32Core) /**
#include "../STM32/pinsDebug_STM32duino.h" * Support routines for STM32GENERIC (Maple)
#elif defined(BOARD_NR_GPIO_PINS) // Only in STM32GENERIC (Maple) */
#include "../STM32/pinsDebug_STM32GENERIC.h"
#else /**
#error "M43 not supported for this board" * Translation of routines & variables used by pinsDebug.h
*/
#ifndef BOARD_NR_GPIO_PINS // Only in STM32GENERIC (Maple)
#error "Expected BOARD_NR_GPIO_PINS not found"
#endif #endif
#include "fastio.h"
extern const stm32_pin_info PIN_MAP[BOARD_NR_GPIO_PINS];
#define NUM_DIGITAL_PINS BOARD_NR_GPIO_PINS
#define NUMBER_PINS_TOTAL BOARD_NR_GPIO_PINS
#define VALID_PIN(pin) (pin >= 0 && pin < BOARD_NR_GPIO_PINS)
#define GET_ARRAY_PIN(p) pin_t(pin_array[p].pin)
#define pwm_status(pin) PWM_PIN(pin)
#define digitalRead_mod(p) extDigitalRead(p)
#define PRINT_PIN(p) do{ sprintf_P(buffer, PSTR("%3hd "), int16_t(p)); SERIAL_ECHO(buffer); }while(0)
#define PRINT_PORT(p) print_port(p)
#define PRINT_ARRAY_NAME(x) do{ sprintf_P(buffer, PSTR("%-" STRINGIFY(MAX_NAME_LENGTH) "s"), pin_array[x].name); SERIAL_ECHO(buffer); }while(0)
#define MULTI_NAME_PAD 21 // space needed to be pretty if not first name assigned to a pin
// pins that will cause hang/reset/disconnect in M43 Toggle and Watch utilities
#ifndef M43_NEVER_TOUCH
#define M43_NEVER_TOUCH(Q) (Q >= 9 && Q <= 12) // SERIAL/USB pins PA9(TX) PA10(RX)
#endif
static inline int8_t get_pin_mode(pin_t pin) {
return VALID_PIN(pin) ? _GET_MODE(pin) : -1;
}
static inline pin_t DIGITAL_PIN_TO_ANALOG_PIN(pin_t pin) {
if (!VALID_PIN(pin)) return -1;
int8_t adc_channel = int8_t(PIN_MAP[pin].adc_channel);
#ifdef NUM_ANALOG_INPUTS
if (adc_channel >= NUM_ANALOG_INPUTS) adc_channel = ADCx;
#endif
return pin_t(adc_channel);
}
static inline bool IS_ANALOG(pin_t pin) {
if (!VALID_PIN(pin)) return false;
if (PIN_MAP[pin].adc_channel != ADCx) {
#ifdef NUM_ANALOG_INPUTS
if (PIN_MAP[pin].adc_channel >= NUM_ANALOG_INPUTS) return false;
#endif
return _GET_MODE(pin) == GPIO_INPUT_ANALOG && !M43_NEVER_TOUCH(pin);
}
return false;
}
static inline bool GET_PINMODE(const pin_t pin) {
return VALID_PIN(pin) && !IS_INPUT(pin);
}
static inline bool GET_ARRAY_IS_DIGITAL(const int16_t array_pin) {
const pin_t pin = GET_ARRAY_PIN(array_pin);
return (!IS_ANALOG(pin)
#ifdef NUM_ANALOG_INPUTS
|| PIN_MAP[pin].adc_channel >= NUM_ANALOG_INPUTS
#endif
);
}
#include "../../inc/MarlinConfig.h" // Allow pins/pins.h to set density
static inline void pwm_details(const pin_t pin) {
if (PWM_PIN(pin)) {
timer_dev * const tdev = PIN_MAP[pin].timer_device;
const uint8_t channel = PIN_MAP[pin].timer_channel;
const char num = (
#if EITHER(STM32_HIGH_DENSITY, STM32_XL_DENSITY)
tdev == &timer8 ? '8' :
tdev == &timer5 ? '5' :
#endif
tdev == &timer4 ? '4' :
tdev == &timer3 ? '3' :
tdev == &timer2 ? '2' :
tdev == &timer1 ? '1' : '?'
);
char buffer[10];
sprintf_P(buffer, PSTR(" TIM%c CH%c"), num, ('0' + channel));
SERIAL_ECHO(buffer);
}
}
static inline void print_port(pin_t pin) {
const char port = 'A' + char(pin >> 4); // pin div 16
const int16_t gbit = PIN_MAP[pin].gpio_bit;
char buffer[8];
sprintf_P(buffer, PSTR("P%c%hd "), port, gbit);
if (gbit < 10) SERIAL_CHAR(' ');
SERIAL_ECHO(buffer);
}

95
Marlin/src/HAL/STM32_F4_F7/HAL.cpp

@ -1,95 +0,0 @@
/**
* Marlin 3D Printer Firmware
*
* Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
* Copyright (c) 2016 Bob Cousins bobcousins42@googlemail.com
* Copyright (c) 2015-2016 Nico Tonnhofer wurstnase.reprap@gmail.com
* Copyright (c) 2017 Victor Perez
*
* This program is free software: you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation, either version 3 of the License, or
* (at your option) any later version.
*
* This program is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with this program. If not, see <https://www.gnu.org/licenses/>.
*
*/
#if defined(STM32GENERIC) && (defined(STM32F4) || defined(STM32F7))
#include "HAL.h"
//#include <Wire.h>
// ------------------------
// Public Variables
// ------------------------
uint16_t HAL_adc_result;
// ------------------------
// Public functions
// ------------------------
/* VGPV Done with defines
// disable interrupts
void cli() { noInterrupts(); }
// enable interrupts
void sei() { interrupts(); }
*/
void HAL_clear_reset_source() { __HAL_RCC_CLEAR_RESET_FLAGS(); }
uint8_t HAL_get_reset_source() {
if (__HAL_RCC_GET_FLAG(RCC_FLAG_IWDGRST) != RESET) return RST_WATCHDOG;
if (__HAL_RCC_GET_FLAG(RCC_FLAG_SFTRST) != RESET) return RST_SOFTWARE;
if (__HAL_RCC_GET_FLAG(RCC_FLAG_PINRST) != RESET) return RST_EXTERNAL;
if (__HAL_RCC_GET_FLAG(RCC_FLAG_PORRST) != RESET) return RST_POWER_ON;
return 0;
}
void _delay_ms(const int delay_ms) { delay(delay_ms); }
extern "C" {
extern unsigned int _ebss; // end of bss section
}
// return free memory between end of heap (or end bss) and whatever is current
/*
#include <wirish/syscalls.c>
//extern caddr_t _sbrk(int incr);
#ifndef CONFIG_HEAP_END
extern char _lm_heap_end;
#define CONFIG_HEAP_END ((caddr_t)&_lm_heap_end)
#endif
extern "C" {
static int freeMemory() {
char top = 't';
return &top - reinterpret_cast<char*>(sbrk(0));
}
int freeMemory() {
int free_memory;
int heap_end = (int)_sbrk(0);
free_memory = ((int)&free_memory) - ((int)heap_end);
return free_memory;
}
}
*/
// ------------------------
// ADC
// ------------------------
void HAL_adc_start_conversion(const uint8_t adc_pin) { HAL_adc_result = analogRead(adc_pin); }
uint16_t HAL_adc_get_result() { return HAL_adc_result; }
#endif // STM32GENERIC && (STM32F4 || STM32F7)

203
Marlin/src/HAL/STM32_F4_F7/HAL.h

@ -1,203 +0,0 @@
/**
* Marlin 3D Printer Firmware
*
* Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
* Copyright (c) 2016 Bob Cousins bobcousins42@googlemail.com
* Copyright (c) 2015-2016 Nico Tonnhofer wurstnase.reprap@gmail.com
* Copyright (c) 2017 Victor Perez
*
* This program is free software: you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation, either version 3 of the License, or
* (at your option) any later version.
*
* This program is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with this program. If not, see <https://www.gnu.org/licenses/>.
*
*/
#pragma once
#define CPU_32_BIT
#include "../../inc/MarlinConfigPre.h"
#include "../shared/Marduino.h"
#include "../shared/math_32bit.h"
#include "../shared/HAL_SPI.h"
#include "fastio.h"
#include "watchdog.h"
#include <stdint.h>
#if defined(STM32F4) && USBCON
#include <USBSerial.h>
#endif
// ------------------------
// Defines
// ------------------------
// Serial override
//extern HalSerial usb_serial;
#define _MSERIAL(X) SerialUART##X
#define MSERIAL(X) _MSERIAL(X)
#define SerialUART0 Serial1
#if defined(STM32F4) && SERIAL_PORT == 0
#error "SERIAL_PORT cannot be 0. (Port 0 does not exist.) Please update your configuration."
#elif SERIAL_PORT == -1
#define MYSERIAL0 SerialUSB
#elif WITHIN(SERIAL_PORT, 0, 6)
#define MYSERIAL0 MSERIAL(SERIAL_PORT)
#else
#error "SERIAL_PORT must be from -1 to 6. Please update your configuration."
#endif
#ifdef SERIAL_PORT_2
#if defined(STM32F4) && SERIAL_PORT_2 == 0
#error "SERIAL_PORT_2 cannot be 0. (Port 0 does not exist.) Please update your configuration."
#elif SERIAL_PORT_2 == -1
#define MYSERIAL1 SerialUSB
#elif WITHIN(SERIAL_PORT_2, 0, 6)
#define MYSERIAL1 MSERIAL(SERIAL_PORT_2)
#else
#error "SERIAL_PORT_2 must be from -1 to 6. Please update your configuration."
#endif
#endif
#ifdef LCD_SERIAL_PORT
#if defined(STM32F4) && LCD_SERIAL_PORT == 0
#error "LCD_SERIAL_PORT cannot be 0. (Port 0 does not exist.) Please update your configuration."
#elif LCD_SERIAL_PORT == -1
#define LCD_SERIAL SerialUSB
#elif WITHIN(LCD_SERIAL_PORT, 0, 6)
#define LCD_SERIAL MSERIAL(LCD_SERIAL_PORT)
#else
#error "LCD_SERIAL_PORT must be from -1 to 6. Please update your configuration."
#endif
#endif
/**
* TODO: review this to return 1 for pins that are not analog input
*/
#ifndef analogInputToDigitalPin
#define analogInputToDigitalPin(p) (p)
#endif
#define CRITICAL_SECTION_START() uint32_t primask = __get_PRIMASK(); __disable_irq()
#define CRITICAL_SECTION_END() if (!primask) __enable_irq()
#define ISRS_ENABLED() (!__get_PRIMASK())
#define ENABLE_ISRS() __enable_irq()
#define DISABLE_ISRS() __disable_irq()
#define cli() __disable_irq()
#define sei() __enable_irq()
// On AVR this is in math.h?
#define square(x) ((x)*(x))
#ifndef strncpy_P
#define strncpy_P(dest, src, num) strncpy((dest), (src), (num))
#endif
// Fix bug in pgm_read_ptr
#undef pgm_read_ptr
#define pgm_read_ptr(addr) (*(addr))
// ------------------------
// Types
// ------------------------
typedef int8_t pin_t;
#ifdef STM32F4
#define HAL_SERVO_LIB libServo
#endif
// ------------------------
// Public Variables
// ------------------------
// Result of last ADC conversion
extern uint16_t HAL_adc_result;
// ------------------------
// Public functions
// ------------------------
// Memory related
#define __bss_end __bss_end__
inline void HAL_init() {}
// Clear reset reason
void HAL_clear_reset_source();
// Reset reason
uint8_t HAL_get_reset_source();
inline void HAL_reboot() {} // reboot the board or restart the bootloader
void _delay_ms(const int delay);
/*
extern "C" {
int freeMemory();
}
*/
extern "C" char* _sbrk(int incr);
/*
int freeMemory() {
volatile int top;
top = (int)((char*)&top - reinterpret_cast<char*>(_sbrk(0)));
return top;
}
*/
#if GCC_VERSION <= 50000
#pragma GCC diagnostic push
#pragma GCC diagnostic ignored "-Wunused-function"
#endif
static inline int freeMemory() {
volatile char top;
return &top - reinterpret_cast<char*>(_sbrk(0));
}
#if GCC_VERSION <= 50000
#pragma GCC diagnostic pop
#endif
//
// ADC
//
#define HAL_ANALOG_SELECT(pin) pinMode(pin, INPUT)
inline void HAL_adc_init() {}
#define HAL_ADC_VREF 3.3
#define HAL_ADC_RESOLUTION 10
#define HAL_START_ADC(pin) HAL_adc_start_conversion(pin)
#define HAL_READ_ADC() HAL_adc_result
#define HAL_ADC_READY() true
void HAL_adc_start_conversion(const uint8_t adc_pin);
uint16_t HAL_adc_get_result();
#define GET_PIN_MAP_PIN(index) index
#define GET_PIN_MAP_INDEX(pin) pin
#define PARSED_PIN_INDEX(code, dval) parser.intval(code, dval)
#ifdef STM32F4
#define JTAG_DISABLE() afio_cfg_debug_ports(AFIO_DEBUG_SW_ONLY)
#define JTAGSWD_DISABLE() afio_cfg_debug_ports(AFIO_DEBUG_NONE)
#endif

164
Marlin/src/HAL/STM32_F4_F7/HAL_SPI.cpp

@ -1,164 +0,0 @@
/**
* Marlin 3D Printer Firmware
* Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
*
* Based on Sprinter and grbl.
* Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm
* Copyright (c) 2017 Victor Perez
*
* This program is free software: you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation, either version 3 of the License, or
* (at your option) any later version.
*
* This program is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with this program. If not, see <https://www.gnu.org/licenses/>.
*
*/
#if defined(STM32GENERIC) && (defined(STM32F4) || defined(STM32F7))
/**
* Software SPI functions originally from Arduino Sd2Card Library
* Copyright (c) 2009 by William Greiman
*/
/**
* Adapted to the Marlin STM32F4/7 HAL
*/
#include "../../inc/MarlinConfig.h"
#include <SPI.h>
#include <pins_arduino.h>
#include "../shared/HAL_SPI.h"
#include "spi_pins.h"
// ------------------------
// Public Variables
// ------------------------
static SPISettings spiConfig;
// ------------------------
// Public functions
// ------------------------
#if ENABLED(SOFTWARE_SPI)
// ------------------------
// Software SPI
// ------------------------
#error "Software SPI not supported for STM32F4/7. Use Hardware SPI."
#else
// ------------------------
// Hardware SPI
// ------------------------
/**
* VGPV SPI speed start and F_CPU/2, by default 72/2 = 36Mhz
*/
/**
* @brief Begin SPI port setup
*
* @return Nothing
*
* @details Only configures SS pin since libmaple creates and initialize the SPI object
*/
void spiBegin() {
#if !defined(SS_PIN) || SS_PIN < 0
#error "SS_PIN not defined!"
#endif
OUT_WRITE(SS_PIN, HIGH);
}
/** Configure SPI for specified SPI speed */
void spiInit(uint8_t spiRate) {
// Use datarates Marlin uses
uint32_t clock;
switch (spiRate) {
case SPI_FULL_SPEED: clock = 20000000; break; // 13.9mhz=20000000 6.75mhz=10000000 3.38mhz=5000000 .833mhz=1000000
case SPI_HALF_SPEED: clock = 5000000; break;
case SPI_QUARTER_SPEED: clock = 2500000; break;
case SPI_EIGHTH_SPEED: clock = 1250000; break;
case SPI_SPEED_5: clock = 625000; break;
case SPI_SPEED_6: clock = 300000; break;
default: clock = 4000000; // Default from the SPI libarary
}
spiConfig = SPISettings(clock, MSBFIRST, SPI_MODE0);
SPI.begin();
}
/**
* @brief Receives a single byte from the SPI port.
*
* @return Byte received
*
* @details
*/
uint8_t spiRec() {
SPI.beginTransaction(spiConfig);
uint8_t returnByte = SPI.transfer(0xFF);
SPI.endTransaction();
return returnByte;
}
/**
* @brief Receives a number of bytes from the SPI port to a buffer
*
* @param buf Pointer to starting address of buffer to write to.
* @param nbyte Number of bytes to receive.
* @return Nothing
*
* @details Uses DMA
*/
void spiRead(uint8_t* buf, uint16_t nbyte) {
SPI.beginTransaction(spiConfig);
#ifndef STM32GENERIC
SPI.dmaTransfer(0, const_cast<uint8_t*>(buf), nbyte);
#else
SPI.transfer((uint8_t*)buf, nbyte);
#endif
SPI.endTransaction();
}
/**
* @brief Sends a single byte on SPI port
*
* @param b Byte to send
*
* @details
*/
void spiSend(uint8_t b) {
SPI.beginTransaction(spiConfig);
SPI.transfer(b);
SPI.endTransaction();
}
/**
* @brief Write token and then write from 512 byte buffer to SPI (for SD card)
*
* @param buf Pointer with buffer start address
* @return Nothing
*
* @details Use DMA
*/
void spiSendBlock(uint8_t token, const uint8_t* buf) {
SPI.beginTransaction(spiConfig);
SPI.transfer(token);
#ifndef STM32GENERIC
SPI.dmaSend(const_cast<uint8_t*>(buf), 512);
#else
SPI.transfer((uint8_t*)buf, nullptr, 512);
#endif
SPI.endTransaction();
}
#endif // SOFTWARE_SPI
#endif // STM32GENERIC && (STM32F4 || STM32F7)

6
Marlin/src/HAL/STM32_F4_F7/README.md

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

12
Marlin/src/HAL/STM32_F4_F7/STM32F4/README.md

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

113
Marlin/src/HAL/STM32_F4_F7/STM32F4/timers.cpp

@ -1,113 +0,0 @@
/**
* Marlin 3D Printer Firmware
*
* Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
* Copyright (c) 2016 Bob Cousins bobcousins42@googlemail.com
* Copyright (c) 2015-2016 Nico Tonnhofer wurstnase.reprap@gmail.com
*
* This program is free software: you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation, either version 3 of the License, or
* (at your option) any later version.
*
* This program is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with this program. If not, see <https://www.gnu.org/licenses/>.
*
*/
#if defined(STM32GENERIC) && defined(STM32F4)
#include "../../../inc/MarlinConfig.h"
// ------------------------
// Local defines
// ------------------------
#define NUM_HARDWARE_TIMERS 2
#define STEP_TIMER_IRQ_ID TIM5_IRQn
#define TEMP_TIMER_IRQ_ID TIM7_IRQn
// ------------------------
// Private Variables
// ------------------------
stm32_timer_t TimerHandle[NUM_HARDWARE_TIMERS];
// ------------------------
// Public functions
// ------------------------
bool timers_initialized[NUM_HARDWARE_TIMERS] = {false};
void HAL_timer_start(const uint8_t timer_num, const uint32_t frequency) {
if (!timers_initialized[timer_num]) {
constexpr uint32_t step_prescaler = STEPPER_TIMER_PRESCALE - 1,
temp_prescaler = TEMP_TIMER_PRESCALE - 1;
switch (timer_num) {
case STEP_TIMER_NUM:
// STEPPER TIMER TIM5 - use a 32bit timer
__HAL_RCC_TIM5_CLK_ENABLE();
TimerHandle[timer_num].handle.Instance = TIM5;
TimerHandle[timer_num].handle.Init.Prescaler = step_prescaler;
TimerHandle[timer_num].handle.Init.CounterMode = TIM_COUNTERMODE_UP;
TimerHandle[timer_num].handle.Init.ClockDivision = TIM_CLOCKDIVISION_DIV1;
TimerHandle[timer_num].callback = (uint32_t)TC5_Handler;
HAL_NVIC_SetPriority(STEP_TIMER_IRQ_ID, 1, 0);
break;
case TEMP_TIMER_NUM:
// TEMP TIMER TIM7 - any available 16bit Timer (1 already used for PWM)
__HAL_RCC_TIM7_CLK_ENABLE();
TimerHandle[timer_num].handle.Instance = TIM7;
TimerHandle[timer_num].handle.Init.Prescaler = temp_prescaler;
TimerHandle[timer_num].handle.Init.CounterMode = TIM_COUNTERMODE_UP;
TimerHandle[timer_num].handle.Init.ClockDivision = TIM_CLOCKDIVISION_DIV1;
TimerHandle[timer_num].callback = (uint32_t)TC7_Handler;
HAL_NVIC_SetPriority(TEMP_TIMER_IRQ_ID, 2, 0);
break;
}
timers_initialized[timer_num] = true;
}
TimerHandle[timer_num].handle.Init.Period = (((HAL_TIMER_RATE) / TimerHandle[timer_num].handle.Init.Prescaler) / frequency) - 1;
if (HAL_TIM_Base_Init(&TimerHandle[timer_num].handle) == HAL_OK)
HAL_TIM_Base_Start_IT(&TimerHandle[timer_num].handle);
}
extern "C" {
void TIM5_IRQHandler() { ((void(*)())TimerHandle[0].callback)(); }
void TIM7_IRQHandler() { ((void(*)())TimerHandle[1].callback)(); }
}
void HAL_timer_enable_interrupt(const uint8_t timer_num) {
switch (timer_num) {
case STEP_TIMER_NUM: HAL_NVIC_EnableIRQ(STEP_TIMER_IRQ_ID); break;
case TEMP_TIMER_NUM: HAL_NVIC_EnableIRQ(TEMP_TIMER_IRQ_ID); break;
}
}
void HAL_timer_disable_interrupt(const uint8_t timer_num) {
switch (timer_num) {
case STEP_TIMER_NUM: HAL_NVIC_DisableIRQ(STEP_TIMER_IRQ_ID); break;
case TEMP_TIMER_NUM: HAL_NVIC_DisableIRQ(TEMP_TIMER_IRQ_ID); break;
}
// We NEED memory barriers to ensure Interrupts are actually disabled!
// ( https://dzone.com/articles/nvic-disabling-interrupts-on-arm-cortex-m-and-the )
__DSB();
__ISB();
}
bool HAL_timer_interrupt_enabled(const uint8_t timer_num) {
switch (timer_num) {
case STEP_TIMER_NUM: return NVIC->ISER[(uint32_t)((int32_t)STEP_TIMER_IRQ_ID) >> 5] & (uint32_t)(1 << ((uint32_t)((int32_t)STEP_TIMER_IRQ_ID) & (uint32_t)0x1F));
case TEMP_TIMER_NUM: return NVIC->ISER[(uint32_t)((int32_t)TEMP_TIMER_IRQ_ID) >> 5] & (uint32_t)(1 << ((uint32_t)((int32_t)TEMP_TIMER_IRQ_ID) & (uint32_t)0x1F));
}
return false;
}
#endif // STM32GENERIC && STM32F4

134
Marlin/src/HAL/STM32_F4_F7/STM32F4/timers.h

@ -1,134 +0,0 @@
/**
* Marlin 3D Printer Firmware
*
* Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
* Copyright (c) 2016 Bob Cousins bobcousins42@googlemail.com
* Copyright (c) 2017 Victor Perez
*
* This program is free software: you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation, either version 3 of the License, or
* (at your option) any later version.
*
* This program is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with this program. If not, see <https://www.gnu.org/licenses/>.
*
*/
#pragma once
#include <stdint.h>
// ------------------------
// Defines
// ------------------------
#define FORCE_INLINE __attribute__((always_inline)) inline
#define hal_timer_t uint32_t // TODO: One is 16-bit, one 32-bit - does this need to be checked?
#define HAL_TIMER_TYPE_MAX 0xFFFF
#define HAL_TIMER_RATE (HAL_RCC_GetSysClockFreq() / 2) // frequency of timer peripherals
#ifndef STEP_TIMER_NUM
#define STEP_TIMER_NUM 0 // Timer Index for Stepper
#endif
#ifndef PULSE_TIMER_NUM
#define PULSE_TIMER_NUM STEP_TIMER_NUM
#endif
#ifndef TEMP_TIMER_NUM
#define TEMP_TIMER_NUM 1 // Timer Index for Temperature
#endif
#define TEMP_TIMER_PRESCALE 1000 // prescaler for setting Temp timer, 72Khz
#define TEMP_TIMER_FREQUENCY 1000 // temperature interrupt frequency
#define STEPPER_TIMER_PRESCALE 54 // was 40,prescaler for setting stepper timer, 2Mhz
#define STEPPER_TIMER_RATE (HAL_TIMER_RATE / STEPPER_TIMER_PRESCALE) // frequency of stepper timer
#define STEPPER_TIMER_TICKS_PER_US ((STEPPER_TIMER_RATE) / 1000000) // stepper timer ticks per µs
#define PULSE_TIMER_RATE STEPPER_TIMER_RATE // frequency of pulse timer
#define PULSE_TIMER_PRESCALE STEPPER_TIMER_PRESCALE
#define PULSE_TIMER_TICKS_PER_US STEPPER_TIMER_TICKS_PER_US
#define ENABLE_STEPPER_DRIVER_INTERRUPT() HAL_timer_enable_interrupt(STEP_TIMER_NUM)
#define DISABLE_STEPPER_DRIVER_INTERRUPT() HAL_timer_disable_interrupt(STEP_TIMER_NUM)
#define STEPPER_ISR_ENABLED() HAL_timer_interrupt_enabled(STEP_TIMER_NUM)
#define ENABLE_TEMPERATURE_INTERRUPT() HAL_timer_enable_interrupt(TEMP_TIMER_NUM)
#define DISABLE_TEMPERATURE_INTERRUPT() HAL_timer_disable_interrupt(TEMP_TIMER_NUM)
// TODO change this
#ifdef STM32GENERIC
#define TC_TIMER_ARGS
#else
#define TC_TIMER_ARGS stimer_t *htim
#endif
extern void TC5_Handler(TC_TIMER_ARGS);
extern void TC7_Handler(TC_TIMER_ARGS);
#ifndef HAL_STEP_TIMER_ISR
#define HAL_STEP_TIMER_ISR() void TC5_Handler(TC_TIMER_ARGS)
#endif
#ifndef HAL_TEMP_TIMER_ISR
#define HAL_TEMP_TIMER_ISR() void TC7_Handler(TC_TIMER_ARGS)
#endif
// ------------------------
// Types
// ------------------------
#ifdef STM32GENERIC
typedef struct {
TIM_HandleTypeDef handle;
uint32_t callback;
} tTimerConfig;
typedef tTimerConfig stm32_timer_t;
#else
typedef stimer_t stm32_timer_t;
#endif
// ------------------------
// Public Variables
// ------------------------
extern stm32_timer_t TimerHandle[];
// ------------------------
// Public functions
// ------------------------
void HAL_timer_start(const uint8_t timer_num, const uint32_t frequency);
void HAL_timer_enable_interrupt(const uint8_t timer_num);
void HAL_timer_disable_interrupt(const uint8_t timer_num);
bool HAL_timer_interrupt_enabled(const uint8_t timer_num);
FORCE_INLINE static uint32_t HAL_timer_get_count(const uint8_t timer_num) {
return __HAL_TIM_GET_COUNTER(&TimerHandle[timer_num].handle);
}
FORCE_INLINE static void HAL_timer_set_compare(const uint8_t timer_num, const uint32_t compare) {
__HAL_TIM_SET_AUTORELOAD(&TimerHandle[timer_num].handle, compare);
if (HAL_timer_get_count(timer_num) >= compare)
TimerHandle[timer_num].handle.Instance->EGR |= TIM_EGR_UG; // Generate an immediate update interrupt
}
FORCE_INLINE static hal_timer_t HAL_timer_get_compare(const uint8_t timer_num) {
return __HAL_TIM_GET_AUTORELOAD(&TimerHandle[timer_num].handle);
}
#ifdef STM32GENERIC
FORCE_INLINE static void HAL_timer_isr_prologue(const uint8_t timer_num) {
if (__HAL_TIM_GET_FLAG(&TimerHandle[timer_num].handle, TIM_FLAG_UPDATE) == SET)
__HAL_TIM_CLEAR_FLAG(&TimerHandle[timer_num].handle, TIM_FLAG_UPDATE);
}
#else
#define HAL_timer_isr_prologue(TIMER_NUM)
#endif
#define HAL_timer_isr_epilogue(TIMER_NUM)

27
Marlin/src/HAL/STM32_F4_F7/STM32F7/README.md

@ -1,27 +0,0 @@
# This HAL is for the STM32F765 board "The Borg" used with STM32Generic Arduino core by danieleff.
# Original core is located at:
https://github.com/danieleff/STM32GENERIC
but I haven't committed the changes needed for the Borg there yet, so please use:
https://github.com/Spawn32/STM32GENERIC
Unzip it into [Arduino]/hardware folder
Download the latest GNU ARM Embedded Toolchain:
https://developer.arm.com/open-source/gnu-toolchain/gnu-rm/downloads
(The one in Arduino doesn't support STM32F7).
Change compiler.path in platform.txt to point to the one you downloaded.
# This HAL is in development.
# Currently only tested on "The Borg".
You will also need the latest Arduino 1.9.0-beta or newer.
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.

898
Marlin/src/HAL/STM32_F4_F7/STM32F7/TMC2660.cpp

@ -1,898 +0,0 @@
/**
* TMC26XStepper.cpp - - TMC26X Stepper library for Wiring/Arduino
*
* based on the stepper library by Tom Igoe, et. al.
*
* Copyright (c) 2011, Interactive Matter, Marcus Nowotny
*
* Permission is hereby granted, free of charge, to any person obtaining a copy
* of this software and associated documentation files (the "Software"), to deal
* in the Software without restriction, including without limitation the rights
* to use, copy, modify, merge, publish, distribute, sublicense, and/or sell
* copies of the Software, and to permit persons to whom the Software is
* furnished to do so, subject to the following conditions:
*
* The above copyright notice and this permission notice shall be included in
* all copies or substantial portions of the Software.
*
* THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
* IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
* FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
* AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
* LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM,
* OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN
* THE SOFTWARE.
*/
#if defined(STM32GENERIC) && defined(STM32F7)
#include "../../../inc/MarlinConfigPre.h"
#if HAS_DRIVER(TMC2660)
#include <stdbool.h>
#include <SPI.h>
#include "TMC2660.h"
#include "../../../inc/MarlinConfig.h"
#include "../../../MarlinCore.h"
#include "../../../module/stepper/indirection.h"
#include "../../../module/printcounter.h"
#include "../../../libs/duration_t.h"
#include "../../../libs/hex_print.h"
//some default values used in initialization
#define DEFAULT_MICROSTEPPING_VALUE 32
//TMC26X register definitions
#define DRIVER_CONTROL_REGISTER 0x0UL
#define CHOPPER_CONFIG_REGISTER 0x80000UL
#define COOL_STEP_REGISTER 0xA0000ul
#define STALL_GUARD2_LOAD_MEASURE_REGISTER 0xC0000ul
#define DRIVER_CONFIG_REGISTER 0xE0000ul
#define REGISTER_BIT_PATTERN 0xFFFFFul
//definitions for the driver control register
#define MICROSTEPPING_PATTERN 0xFul
#define STEP_INTERPOLATION 0x200UL
#define DOUBLE_EDGE_STEP 0x100UL
#define VSENSE 0x40UL
#define READ_MICROSTEP_POSTION 0x0UL
#define READ_STALL_GUARD_READING 0x10UL
#define READ_STALL_GUARD_AND_COOL_STEP 0x20UL
#define READ_SELECTION_PATTERN 0x30UL
//definitions for the chopper config register
#define CHOPPER_MODE_STANDARD 0x0UL
#define CHOPPER_MODE_T_OFF_FAST_DECAY 0x4000UL
#define T_OFF_PATTERN 0xFul
#define RANDOM_TOFF_TIME 0x2000UL
#define BLANK_TIMING_PATTERN 0x18000UL
#define BLANK_TIMING_SHIFT 15
#define HYSTERESIS_DECREMENT_PATTERN 0x1800UL
#define HYSTERESIS_DECREMENT_SHIFT 11
#define HYSTERESIS_LOW_VALUE_PATTERN 0x780UL
#define HYSTERESIS_LOW_SHIFT 7
#define HYSTERESIS_START_VALUE_PATTERN 0x78UL
#define HYSTERESIS_START_VALUE_SHIFT 4
#define T_OFF_TIMING_PATERN 0xFul
//definitions for cool step register
#define MINIMUM_CURRENT_FOURTH 0x8000UL
#define CURRENT_DOWN_STEP_SPEED_PATTERN 0x6000UL
#define SE_MAX_PATTERN 0xF00ul
#define SE_CURRENT_STEP_WIDTH_PATTERN 0x60UL
#define SE_MIN_PATTERN 0xFul
//definitions for StallGuard2 current register
#define STALL_GUARD_FILTER_ENABLED 0x10000UL
#define STALL_GUARD_TRESHHOLD_VALUE_PATTERN 0x17F00ul
#define CURRENT_SCALING_PATTERN 0x1Ful
#define STALL_GUARD_CONFIG_PATTERN 0x17F00ul
#define STALL_GUARD_VALUE_PATTERN 0x7F00ul
//definitions for the input from the TMC2660
#define STATUS_STALL_GUARD_STATUS 0x1UL
#define STATUS_OVER_TEMPERATURE_SHUTDOWN 0x2UL
#define STATUS_OVER_TEMPERATURE_WARNING 0x4UL
#define STATUS_SHORT_TO_GROUND_A 0x8UL
#define STATUS_SHORT_TO_GROUND_B 0x10UL
#define STATUS_OPEN_LOAD_A 0x20UL
#define STATUS_OPEN_LOAD_B 0x40UL
#define STATUS_STAND_STILL 0x80UL
#define READOUT_VALUE_PATTERN 0xFFC00ul
#define CPU_32_BIT
//default values
#define INITIAL_MICROSTEPPING 0x3UL //32th microstepping
SPIClass SPI_6(SPI6, SPI6_MOSI_PIN, SPI6_MISO_PIN, SPI6_SCK_PIN);
#define STEPPER_SPI SPI_6
//debuging output
//#define TMC_DEBUG1
uint8_t current_scaling = 0;
/**
* Constructor
* number_of_steps - the steps per rotation
* cs_pin - the SPI client select pin
* dir_pin - the pin where the direction pin is connected
* step_pin - the pin where the step pin is connected
*/
TMC26XStepper::TMC26XStepper(const int16_t in_steps, int16_t cs_pin, int16_t dir_pin, int16_t step_pin, uint16_t current, uint16_t resistor) {
// We are not started yet
started = false;
// By default cool step is not enabled
cool_step_enabled = false;
// Save the pins for later use
this->cs_pin = cs_pin;
this->dir_pin = dir_pin;
this->step_pin = step_pin;
// Store the current sense resistor value for later use
this->resistor = resistor;
// Initizalize our status values
this->steps_left = 0;
this->direction = 0;
// Initialize register values
driver_control_register_value = DRIVER_CONTROL_REGISTER | INITIAL_MICROSTEPPING;
chopper_config_register = CHOPPER_CONFIG_REGISTER;
// Setting the default register values
driver_control_register_value = DRIVER_CONTROL_REGISTER|INITIAL_MICROSTEPPING;
microsteps = _BV(INITIAL_MICROSTEPPING);
chopper_config_register = CHOPPER_CONFIG_REGISTER;
cool_step_register_value = COOL_STEP_REGISTER;
stallguard2_current_register_value = STALL_GUARD2_LOAD_MEASURE_REGISTER;
driver_configuration_register_value = DRIVER_CONFIG_REGISTER | READ_STALL_GUARD_READING;
// Set the current
setCurrent(current);
// Set to a conservative start value
setConstantOffTimeChopper(7, 54, 13,12,1);
// Set a nice microstepping value
setMicrosteps(DEFAULT_MICROSTEPPING_VALUE);
// Save the number of steps
number_of_steps = in_steps;
}
/**
* start & configure the stepper driver
* just must be called.
*/
void TMC26XStepper::start() {
#ifdef TMC_DEBUG1
SERIAL_ECHOLNPGM("\n TMC26X stepper library");
SERIAL_ECHOPAIR("\n CS pin: ", cs_pin);
SERIAL_ECHOPAIR("\n DIR pin: ", dir_pin);
SERIAL_ECHOPAIR("\n STEP pin: ", step_pin);
SERIAL_PRINTF("\n current scaling: %d", current_scaling);
SERIAL_PRINTF("\n Resistor: %d", resistor);
//SERIAL_PRINTF("\n current: %d", current);
SERIAL_ECHOPAIR("\n Microstepping: ", microsteps);
#endif
//set the pins as output & its initial value
pinMode(step_pin, OUTPUT);
pinMode(dir_pin, OUTPUT);
pinMode(cs_pin, OUTPUT);
extDigitalWrite(step_pin, LOW);
extDigitalWrite(dir_pin, LOW);
extDigitalWrite(cs_pin, HIGH);
STEPPER_SPI.begin();
STEPPER_SPI.beginTransaction(SPISettings(4000000, MSBFIRST, SPI_MODE3));
//set the initial values
send262(driver_control_register_value);
send262(chopper_config_register);
send262(cool_step_register_value);
send262(stallguard2_current_register_value);
send262(driver_configuration_register_value);
//save that we are in running mode
started = true;
}
/**
* Mark the driver as unstarted to be able to start it again
*/
void TMC26XStepper::un_start() { started = false; }
/**
* Sets the speed in revs per minute
*/
void TMC26XStepper::setSpeed(uint16_t whatSpeed) {
this->speed = whatSpeed;
this->step_delay = 60UL * sq(1000UL) / ((uint32_t)this->number_of_steps * (uint32_t)whatSpeed * (uint32_t)this->microsteps);
#ifdef TMC_DEBUG0 // crashes
SERIAL_ECHOPAIR("\nStep delay in micros: ", this->step_delay);
#endif
// Update the next step time
this->next_step_time = this->last_step_time + this->step_delay;
}
uint16_t TMC26XStepper::getSpeed() { return this->speed; }
/**
* Moves the motor steps_to_move steps.
* Negative indicates the reverse direction.
*/
char TMC26XStepper::step(int16_t steps_to_move) {
if (this->steps_left == 0) {
this->steps_left = ABS(steps_to_move); // how many steps to take
// determine direction based on whether steps_to_move is + or -:
if (steps_to_move > 0)
this->direction = 1;
else if (steps_to_move < 0)
this->direction = 0;
return 0;
}
return -1;
}
char TMC26XStepper::move() {
// decrement the number of steps, moving one step each time:
if (this->steps_left > 0) {
uint32_t time = micros();
// move only if the appropriate delay has passed:
// rem if (time >= this->next_step_time) {
if (ABS(time - this->last_step_time) > this->step_delay) {
// increment or decrement the step number,
// depending on direction:
if (this->direction == 1)
extDigitalWrite(step_pin, HIGH);
else {
extDigitalWrite(dir_pin, HIGH);
extDigitalWrite(step_pin, HIGH);
}
// get the timeStamp of when you stepped:
this->last_step_time = time;
this->next_step_time = time + this->step_delay;
// decrement the steps left:
steps_left--;
//disable the step & dir pins
extDigitalWrite(step_pin, LOW);
extDigitalWrite(dir_pin, LOW);
}
return -1;
}
return 0;
}
char TMC26XStepper::isMoving() { return this->steps_left > 0; }
uint16_t TMC26XStepper::getStepsLeft() { return this->steps_left; }
char TMC26XStepper::stop() {
//note to self if the motor is currently moving
char state = isMoving();
//stop the motor
this->steps_left = 0;
this->direction = 0;
//return if it was moving
return state;
}
void TMC26XStepper::setCurrent(uint16_t current) {
uint8_t current_scaling = 0;
//calculate the current scaling from the max current setting (in mA)
float mASetting = (float)current,
resistor_value = (float)this->resistor;
// remove vsense flag
this->driver_configuration_register_value &= ~(VSENSE);
// Derived from I = (cs + 1) / 32 * (Vsense / Rsense)
// leading to cs = 32 * R * I / V (with V = 0,31V oder 0,165V and I = 1000 * current)
// with Rsense = 0,15
// for vsense = 0,310V (VSENSE not set)
// or vsense = 0,165V (VSENSE set)
current_scaling = (byte)((resistor_value * mASetting * 32.0 / (0.31 * sq(1000.0))) - 0.5); //theoretically - 1.0 for better rounding it is 0.5
// Check if the current scalingis too low
if (current_scaling < 16) {
// Set the csense bit to get a use half the sense voltage (to support lower motor currents)
this->driver_configuration_register_value |= VSENSE;
// and recalculate the current setting
current_scaling = (byte)((resistor_value * mASetting * 32.0 / (0.165 * sq(1000.0))) - 0.5); //theoretically - 1.0 for better rounding it is 0.5
#ifdef TMC_DEBUG0 // crashes
SERIAL_ECHOPAIR("\nCS (Vsense=1): ",current_scaling);
#endif
}
#ifdef TMC_DEBUG0 // crashes
else
SERIAL_ECHOPAIR("\nCS: ", current_scaling);
#endif
// do some sanity checks
NOMORE(current_scaling, 31);
// delete the old value
stallguard2_current_register_value &= ~(CURRENT_SCALING_PATTERN);
// set the new current scaling
stallguard2_current_register_value |= current_scaling;
// if started we directly send it to the motor
if (started) {
send262(driver_configuration_register_value);
send262(stallguard2_current_register_value);
}
}
uint16_t TMC26XStepper::getCurrent() {
// Calculate the current according to the datasheet to be on the safe side.
// This is not the fastest but the most accurate and illustrative way.
float result = (float)(stallguard2_current_register_value & CURRENT_SCALING_PATTERN),
resistor_value = (float)this->resistor,
voltage = (driver_configuration_register_value & VSENSE) ? 0.165 : 0.31;
result = (result + 1.0) / 32.0 * voltage / resistor_value * sq(1000.0);
return (uint16_t)result;
}
void TMC26XStepper::setStallGuardThreshold(char stallguard_threshold, char stallguard_filter_enabled) {
// We just have 5 bits
LIMIT(stallguard_threshold, -64, 63);
// Add trim down to 7 bits
stallguard_threshold &= 0x7F;
// Delete old StallGuard settings
stallguard2_current_register_value &= ~(STALL_GUARD_CONFIG_PATTERN);
if (stallguard_filter_enabled)
stallguard2_current_register_value |= STALL_GUARD_FILTER_ENABLED;
// Set the new StallGuard threshold
stallguard2_current_register_value |= (((uint32_t)stallguard_threshold << 8) & STALL_GUARD_CONFIG_PATTERN);
// If started we directly send it to the motor
if (started) send262(stallguard2_current_register_value);
}
char TMC26XStepper::getStallGuardThreshold() {
uint32_t stallguard_threshold = stallguard2_current_register_value & STALL_GUARD_VALUE_PATTERN;
//shift it down to bit 0
stallguard_threshold >>= 8;
//convert the value to an int16_t to correctly handle the negative numbers
char result = stallguard_threshold;
//check if it is negative and fill it up with leading 1 for proper negative number representation
//rem if (result & _BV(6)) {
if (TEST(result, 6)) result |= 0xC0;
return result;
}
char TMC26XStepper::getStallGuardFilter() {
if (stallguard2_current_register_value & STALL_GUARD_FILTER_ENABLED)
return -1;
return 0;
}
/**
* Set the number of microsteps per step.
* 0,2,4,8,16,32,64,128,256 is supported
* any value in between will be mapped to the next smaller value
* 0 and 1 set the motor in full step mode
*/
void TMC26XStepper::setMicrosteps(const int16_t in_steps) {
uint16_t setting_pattern;
if (in_steps >= 256) setting_pattern = 0;
else if (in_steps >= 128) setting_pattern = 1;
else if (in_steps >= 64) setting_pattern = 2;
else if (in_steps >= 32) setting_pattern = 3;
else if (in_steps >= 16) setting_pattern = 4;
else if (in_steps >= 8) setting_pattern = 5;
else if (in_steps >= 4) setting_pattern = 6;
else if (in_steps >= 2) setting_pattern = 7;
else if (in_steps <= 1) setting_pattern = 8; // 1 and 0 lead to full step
microsteps = _BV(8 - setting_pattern);
#ifdef TMC_DEBUG0 // crashes
SERIAL_ECHOPAIR("\n Microstepping: ", microsteps);
#endif
// Delete the old value
this->driver_control_register_value &= 0x000FFFF0UL;
// Set the new value
this->driver_control_register_value |= setting_pattern;
// If started we directly send it to the motor
if (started) send262(driver_control_register_value);
// Recalculate the stepping delay by simply setting the speed again
this->setSpeed(this->speed);
}
/**
* returns the effective number of microsteps at the moment
*/
int16_t TMC26XStepper::getMicrosteps() { return microsteps; }
/**
* constant_off_time: The off time setting controls the minimum chopper frequency.
* For most applications an off time within the range of 5μs to 20μs will fit.
* 2...15: off time setting
*
* blank_time: Selects the comparator blank time. This time needs to safely cover the switching event and the
* duration of the ringing on the sense resistor. For
* 0: min. setting 3: max. setting
*
* fast_decay_time_setting: Fast decay time setting. With CHM=1, these bits control the portion of fast decay for each chopper cycle.
* 0: slow decay only
* 1...15: duration of fast decay phase
*
* sine_wave_offset: Sine wave offset. With CHM=1, these bits control the sine wave offset.
* A positive offset corrects for zero crossing error.
* -3..-1: negative offset 0: no offset 1...12: positive offset
*
* use_current_comparator: Selects usage of the current comparator for termination of the fast decay cycle.
* If current comparator is enabled, it terminates the fast decay cycle in case the current
* reaches a higher negative value than the actual positive value.
* 1: enable comparator termination of fast decay cycle
* 0: end by time only
*/
void TMC26XStepper::setConstantOffTimeChopper(char constant_off_time, char blank_time, char fast_decay_time_setting, char sine_wave_offset, uint8_t use_current_comparator) {
// Perform some sanity checks
LIMIT(constant_off_time, 2, 15);
// Save the constant off time
this->constant_off_time = constant_off_time;
// Calculate the value acc to the clock cycles
const char blank_value = blank_time >= 54 ? 3 :
blank_time >= 36 ? 2 :
blank_time >= 24 ? 1 : 0;
LIMIT(fast_decay_time_setting, 0, 15);
LIMIT(sine_wave_offset, -3, 12);
// Shift the sine_wave_offset
sine_wave_offset += 3;
// Calculate the register setting
// First of all delete all the values for this
chopper_config_register &= ~(_BV(12) | BLANK_TIMING_PATTERN | HYSTERESIS_DECREMENT_PATTERN | HYSTERESIS_LOW_VALUE_PATTERN | HYSTERESIS_START_VALUE_PATTERN | T_OFF_TIMING_PATERN);
// Set the constant off pattern
chopper_config_register |= CHOPPER_MODE_T_OFF_FAST_DECAY;
// Set the blank timing value
chopper_config_register |= ((uint32_t)blank_value) << BLANK_TIMING_SHIFT;
// Setting the constant off time
chopper_config_register |= constant_off_time;
// Set the fast decay time
// Set msb
chopper_config_register |= (((uint32_t)(fast_decay_time_setting & 0x8)) << HYSTERESIS_DECREMENT_SHIFT);
// Other bits
chopper_config_register |= (((uint32_t)(fast_decay_time_setting & 0x7)) << HYSTERESIS_START_VALUE_SHIFT);
// Set the sine wave offset
chopper_config_register |= (uint32_t)sine_wave_offset << HYSTERESIS_LOW_SHIFT;
// Using the current comparator?
if (!use_current_comparator)
chopper_config_register |= _BV(12);
// If started we directly send it to the motor
if (started) {
// rem send262(driver_control_register_value);
send262(chopper_config_register);
}
}
/**
* constant_off_time: The off time setting controls the minimum chopper frequency.
* For most applications an off time within the range of 5μs to 20μs will fit.
* 2...15: off time setting
*
* blank_time: Selects the comparator blank time. This time needs to safely cover the switching event and the
* duration of the ringing on the sense resistor. For
* 0: min. setting 3: max. setting
*
* hysteresis_start: Hysteresis start setting. Please remark, that this value is an offset to the hysteresis end value HEND.
* 1...8
*
* hysteresis_end: Hysteresis end setting. Sets the hysteresis end value after a number of decrements. Decrement interval time is controlled by HDEC.
* The sum HSTRT+HEND must be <16. At a current setting CS of max. 30 (amplitude reduced to 240), the sum is not limited.
* -3..-1: negative HEND 0: zero HEND 1...12: positive HEND
*
* hysteresis_decrement: Hysteresis decrement setting. This setting determines the slope of the hysteresis during on time and during fast decay time.
* 0: fast decrement 3: very slow decrement
*/
void TMC26XStepper::setSpreadCycleChopper(char constant_off_time, char blank_time, char hysteresis_start, char hysteresis_end, char hysteresis_decrement) {
// Perform some sanity checks
LIMIT(constant_off_time, 2, 15);
// Save the constant off time
this->constant_off_time = constant_off_time;
// Calculate the value acc to the clock cycles
const char blank_value = blank_time >= 54 ? 3 :
blank_time >= 36 ? 2 :
blank_time >= 24 ? 1 : 0;
LIMIT(hysteresis_start, 1, 8);
hysteresis_start--;
LIMIT(hysteresis_start, -3, 12);
// Shift the hysteresis_end
hysteresis_end += 3;
LIMIT(hysteresis_decrement, 0, 3);
//first of all delete all the values for this
chopper_config_register &= ~(CHOPPER_MODE_T_OFF_FAST_DECAY | BLANK_TIMING_PATTERN | HYSTERESIS_DECREMENT_PATTERN | HYSTERESIS_LOW_VALUE_PATTERN | HYSTERESIS_START_VALUE_PATTERN | T_OFF_TIMING_PATERN);
//set the blank timing value
chopper_config_register |= ((uint32_t)blank_value) << BLANK_TIMING_SHIFT;
//setting the constant off time
chopper_config_register |= constant_off_time;
//set the hysteresis_start
chopper_config_register |= ((uint32_t)hysteresis_start) << HYSTERESIS_START_VALUE_SHIFT;
//set the hysteresis end
chopper_config_register |= ((uint32_t)hysteresis_end) << HYSTERESIS_LOW_SHIFT;
//set the hystereis decrement
chopper_config_register |= ((uint32_t)blank_value) << BLANK_TIMING_SHIFT;
//if started we directly send it to the motor
if (started) {
//rem send262(driver_control_register_value);
send262(chopper_config_register);
}
}
/**
* In a constant off time chopper scheme both coil choppers run freely, i.e. are not synchronized.
* The frequency of each chopper mainly depends on the coil current and the position dependant motor coil inductivity, thus it depends on the microstep position.
* With some motors a slightly audible beat can occur between the chopper frequencies, especially when they are near to each other. This typically occurs at a
* few microstep positions within each quarter wave. This effect normally is not audible when compared to mechanical noise generated by ball bearings, etc.
* Further factors which can cause a similar effect are a poor layout of sense resistor GND connection.
* Hint: A common factor, which can cause motor noise, is a bad PCB layout causing coupling of both sense resistor voltages
* (please refer to sense resistor layout hint in chapter 8.1).
* In order to minimize the effect of a beat between both chopper frequencies, an internal random generator is provided.
* It modulates the slow decay time setting when switched on by the RNDTF bit. The RNDTF feature further spreads the chopper spectrum,
* reducing electromagnetic emission on single frequencies.
*/
void TMC26XStepper::setRandomOffTime(char value) {
if (value)
chopper_config_register |= RANDOM_TOFF_TIME;
else
chopper_config_register &= ~(RANDOM_TOFF_TIME);
//if started we directly send it to the motor
if (started) {
//rem send262(driver_control_register_value);
send262(chopper_config_register);
}
}
void TMC26XStepper::setCoolStepConfiguration(
uint16_t lower_SG_threshold,
uint16_t SG_hysteresis,
uint8_t current_decrement_step_size,
uint8_t current_increment_step_size,
uint8_t lower_current_limit
) {
// Sanitize the input values
NOMORE(lower_SG_threshold, 480);
// Divide by 32
lower_SG_threshold >>= 5;
NOMORE(SG_hysteresis, 480);
// Divide by 32
SG_hysteresis >>= 5;
NOMORE(current_decrement_step_size, 3);
NOMORE(current_increment_step_size, 3);
NOMORE(lower_current_limit, 1);
// Store the lower level in order to enable/disable the cool step
this->cool_step_lower_threshold=lower_SG_threshold;
// If cool step is not enabled we delete the lower value to keep it disabled
if (!this->cool_step_enabled) lower_SG_threshold = 0;
// The good news is that we can start with a complete new cool step register value
// And simply set the values in the register
cool_step_register_value = ((uint32_t)lower_SG_threshold)
| (((uint32_t)SG_hysteresis) << 8)
| (((uint32_t)current_decrement_step_size) << 5)
| (((uint32_t)current_increment_step_size) << 13)
| (((uint32_t)lower_current_limit) << 15)
| COOL_STEP_REGISTER; // Register signature
if (started) send262(cool_step_register_value);
}
void TMC26XStepper::setCoolStepEnabled(boolean enabled) {
// Simply delete the lower limit to disable the cool step
cool_step_register_value &= ~SE_MIN_PATTERN;
// And set it to the proper value if cool step is to be enabled
if (enabled)
cool_step_register_value |= this->cool_step_lower_threshold;
// And save the enabled status
this->cool_step_enabled = enabled;
// Save the register value
if (started) send262(cool_step_register_value);
}
boolean TMC26XStepper::isCoolStepEnabled() { return this->cool_step_enabled; }
uint16_t TMC26XStepper::getCoolStepLowerSgThreshold() {
// We return our internally stored value - in order to provide the correct setting even if cool step is not enabled
return this->cool_step_lower_threshold<<5;
}
uint16_t TMC26XStepper::getCoolStepUpperSgThreshold() {
return uint8_t((cool_step_register_value & SE_MAX_PATTERN) >> 8) << 5;
}
uint8_t TMC26XStepper::getCoolStepCurrentIncrementSize() {
return uint8_t((cool_step_register_value & CURRENT_DOWN_STEP_SPEED_PATTERN) >> 13);
}
uint8_t TMC26XStepper::getCoolStepNumberOfSGReadings() {
return uint8_t((cool_step_register_value & SE_CURRENT_STEP_WIDTH_PATTERN) >> 5);
}
uint8_t TMC26XStepper::getCoolStepLowerCurrentLimit() {
return uint8_t((cool_step_register_value & MINIMUM_CURRENT_FOURTH) >> 15);
}
void TMC26XStepper::setEnabled(boolean enabled) {
//delete the t_off in the chopper config to get sure
chopper_config_register &= ~(T_OFF_PATTERN);
if (enabled) {
//and set the t_off time
chopper_config_register |= this->constant_off_time;
}
//if not enabled we don't have to do anything since we already delete t_off from the register
if (started) send262(chopper_config_register);
}
boolean TMC26XStepper::isEnabled() { return !!(chopper_config_register & T_OFF_PATTERN); }
/**
* reads a value from the TMC26X status register. The value is not obtained directly but can then
* be read by the various status routines.
*/
void TMC26XStepper::readStatus(char read_value) {
uint32_t old_driver_configuration_register_value = driver_configuration_register_value;
//reset the readout configuration
driver_configuration_register_value &= ~(READ_SELECTION_PATTERN);
//this now equals TMC26X_READOUT_POSITION - so we just have to check the other two options
if (read_value == TMC26X_READOUT_STALLGUARD)
driver_configuration_register_value |= READ_STALL_GUARD_READING;
else if (read_value == TMC26X_READOUT_CURRENT)
driver_configuration_register_value |= READ_STALL_GUARD_AND_COOL_STEP;
//all other cases are ignored to prevent funny values
//check if the readout is configured for the value we are interested in
if (driver_configuration_register_value != old_driver_configuration_register_value) {
//because then we need to write the value twice - one time for configuring, second time to get the value, see below
send262(driver_configuration_register_value);
}
//write the configuration to get the last status
send262(driver_configuration_register_value);
}
int16_t TMC26XStepper::getMotorPosition() {
//we read it out even if we are not started yet - perhaps it is useful information for somebody
readStatus(TMC26X_READOUT_POSITION);
return getReadoutValue();
}
//reads the StallGuard setting from last status
//returns -1 if StallGuard information is not present
int16_t TMC26XStepper::getCurrentStallGuardReading() {
//if we don't yet started there cannot be a StallGuard value
if (!started) return -1;
//not time optimal, but solution optiomal:
//first read out the StallGuard value
readStatus(TMC26X_READOUT_STALLGUARD);
return getReadoutValue();
}
uint8_t TMC26XStepper::getCurrentCSReading() {
//if we don't yet started there cannot be a StallGuard value
if (!started) return 0;
//not time optimal, but solution optiomal:
//first read out the StallGuard value
readStatus(TMC26X_READOUT_CURRENT);
return (getReadoutValue() & 0x1F);
}
uint16_t TMC26XStepper::getCurrentCurrent() {
float result = (float)getCurrentCSReading(),
resistor_value = (float)this->resistor,
voltage = (driver_configuration_register_value & VSENSE)? 0.165 : 0.31;
result = (result + 1.0) / 32.0 * voltage / resistor_value * sq(1000.0);
return (uint16_t)result;
}
/**
* Return true if the StallGuard threshold has been reached
*/
boolean TMC26XStepper::isStallGuardOverThreshold() {
if (!this->started) return false;
return (driver_status_result & STATUS_STALL_GUARD_STATUS);
}
/**
* returns if there is any over temperature condition:
* OVER_TEMPERATURE_PREWARING if pre warning level has been reached
* OVER_TEMPERATURE_SHUTDOWN if the temperature is so hot that the driver is shut down
* Any of those levels are not too good.
*/
char TMC26XStepper::getOverTemperature() {
if (!this->started) return 0;
if (driver_status_result & STATUS_OVER_TEMPERATURE_SHUTDOWN)
return TMC26X_OVERTEMPERATURE_SHUTDOWN;
if (driver_status_result & STATUS_OVER_TEMPERATURE_WARNING)
return TMC26X_OVERTEMPERATURE_PREWARING;
return 0;
}
// Is motor channel A shorted to ground
boolean TMC26XStepper::isShortToGroundA() {
if (!this->started) return false;
return (driver_status_result & STATUS_SHORT_TO_GROUND_A);
}
// Is motor channel B shorted to ground
boolean TMC26XStepper::isShortToGroundB() {
if (!this->started) return false;
return (driver_status_result & STATUS_SHORT_TO_GROUND_B);
}
// Is motor channel A connected
boolean TMC26XStepper::isOpenLoadA() {
if (!this->started) return false;
return (driver_status_result & STATUS_OPEN_LOAD_A);
}
// Is motor channel B connected
boolean TMC26XStepper::isOpenLoadB() {
if (!this->started) return false;
return (driver_status_result & STATUS_OPEN_LOAD_B);
}
// Is chopper inactive since 2^20 clock cycles - defaults to ~0,08s
boolean TMC26XStepper::isStandStill() {
if (!this->started) return false;
return (driver_status_result & STATUS_STAND_STILL);
}
//is chopper inactive since 2^20 clock cycles - defaults to ~0,08s
boolean TMC26XStepper::isStallGuardReached() {
if (!this->started) return false;
return (driver_status_result & STATUS_STALL_GUARD_STATUS);
}
//reads the StallGuard setting from last status
//returns -1 if StallGuard information is not present
int16_t TMC26XStepper::getReadoutValue() {
return (int)(driver_status_result >> 10);
}
int16_t TMC26XStepper::getResistor() { return this->resistor; }
boolean TMC26XStepper::isCurrentScalingHalfed() {
return !!(this->driver_configuration_register_value & VSENSE);
}
/**
* version() returns the version of the library:
*/
int16_t TMC26XStepper::version() { return 1; }
void TMC26XStepper::debugLastStatus() {
#ifdef TMC_DEBUG1
if (this->started) {
if (this->getOverTemperature()&TMC26X_OVERTEMPERATURE_PREWARING)
SERIAL_ECHOLNPGM("\n WARNING: Overtemperature Prewarning!");
else if (this->getOverTemperature()&TMC26X_OVERTEMPERATURE_SHUTDOWN)
SERIAL_ECHOLNPGM("\n ERROR: Overtemperature Shutdown!");
if (this->isShortToGroundA())
SERIAL_ECHOLNPGM("\n ERROR: SHORT to ground on channel A!");
if (this->isShortToGroundB())
SERIAL_ECHOLNPGM("\n ERROR: SHORT to ground on channel B!");
if (this->isOpenLoadA())
SERIAL_ECHOLNPGM("\n ERROR: Channel A seems to be unconnected!");
if (this->isOpenLoadB())
SERIAL_ECHOLNPGM("\n ERROR: Channel B seems to be unconnected!");
if (this->isStallGuardReached())
SERIAL_ECHOLNPGM("\n INFO: Stall Guard level reached!");
if (this->isStandStill())
SERIAL_ECHOLNPGM("\n INFO: Motor is standing still.");
uint32_t readout_config = driver_configuration_register_value & READ_SELECTION_PATTERN;
const int16_t value = getReadoutValue();
if (readout_config == READ_MICROSTEP_POSTION) {
SERIAL_ECHOPAIR("\n Microstep position phase A: ", value);
}
else if (readout_config == READ_STALL_GUARD_READING) {
SERIAL_ECHOPAIR("\n Stall Guard value:", value);
}
else if (readout_config == READ_STALL_GUARD_AND_COOL_STEP) {
SERIAL_ECHOPAIR("\n Approx Stall Guard: ", value & 0xF);
SERIAL_ECHOPAIR("\n Current level", value & 0x1F0);
}
}
#endif
}
/**
* send register settings to the stepper driver via SPI
* returns the current status
*/
inline void TMC26XStepper::send262(uint32_t datagram) {
uint32_t i_datagram;
//preserver the previous spi mode
//uint8_t oldMode = SPCR & SPI_MODE_MASK;
//if the mode is not correct set it to mode 3
//if (oldMode != SPI_MODE3) {
// SPI.setDataMode(SPI_MODE3);
//}
//select the TMC driver
extDigitalWrite(cs_pin, LOW);
//ensure that only valid bist are set (0-19)
//datagram &=REGISTER_BIT_PATTERN;
#ifdef TMC_DEBUG1
//SERIAL_PRINTF("Sending ");
//SERIAL_PRINTF("Sending ", datagram,HEX);
//SERIAL_ECHOPAIR("\n\nSending \n", print_hex_long(datagram));
SERIAL_PRINTF("\n\nSending %x", datagram);
#endif
//write/read the values
i_datagram = STEPPER_SPI.transfer((datagram >> 16) & 0xFF);
i_datagram <<= 8;
i_datagram |= STEPPER_SPI.transfer((datagram >> 8) & 0xFF);
i_datagram <<= 8;
i_datagram |= STEPPER_SPI.transfer((datagram) & 0xFF);
i_datagram >>= 4;
#ifdef TMC_DEBUG1
//SERIAL_PRINTF("Received ");
//SERIAL_PRINTF("Received ", i_datagram,HEX);
//SERIAL_ECHOPAIR("\n\nReceived \n", i_datagram);
SERIAL_PRINTF("\n\nReceived %x", i_datagram);
debugLastStatus();
#endif
//deselect the TMC chip
extDigitalWrite(cs_pin, HIGH);
//restore the previous SPI mode if neccessary
//if the mode is not correct set it to mode 3
//if (oldMode != SPI_MODE3) {
// SPI.setDataMode(oldMode);
//}
//store the datagram as status result
driver_status_result = i_datagram;
}
#endif // HAS_DRIVER(TMC2660)
#endif // STM32GENERIC && STM32F7

593
Marlin/src/HAL/STM32_F4_F7/STM32F7/TMC2660.h

@ -1,593 +0,0 @@
/**
* TMC26XStepper.h - - TMC26X Stepper library for Wiring/Arduino
*
* based on the stepper library by Tom Igoe, et. al.
*
* Copyright (c) 2011, Interactive Matter, Marcus Nowotny
*
* Permission is hereby granted, free of charge, to any person obtaining a copy
* of this software and associated documentation files (the "Software"), to deal
* in the Software without restriction, including without limitation the rights
* to use, copy, modify, merge, publish, distribute, sublicense, and/or sell
* copies of the Software, and to permit persons to whom the Software is
* furnished to do so, subject to the following conditions:
*
* The above copyright notice and this permission notice shall be included in
* all copies or substantial portions of the Software.
*
* THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
* IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
* FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
* AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
* LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM,
* OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN
* THE SOFTWARE.
*/
#pragma once
#include <stdint.h>
//! return value for TMC26XStepper.getOverTemperature() if there is a overtemperature situation in the TMC chip
/*!
* This warning indicates that the TMC chip is too warm.
* It is still working but some parameters may be inferior.
* You should do something against it.
*/
#define TMC26X_OVERTEMPERATURE_PREWARING 1
//! return value for TMC26XStepper.getOverTemperature() if there is a overtemperature shutdown in the TMC chip
/*!
* This warning indicates that the TMC chip is too warm to operate and has shut down to prevent damage.
* It will stop working until it cools down again.
* If you encouter this situation you must do something against it. Like reducing the current or improving the PCB layout
* and/or heat management.
*/
#define TMC26X_OVERTEMPERATURE_SHUTDOWN 2
//which values can be read out
/*!
* Selects to readout the microstep position from the motor.
*\sa readStatus()
*/
#define TMC26X_READOUT_POSITION 0
/*!
* Selects to read out the StallGuard value of the motor.
*\sa readStatus()
*/
#define TMC26X_READOUT_STALLGUARD 1
/*!
* Selects to read out the current current setting (acc. to CoolStep) and the upper bits of the StallGuard value from the motor.
*\sa readStatus(), setCurrent()
*/
#define TMC26X_READOUT_CURRENT 3
/*!
* Define to set the minimum current for CoolStep operation to 1/2 of the selected CS minium.
*\sa setCoolStepConfiguration()
*/
#define COOL_STEP_HALF_CS_LIMIT 0
/*!
* Define to set the minimum current for CoolStep operation to 1/4 of the selected CS minium.
*\sa setCoolStepConfiguration()
*/
#define COOL_STEP_QUARTDER_CS_LIMIT 1
/*!
* \class TMC26XStepper
* \brief Class representing a TMC26X stepper driver
*
* To use one of these drivers in your code create an object of its class:
* \code
* TMC26XStepper tmc_stepper = TMC26XStepper(200,1,2,3,500);
* \endcode
* see TMC26XStepper(int16_t number_of_steps, int16_t cs_pin, int16_t dir_pin, int16_t step_pin, uint16_t rms_current)
*
* Keep in mind that you need to start the driver with start() in order to configure the TMC26X.
*
* The most important function is move(). It checks if the motor requires a step. It's important to call move() as
* often as possible in loop(). I suggest using a very fast loop routine and always call move() at the beginning or end.
*
* To move you must set a movement speed with setSpeed(). The speed is a positive value, setting the RPM.
*
* To really move the motor you have to call step() to tell the driver to move the motor the given number
* of steps in the given direction. Positive values move the motor in one direction, negative values in the other.
*
* You can check with isMoving() if the motor is still moving or stop it abruptly with stop().
*/
class TMC26XStepper {
public:
/*!
* \brief Create a new representation of a stepper motor connected to a TMC26X stepper driver
*
* Main constructor. If in doubt use this. All parameters must be provided as described below.
*
* \param number_of_steps Number of steps the motor has per rotation.
* \param cs_pin Arduino pin connected to the Client Select Pin (!CS) of the TMC26X for SPI.
* \param dir_pin Arduino pin connected to the DIR input of the TMC26X.
* \param step_pin Arduino pin connected to the STEP pin of the TMC26X.
* \param rms_current Maximum current to provide to the motor in mA (!). A value of 200 will send up to 200mA to the motor.
* \param resistor Current sense resistor in milli-Ohm, defaults to 0.15 Ohm (or 150 milli-Ohm) as in the TMC260 Arduino Shield.
*
* You must also call TMC26XStepper.start() to configure the stepper driver for use.
*
* By default the Constant Off Time chopper is used. See TMC26XStepper.setConstantOffTimeChopper() for details.
* This should work on most motors (YMMV). You may want to configure and use the Spread Cycle Chopper. See setSpreadCycleChopper().
*
* By default a microstepping of 1/32 is used to provide a smooth motor run while still giving a good progression per step.
* Change stepping by sending setMicrosteps() a different value.
* \sa start(), setMicrosteps()
*/
TMC26XStepper(const int16_t in_steps, int16_t cs_pin, int16_t dir_pin, int16_t step_pin, uint16_t current, uint16_t resistor=100); //resistor=150
/*!
* \brief Configure and start the TMC26X stepper driver. Before this is called the stepper driver is nonfunctional.
*
* Configure the TMC26X stepper driver for the given values via SPI.
* Most member functions are non-functional if the driver has not been started,
* therefore it is best to call this in setup().
*/
void start();
/*!
* \brief Reset the stepper in unconfigured mode.
*
* Allows start to be called again. It doesn't change the internal stepper
* configuration or the desired configuration. It just marks the stepper as
* not-yet-started. The stepper doesn't need to be reconfigured before
* starting again, and is not reset to any factory settings.
* It must be reset intentionally.
* (Hint: Normally you do not need this function)
*/
void un_start();
/*!
* \brief Set the rotation speed in RPM.
* \param whatSpeed the desired speed in RPM.
*/
void setSpeed(uint16_t whatSpeed);
/*!
* \brief Report the currently selected speed in RPM.
* \sa setSpeed()
*/
uint16_t getSpeed();
/*!
* \brief Set the number of microsteps in 2^i values (rounded) up to 256
*
* This method sets the number of microsteps per step in 2^i interval.
* It accepts 1, 2, 4, 16, 32, 64, 128 or 256 as valid microsteps.
* Other values will be rounded down to the next smaller value (e.g., 3 gives a microstepping of 2).
* You can always check the current microstepping with getMicrosteps().
*/
void setMicrosteps(const int16_t in_steps);
/*!
* \brief Return the effective current number of microsteps selected.
*
* Always returns the effective number of microsteps.
* This may be different from the micro-steps set in setMicrosteps() since it is rounded to 2^i.
*
* \sa setMicrosteps()
*/
int16_t getMicrosteps();
/*!
* \brief Initiate a movement with the given number of steps. Positive values move in one direction, negative in the other.
*
* \param number_of_steps The number of steps to move the motor.
* \return 0 if the motor was not moving and moves now. -1 if the motor is moving and the new steps could not be set.
*
* If the previous movement is incomplete the function returns -1 and doesn't change the steps to move the motor.
* If the motor does not move it returns 0.
*
* The movement direction is determined by the sign of the steps parameter. The motor direction in machine space
* cannot be determined, as it depends on the construction of the motor and how it functions in the drive system.
*
* For safety, verify with isMoving() or even use stop() to stop the motor before giving it new step directions.
* \sa isMoving(), getStepsLeft(), stop()
*/
char step(int16_t number_of_steps);
/*!
* \brief Central movement method. Must be called as often as possible in the loop function and is very fast.
*
* Check if the motor still has to move and whether the wait-to-step interval has expired, and manages the
* number of steps remaining to fulfill the current move command.
*
* This function is implemented to be as fast as possible, so call it as often as possible in your loop.
* It should be invoked with as frequently and with as much regularity as possible.
*
* This can be called even when the motor is known not to be moving. It will simply return.
*
* The frequency with which this function is called determines the top stepping speed of the motor.
* It is recommended to call this using a hardware timer to ensure regular invocation.
* \sa step()
*/
char move();
/*!
* \brief Check whether the last movement command is done.
* \return 0 if the motor stops, -1 if the motor is moving.
*
* Used to determine if the motor is ready for new movements.
*\sa step(), move()
*/
char isMoving();
/*!
* \brief Get the number of steps left in the current movement.
* \return The number of steps left in the movement. Always positive.
*/
uint16_t getStepsLeft();
/*!
* \brief Stop the motor immediately.
* \return -1 if the motor was moving and is really stoped or 0 if it was not moving at all.
*
* This method directly and abruptly stops the motor and may be used as an emergency stop.
*/
char stop();
/*!
* \brief Set and configure the classical Constant Off Timer Chopper
* \param constant_off_time The off time setting controls the minimum chopper frequency. For most applications an off time within the range of 5μs to 20μs will fit. Setting this parameter to zero completely disables all driver transistors and the motor can free-wheel. 0: chopper off, 1:15: off time setting (1 will work with minimum blank time of 24 clocks)
* \param blank_time Comparator blank time. This duration needs to safely cover the duration of the switching event and the ringing on the sense resistor. For most low current drivers, a setting of 1 or 2 is good. For high current applications with large MOSFETs, a setting of 2 or 3 will be required. 0 (min setting) (3) amx setting
* \param fast_decay_time_setting Fast decay time setting. Controls the portion of fast decay for each chopper cycle. 0: slow decay only, 115: duration of fast decay phase
* \param sine_wave_offset Sine wave offset. Controls the sine wave offset. A positive offset corrects for zero crossing error. -3-1: negative offset, 0: no offset,112: positive offset
* \param use_curreent_comparator Selects usage of the current comparator for termination of the fast decay cycle. If current comparator is enabled, it terminates the fast decay cycle in case the current reaches a higher negative value than the actual positive value. (0 disable, -1 enable).
*
* The classic constant off time chopper uses a fixed portion of fast decay following each on phase.
* While the duration of the on time is determined by the chopper comparator, the fast decay time needs
* to be set by the user in a way, that the current decay is enough for the driver to be able to follow
* the falling slope of the sine wave, and on the other hand it should not be too long, in order to minimize
* motor current ripple and power dissipation. This best can be tuned using an oscilloscope or
* trying out motor smoothness at different velocities. A good starting value is a fast decay time setting
* similar to the slow decay time setting.
* After tuning of the fast decay time, the offset should be determined, in order to have a smooth zero transition.
* This is necessary, because the fast decay phase leads to the absolute value of the motor current being lower
* than the target current (see figure 17). If the zero offset is too low, the motor stands still for a short
* moment during current zero crossing, if it is set too high, it makes a larger microstep.
* Typically, a positive offset setting is required for optimum operation.
*
* \sa setSpreadCycleChoper() for other alternatives.
* \sa setRandomOffTime() for spreading the noise over a wider spectrum
*/
void setConstantOffTimeChopper(char constant_off_time, char blank_time, char fast_decay_time_setting, char sine_wave_offset, uint8_t use_current_comparator);
/*!
* \brief Sets and configures with spread cycle chopper.
* \param constant_off_time The off time setting controls the minimum chopper frequency. For most applications an off time within the range of 5μs to 20μs will fit. Setting this parameter to zero completely disables all driver transistors and the motor can free-wheel. 0: chopper off, 1:15: off time setting (1 will work with minimum blank time of 24 clocks)
* \param blank_time Selects the comparator blank time. This time needs to safely cover the switching event and the duration of the ringing on the sense resistor. For most low current drivers, a setting of 1 or 2 is good. For high current applications with large MOSFETs, a setting of 2 or 3 will be required. 0 (min setting) (3) amx setting
* \param hysteresis_start Hysteresis start setting. Please remark, that this value is an offset to the hysteresis end value. 1 8
* \param hysteresis_end Hysteresis end setting. Sets the hysteresis end value after a number of decrements. Decrement interval time is controlled by hysteresis_decrement. The sum hysteresis_start + hysteresis_end must be <16. At a current setting CS of max. 30 (amplitude reduced to 240), the sum is not limited.
* \param hysteresis_decrement Hysteresis decrement setting. This setting determines the slope of the hysteresis during on time and during fast decay time. 0 (fast decrement) 3 (slow decrement).
*
* The spreadCycle chopper scheme (pat.fil.) is a precise and simple to use chopper principle, which automatically determines
* the optimum fast decay portion for the motor. Anyhow, a number of settings can be made in order to optimally fit the driver
* to the motor.
* Each chopper cycle is comprised of an on-phase, a slow decay phase, a fast decay phase and a second slow decay phase.
* The slow decay phases limit the maximum chopper frequency and are important for low motor and driver power dissipation.
* The hysteresis start setting limits the chopper frequency by forcing the driver to introduce a minimum amount of
* current ripple into the motor coils. The motor inductivity determines the ability to follow a changing motor current.
* The duration of the on- and fast decay phase needs to cover at least the blank time, because the current comparator is
* disabled during this time.
*
* \sa setRandomOffTime() for spreading the noise over a wider spectrum
*/
void setSpreadCycleChopper(char constant_off_time, char blank_time, char hysteresis_start, char hysteresis_end, char hysteresis_decrement);
/*!
* \brief Use random off time for noise reduction (0 for off, -1 for on).
* \param value 0 for off, -1 for on
*
* In a constant off time chopper scheme both coil choppers run freely, i.e. are not synchronized.
* The frequency of each chopper mainly depends on the coil current and the position dependant motor coil inductivity,
* thus it depends on the microstep position. With some motors a slightly audible beat can occur between the chopper
* frequencies, especially when they are near to each other. This typically occurs at a few microstep positions within
* each quarter wave.
* This effect normally is not audible when compared to mechanical noise generated by ball bearings,
* etc. Further factors which can cause a similar effect are a poor layout of sense resistor GND connection.
* In order to minimize the effect of a beat between both chopper frequencies, an internal random generator is provided.
* It modulates the slow decay time setting when switched on. The random off time feature further spreads the chopper spectrum,
* reducing electromagnetic emission on single frequencies.
*/
void setRandomOffTime(char value);
/*!
* \brief set the maximum motor current in mA (1000 is 1 Amp)
* Keep in mind this is the maximum peak Current. The RMS current will be 1/sqrt(2) smaller. The actual current can also be smaller
* by employing CoolStep.
* \param current the maximum motor current in mA
* \sa getCurrent(), getCurrentCurrent()
*/
void setCurrent(uint16_t current);
/*!
* \brief readout the motor maximum current in mA (1000 is an Amp)
* This is the maximum current. to get the current current - which may be affected by CoolStep us getCurrentCurrent()
* \return the maximum motor current in milli amps
* \sa getCurrentCurrent()
*/
uint16_t getCurrent();
/*!
* \brief set the StallGuard threshold in order to get sensible StallGuard readings.
* \param stallguard_threshold -64 63 the StallGuard threshold
* \param stallguard_filter_enabled 0 if the filter is disabled, -1 if it is enabled
*
* The StallGuard threshold is used to optimize the StallGuard reading to sensible values. It should be at 0 at
* the maximum allowable load on the otor (but not before). = is a good starting point (and the default)
* If you get Stall Gaurd readings of 0 without any load or with too little laod increase the value.
* If you get readings of 1023 even with load decrease the setting.
*
* If you switch on the filter the StallGuard reading is only updated each 4th full step to reduce the noise in the
* reading.
*
* \sa getCurrentStallGuardReading() to read out the current value.
*/
void setStallGuardThreshold(char stallguard_threshold, char stallguard_filter_enabled);
/*!
* \brief reads out the StallGuard threshold
* \return a number between -64 and 63.
*/
char getStallGuardThreshold();
/*!
* \brief returns the current setting of the StallGuard filter
* \return 0 if not set, -1 if set
*/
char getStallGuardFilter();
/*!
* \brief This method configures the CoolStep smart energy operation. You must have a proper StallGuard configuration for the motor situation (current, voltage, speed) in rder to use this feature.
* \param lower_SG_threshold Sets the lower threshold for stallGuard2TM reading. Below this value, the motor current becomes increased. Allowed values are 0...480
* \param SG_hysteresis Sets the distance between the lower and the upper threshold for stallGuard2TM reading. Above the upper threshold (which is lower_SG_threshold+SG_hysteresis+1) the motor current becomes decreased. Allowed values are 0...480
* \param current_decrement_step_size Sets the current decrement steps. If the StallGuard value is above the threshold the current gets decremented by this step size. 0...32
* \param current_increment_step_size Sets the current increment step. The current becomes incremented for each measured stallGuard2TM value below the lower threshold. 0...8
* \param lower_current_limit Sets the lower motor current limit for coolStepTM operation by scaling the CS value. Values can be COOL_STEP_HALF_CS_LIMIT, COOL_STEP_QUARTER_CS_LIMIT
* The CoolStep smart energy operation automatically adjust the current sent into the motor according to the current load,
* read out by the StallGuard in order to provide the optimum torque with the minimal current consumption.
* You configure the CoolStep current regulator by defining upper and lower bounds of StallGuard readouts. If the readout is above the
* limit the current gets increased, below the limit the current gets decreased.
* You can specify the upper an lower threshold of the StallGuard readout in order to adjust the current. You can also set the number of
* StallGuard readings neccessary above or below the limit to get a more stable current adjustement.
* The current adjustement itself is configured by the number of steps the current gests in- or decreased and the absolut minimum current
* (1/2 or 1/4th otf the configured current).
* \sa COOL_STEP_HALF_CS_LIMIT, COOL_STEP_QUARTER_CS_LIMIT
*/
void setCoolStepConfiguration(uint16_t lower_SG_threshold, uint16_t SG_hysteresis, uint8_t current_decrement_step_size,
uint8_t current_increment_step_size, uint8_t lower_current_limit);
/*!
* \brief enables or disables the CoolStep smart energy operation feature. It must be configured before enabling it.
* \param enabled true if CoolStep should be enabled, false if not.
* \sa setCoolStepConfiguration()
*/
void setCoolStepEnabled(boolean enabled);
/*!
* \brief check if the CoolStep feature is enabled
* \sa setCoolStepEnabled()
*/
boolean isCoolStepEnabled();
/*!
* \brief returns the lower StallGuard threshold for the CoolStep operation
* \sa setCoolStepConfiguration()
*/
uint16_t getCoolStepLowerSgThreshold();
/*!
* \brief returns the upper StallGuard threshold for the CoolStep operation
* \sa setCoolStepConfiguration()
*/
uint16_t getCoolStepUpperSgThreshold();
/*!
* \brief returns the number of StallGuard readings befor CoolStep adjusts the motor current.
* \sa setCoolStepConfiguration()
*/
uint8_t getCoolStepNumberOfSGReadings();
/*!
* \brief returns the increment steps for the current for the CoolStep operation
* \sa setCoolStepConfiguration()
*/
uint8_t getCoolStepCurrentIncrementSize();
/*!
* \brief returns the absolut minium current for the CoolStep operation
* \sa setCoolStepConfiguration()
* \sa COOL_STEP_HALF_CS_LIMIT, COOL_STEP_QUARTER_CS_LIMIT
*/
uint8_t getCoolStepLowerCurrentLimit();
/*!
* \brief Get the current microstep position for phase A
* \return The current microstep position for phase A 0255
*
* Keep in mind that this routine reads and writes a value via SPI - so this may take a bit time.
*/
int16_t getMotorPosition();
/*!
* \brief Reads the current StallGuard value.
* \return The current StallGuard value, lesser values indicate higher load, 0 means stall detected.
* Keep in mind that this routine reads and writes a value via SPI - so this may take a bit time.
* \sa setStallGuardThreshold() for tuning the readout to sensible ranges.
*/
int16_t getCurrentStallGuardReading();
/*!
* \brief Reads the current current setting value as fraction of the maximum current
* Returns values between 0 and 31, representing 1/32 to 32/32 (=1)
* \sa setCoolStepConfiguration()
*/
uint8_t getCurrentCSReading();
/*!
*\brief a convenience method to determine if the current scaling uses 0.31V or 0.165V as reference.
*\return false if 0.13V is the reference voltage, true if 0.165V is used.
*/
boolean isCurrentScalingHalfed();
/*!
* \brief Reads the current current setting value and recalculates the absolute current in mA (1A would be 1000).
* This method calculates the currently used current setting (either by setting or by CoolStep) and reconstructs
* the current in mA by usinge the VSENSE and resistor value. This method uses floating point math - so it
* may not be the fastest.
* \sa getCurrentCSReading(), getResistor(), isCurrentScalingHalfed(), getCurrent()
*/
uint16_t getCurrentCurrent();
/*!
* \brief checks if there is a StallGuard warning in the last status
* \return 0 if there was no warning, -1 if there was some warning.
* Keep in mind that this method does not enforce a readout but uses the value of the last status readout.
* You may want to use getMotorPosition() or getCurrentStallGuardReading() to enforce an updated status readout.
*
* \sa setStallGuardThreshold() for tuning the readout to sensible ranges.
*/
boolean isStallGuardOverThreshold();
/*!
* \brief Return over temperature status of the last status readout
* return 0 is everything is OK, TMC26X_OVERTEMPERATURE_PREWARING if status is reached, TMC26X_OVERTEMPERATURE_SHUTDOWN is the chip is shutdown, -1 if the status is unknown.
* Keep in mind that this method does not enforce a readout but uses the value of the last status readout.
* You may want to use getMotorPosition() or getCurrentStallGuardReading() to enforce an updated status readout.
*/
char getOverTemperature();
/*!
* \brief Is motor channel A shorted to ground detected in the last status readout.
* \return true is yes, false if not.
* Keep in mind that this method does not enforce a readout but uses the value of the last status readout.
* You may want to use getMotorPosition() or getCurrentStallGuardReading() to enforce an updated status readout.
*/
boolean isShortToGroundA();
/*!
* \brief Is motor channel B shorted to ground detected in the last status readout.
* \return true is yes, false if not.
* Keep in mind that this method does not enforce a readout but uses the value of the last status readout.
* You may want to use getMotorPosition() or getCurrentStallGuardReading() to enforce an updated status readout.
*/
boolean isShortToGroundB();
/*!
* \brief iIs motor channel A connected according to the last statu readout.
* \return true is yes, false if not.
* Keep in mind that this method does not enforce a readout but uses the value of the last status readout.
* You may want to use getMotorPosition() or getCurrentStallGuardReading() to enforce an updated status readout.
*/
boolean isOpenLoadA();
/*!
* \brief iIs motor channel A connected according to the last statu readout.
* \return true is yes, false if not.
* Keep in mind that this method does not enforce a readout but uses the value of the last status readout.
* You may want to use getMotorPosition() or getCurrentStallGuardReading() to enforce an updated status readout.
*/
boolean isOpenLoadB();
/*!
* \brief Is chopper inactive since 2^20 clock cycles - defaults to ~0,08s
* \return true is yes, false if not.
* Keep in mind that this method does not enforce a readout but uses the value of the last status readout.
* You may want to use getMotorPosition() or getCurrentStallGuardReading() to enforce an updated status readout.
*/
boolean isStandStill();
/*!
* \brief checks if there is a StallGuard warning in the last status
* \return 0 if there was no warning, -1 if there was some warning.
* Keep in mind that this method does not enforce a readout but uses the value of the last status readout.
* You may want to use getMotorPosition() or getCurrentStallGuardReading() to enforce an updated status readout.
*
* \sa isStallGuardOverThreshold()
* TODO why?
*
* \sa setStallGuardThreshold() for tuning the readout to sensible ranges.
*/
boolean isStallGuardReached();
/*!
*\brief enables or disables the motor driver bridges. If disabled the motor can run freely. If enabled not.
*\param enabled a boolean value true if the motor should be enabled, false otherwise.
*/
void setEnabled(boolean enabled);
/*!
*\brief checks if the output bridges are enabled. If the bridges are not enabled the motor can run freely
*\return true if the bridges and by that the motor driver are enabled, false if not.
*\sa setEnabled()
*/
boolean isEnabled();
/*!
* \brief Manually read out the status register
* This function sends a byte to the motor driver in order to get the current readout. The parameter read_value
* seletcs which value will get returned. If the read_vlaue changes in respect to the previous readout this method
* automatically send two bytes to the motor: one to set the redout and one to get the actual readout. So this method
* may take time to send and read one or two bits - depending on the previous readout.
* \param read_value selects which value to read out (0..3). You can use the defines TMC26X_READOUT_POSITION, TMC_262_READOUT_STALLGUARD, or TMC_262_READOUT_CURRENT
* \sa TMC26X_READOUT_POSITION, TMC_262_READOUT_STALLGUARD, TMC_262_READOUT_CURRENT
*/
void readStatus(char read_value);
/*!
* \brief Returns the current sense resistor value in milliohm.
* The default value of ,15 Ohm will return 150.
*/
int16_t getResistor();
/*!
* \brief Prints out all the information that can be found in the last status read out - it does not force a status readout.
* The result is printed via Serial
*/
void debugLastStatus();
/*!
* \brief library version
* \return the version number as int.
*/
int16_t version();
private:
uint16_t steps_left; // The steps the motor has to do to complete the movement
int16_t direction; // Direction of rotation
uint32_t step_delay; // Delay between steps, in ms, based on speed
int16_t number_of_steps; // Total number of steps this motor can take
uint16_t speed; // Store the current speed in order to change the speed after changing microstepping
uint16_t resistor; // Current sense resitor value in milliohm
uint32_t last_step_time, // Timestamp (ms) of the last step
next_step_time; // Timestamp (ms) of the next step
// Driver control register copies to easily set & modify the registers
uint32_t driver_control_register_value,
chopper_config_register,
cool_step_register_value,
stallguard2_current_register_value,
driver_configuration_register_value,
driver_status_result; // The driver status result
// Helper routione to get the top 10 bit of the readout
inline int16_t getReadoutValue();
// The pins for the stepper driver
uint8_t cs_pin, step_pin, dir_pin;
// Status values
boolean started; // If the stepper has been started yet
int16_t microsteps; // The current number of micro steps
char constant_off_time; // We need to remember this value in order to enable and disable the motor
uint8_t cool_step_lower_threshold; // we need to remember the threshold to enable and disable the CoolStep feature
boolean cool_step_enabled; // We need to remember this to configure the coolstep if it si enabled
// SPI sender
inline void send262(uint32_t datagram);
};

127
Marlin/src/HAL/STM32_F4_F7/STM32F7/timers.cpp

@ -1,127 +0,0 @@
/**
* Marlin 3D Printer Firmware
*
* Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
* Copyright (c) 2016 Bob Cousins bobcousins42@googlemail.com
* Copyright (c) 2015-2016 Nico Tonnhofer wurstnase.reprap@gmail.com
*
* This program is free software: you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation, either version 3 of the License, or
* (at your option) any later version.
*
* This program is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with this program. If not, see <https://www.gnu.org/licenses/>.
*
*/
#if defined(STM32GENERIC) && defined(STM32F7)
#include "../../../inc/MarlinConfig.h"
// ------------------------
// Local defines
// ------------------------
#define NUM_HARDWARE_TIMERS 2
//#define PRESCALER 1
// ------------------------
// Private Variables
// ------------------------
tTimerConfig timerConfig[NUM_HARDWARE_TIMERS];
// ------------------------
// Public functions
// ------------------------
bool timers_initialized[NUM_HARDWARE_TIMERS] = { false };
void HAL_timer_start(const uint8_t timer_num, const uint32_t frequency) {
if (!timers_initialized[timer_num]) {
switch (timer_num) {
case STEP_TIMER_NUM:
//STEPPER TIMER TIM5 //use a 32bit timer
__HAL_RCC_TIM5_CLK_ENABLE();
timerConfig[0].timerdef.Instance = TIM5;
timerConfig[0].timerdef.Init.Prescaler = (STEPPER_TIMER_PRESCALE);
timerConfig[0].timerdef.Init.CounterMode = TIM_COUNTERMODE_UP;
timerConfig[0].timerdef.Init.ClockDivision = TIM_CLOCKDIVISION_DIV1;
timerConfig[0].IRQ_Id = TIM5_IRQn;
timerConfig[0].callback = (uint32_t)TC5_Handler;
HAL_NVIC_SetPriority(timerConfig[0].IRQ_Id, 1, 0);
#if PIN_EXISTS(STEPPER_ENABLE)
OUT_WRITE(STEPPER_ENABLE_PIN, HIGH);
#endif
break;
case TEMP_TIMER_NUM:
//TEMP TIMER TIM7 // any available 16bit Timer (1 already used for PWM)
__HAL_RCC_TIM7_CLK_ENABLE();
timerConfig[1].timerdef.Instance = TIM7;
timerConfig[1].timerdef.Init.Prescaler = (TEMP_TIMER_PRESCALE);
timerConfig[1].timerdef.Init.CounterMode = TIM_COUNTERMODE_UP;
timerConfig[1].timerdef.Init.ClockDivision = TIM_CLOCKDIVISION_DIV1;
timerConfig[1].IRQ_Id = TIM7_IRQn;
timerConfig[1].callback = (uint32_t)TC7_Handler;
HAL_NVIC_SetPriority(timerConfig[1].IRQ_Id, 2, 0);
break;
}
timers_initialized[timer_num] = true;
}
timerConfig[timer_num].timerdef.Init.Period = (((HAL_TIMER_RATE) / timerConfig[timer_num].timerdef.Init.Prescaler) / frequency) - 1;
if (HAL_TIM_Base_Init(&timerConfig[timer_num].timerdef) == HAL_OK)
HAL_TIM_Base_Start_IT(&timerConfig[timer_num].timerdef);
}
//forward the interrupt
extern "C" {
void TIM5_IRQHandler() { ((void(*)())timerConfig[0].callback)(); }
void TIM7_IRQHandler() { ((void(*)())timerConfig[1].callback)(); }
}
void HAL_timer_set_compare(const uint8_t timer_num, const uint32_t compare) {
__HAL_TIM_SetAutoreload(&timerConfig[timer_num].timerdef, compare);
}
void HAL_timer_enable_interrupt(const uint8_t timer_num) {
HAL_NVIC_EnableIRQ(timerConfig[timer_num].IRQ_Id);
}
void HAL_timer_disable_interrupt(const uint8_t timer_num) {
HAL_NVIC_DisableIRQ(timerConfig[timer_num].IRQ_Id);
// We NEED memory barriers to ensure Interrupts are actually disabled!
// ( https://dzone.com/articles/nvic-disabling-interrupts-on-arm-cortex-m-and-the )
__DSB();
__ISB();
}
hal_timer_t HAL_timer_get_compare(const uint8_t timer_num) {
return __HAL_TIM_GetAutoreload(&timerConfig[timer_num].timerdef);
}
uint32_t HAL_timer_get_count(const uint8_t timer_num) {
return __HAL_TIM_GetCounter(&timerConfig[timer_num].timerdef);
}
void HAL_timer_isr_prologue(const uint8_t timer_num) {
if (__HAL_TIM_GET_FLAG(&timerConfig[timer_num].timerdef, TIM_FLAG_UPDATE) == SET) {
__HAL_TIM_CLEAR_FLAG(&timerConfig[timer_num].timerdef, TIM_FLAG_UPDATE);
}
}
bool HAL_timer_interrupt_enabled(const uint8_t timer_num) {
const uint32_t IRQ_Id = uint32_t(timerConfig[timer_num].IRQ_Id);
return NVIC->ISER[IRQ_Id >> 5] & _BV32(IRQ_Id & 0x1F);
}
#endif // STM32GENERIC && STM32F7

107
Marlin/src/HAL/STM32_F4_F7/STM32F7/timers.h

@ -1,107 +0,0 @@
/**
* Marlin 3D Printer Firmware
*
* Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
* Copyright (c) 2016 Bob Cousins bobcousins42@googlemail.com
* Copyright (c) 2017 Victor Perez
*
* This program is free software: you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation, either version 3 of the License, or
* (at your option) any later version.
*
* This program is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with this program. If not, see <https://www.gnu.org/licenses/>.
*
*/
#pragma once
#include <stdint.h>
// ------------------------
// Defines
// ------------------------
#define FORCE_INLINE __attribute__((always_inline)) inline
#define hal_timer_t uint32_t // TODO: One is 16-bit, one 32-bit - does this need to be checked?
#define HAL_TIMER_TYPE_MAX 0xFFFF
#define HAL_TIMER_RATE (HAL_RCC_GetSysClockFreq() / 2) // frequency of timer peripherals
#ifndef STEP_TIMER_NUM
#define STEP_TIMER_NUM 0 // Timer Index for Stepper
#endif
#ifndef PULSE_TIMER_NUM
#define PULSE_TIMER_NUM STEP_TIMER_NUM
#endif
#ifndef TEMP_TIMER_NUM
#define TEMP_TIMER_NUM 1 // Timer Index for Temperature
#endif
#define TEMP_TIMER_FREQUENCY 1000 // temperature interrupt frequency
#define TEMP_TIMER_PRESCALE 1000 // prescaler for setting Temp timer, 72Khz
#define STEPPER_TIMER_PRESCALE 54 // was 40,prescaler for setting stepper timer, 2Mhz
#define STEPPER_TIMER_RATE (HAL_TIMER_RATE / STEPPER_TIMER_PRESCALE) // frequency of stepper timer
#define STEPPER_TIMER_TICKS_PER_US ((STEPPER_TIMER_RATE) / 1000000) // stepper timer ticks per µs
#define PULSE_TIMER_RATE STEPPER_TIMER_RATE // frequency of pulse timer
#define PULSE_TIMER_PRESCALE STEPPER_TIMER_PRESCALE
#define PULSE_TIMER_TICKS_PER_US STEPPER_TIMER_TICKS_PER_US
#define ENABLE_STEPPER_DRIVER_INTERRUPT() HAL_timer_enable_interrupt(STEP_TIMER_NUM)
#define DISABLE_STEPPER_DRIVER_INTERRUPT() HAL_timer_disable_interrupt(STEP_TIMER_NUM)
#define ENABLE_TEMPERATURE_INTERRUPT() HAL_timer_enable_interrupt(TEMP_TIMER_NUM)
#define DISABLE_TEMPERATURE_INTERRUPT() HAL_timer_disable_interrupt(TEMP_TIMER_NUM)
#define STEPPER_ISR_ENABLED() HAL_timer_interrupt_enabled(STEP_TIMER_NUM)
#define TEMP_ISR_ENABLED() HAL_timer_interrupt_enabled(TEMP_TIMER_NUM)
// TODO change this
extern void TC5_Handler();
extern void TC7_Handler();
#ifndef HAL_STEP_TIMER_ISR
#define HAL_STEP_TIMER_ISR() void TC5_Handler()
#endif
#ifndef HAL_TEMP_TIMER_ISR
#define HAL_TEMP_TIMER_ISR() void TC7_Handler()
#endif
// ------------------------
// Types
// ------------------------
typedef struct {
TIM_HandleTypeDef timerdef;
IRQn_Type IRQ_Id;
uint32_t callback;
} tTimerConfig;
// ------------------------
// Public Variables
// ------------------------
//extern const tTimerConfig timerConfig[];
// ------------------------
// Public functions
// ------------------------
void HAL_timer_start(const uint8_t timer_num, const uint32_t frequency);
void HAL_timer_enable_interrupt(const uint8_t timer_num);
void HAL_timer_disable_interrupt(const uint8_t timer_num);
bool HAL_timer_interrupt_enabled(const uint8_t timer_num);
void HAL_timer_set_compare(const uint8_t timer_num, const uint32_t compare);
hal_timer_t HAL_timer_get_compare(const uint8_t timer_num);
uint32_t HAL_timer_get_count(const uint8_t timer_num);
void HAL_timer_isr_prologue(const uint8_t timer_num);
#define HAL_timer_isr_epilogue(TIMER_NUM)

51
Marlin/src/HAL/STM32_F4_F7/Servo.cpp

@ -1,51 +0,0 @@
/**
* Marlin 3D Printer Firmware
* Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
*
* Based on Sprinter and grbl.
* Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm
* Copyright (c) 2017 Victor Perez
*
* This program is free software: you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation, either version 3 of the License, or
* (at your option) any later version.
*
* This program is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with this program. If not, see <https://www.gnu.org/licenses/>.
*
*/
#if defined(STM32GENERIC) && (defined(STM32F4) || defined(STM32F7))
#include "../../inc/MarlinConfig.h"
#if HAS_SERVOS
#include "Servo.h"
int8_t libServo::attach(const int pin) {
if (servoIndex >= MAX_SERVOS) return -1;
return super::attach(pin);
}
int8_t libServo::attach(const int pin, const int min, const int max) {
return super::attach(pin, min, max);
}
void libServo::move(const int value) {
constexpr uint16_t servo_delay[] = SERVO_DELAY;
static_assert(COUNT(servo_delay) == NUM_SERVOS, "SERVO_DELAY must be an array NUM_SERVOS long.");
if (attach(0) >= 0) {
write(value);
safe_delay(servo_delay[servoIndex]);
TERN_(DEACTIVATE_SERVOS_AFTER_MOVE, detach());
}
}
#endif // HAS_SERVOS
#endif // STM32GENERIC && (STM32F4 || STM32F7)

41
Marlin/src/HAL/STM32_F4_F7/Servo.h

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

535
Marlin/src/HAL/STM32_F4_F7/eeprom_emul.cpp

@ -1,535 +0,0 @@
/**
******************************************************************************
* @file eeprom_emul.cpp
* @author MCD Application Team
* @version V1.2.6
* @date 04-November-2016
* @brief This file provides all the EEPROM emulation firmware functions.
******************************************************************************
* @attention
*
* Copyright © 2016 STMicroelectronics International N.V.
* All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted, provided that the following conditions are met:
*
* 1. Redistribution of source code must retain the above copyright notice,
* this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright notice,
* this list of conditions and the following disclaimer in the documentation
* and/or other materials provided with the distribution.
* 3. Neither the name of STMicroelectronics nor the names of other
* contributors to this software may be used to endorse or promote products
* derived from this software without specific written permission.
* 4. This software, including modifications and/or derivative works of this
* software, must execute solely and exclusively on microcontroller or
* microprocessor devices manufactured by or for STMicroelectronics.
* 5. Redistribution and use of this software other than as permitted under
* this license is void and will automatically terminate your rights under
* this license.
*
* THIS SOFTWARE IS PROVIDED BY STMICROELECTRONICS AND CONTRIBUTORS "AS IS"
* AND ANY EXPRESS, IMPLIED OR STATUTORY WARRANTIES, INCLUDING, BUT NOT
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY, FITNESS FOR A
* PARTICULAR PURPOSE AND NON-INFRINGEMENT OF THIRD PARTY INTELLECTUAL PROPERTY
* RIGHTS ARE DISCLAIMED TO THE FULLEST EXTENT PERMITTED BY LAW. IN NO EVENT
* SHALL STMICROELECTRONICS OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT
* LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA,
* OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF
* LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING
* NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE,
* EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
*
******************************************************************************
*/
/** @addtogroup EEPROM_Emulation
* @{
*/
#if defined(STM32GENERIC) && (defined(STM32F4) || defined(STM32F7))
#include "../../inc/MarlinConfig.h"
#if ENABLED(FLASH_EEPROM_EMULATION)
/* Includes ------------------------------------------------------------------*/
#include "eeprom_emul.h"
/* Private variables ---------------------------------------------------------*/
/* Global variable used to store variable value in read sequence */
uint16_t DataVar = 0;
/* Virtual address defined by the user: 0xFFFF value is prohibited */
uint16_t VirtAddVarTab[NB_OF_VAR];
/* Private function prototypes -----------------------------------------------*/
static HAL_StatusTypeDef EE_Format();
static uint16_t EE_FindValidPage(uint8_t Operation);
static uint16_t EE_VerifyPageFullWriteVariable(uint16_t VirtAddress, uint16_t Data);
static uint16_t EE_PageTransfer(uint16_t VirtAddress, uint16_t Data);
static uint16_t EE_VerifyPageFullyErased(uint32_t Address);
/**
* @brief Restore the pages to a known good state in case of page's status
* corruption after a power loss.
* @param None.
* @retval - Flash error code: on write Flash error
* - FLASH_COMPLETE: on success
*/
/* Private functions ---------------------------------------------------------*/
uint16_t EE_Initialize() {
/* Get Page0 and Page1 status */
uint16_t PageStatus0 = (*(__IO uint16_t*)PAGE0_BASE_ADDRESS),
PageStatus1 = (*(__IO uint16_t*)PAGE1_BASE_ADDRESS);
FLASH_EraseInitTypeDef pEraseInit;
pEraseInit.TypeErase = TYPEERASE_SECTORS;
pEraseInit.Sector = PAGE0_ID;
pEraseInit.NbSectors = 1;
pEraseInit.VoltageRange = VOLTAGE_RANGE;
HAL_StatusTypeDef FlashStatus; // = HAL_OK
/* Check for invalid header states and repair if necessary */
uint32_t SectorError;
switch (PageStatus0) {
case ERASED:
if (PageStatus1 == VALID_PAGE) { /* Page0 erased, Page1 valid */
/* Erase Page0 */
if (!EE_VerifyPageFullyErased(PAGE0_BASE_ADDRESS)) {
/* As the last operation, simply return the result */
return HAL_FLASHEx_Erase(&pEraseInit, &SectorError);
}
}
else if (PageStatus1 == RECEIVE_DATA) { /* Page0 erased, Page1 receive */
/* Erase Page0 */
if (!EE_VerifyPageFullyErased(PAGE0_BASE_ADDRESS)) {
HAL_StatusTypeDef fStat = HAL_FLASHEx_Erase(&pEraseInit, &SectorError);
/* If erase operation was failed, a Flash error code is returned */
if (fStat != HAL_OK) return fStat;
}
/* Mark Page1 as valid */
/* As the last operation, simply return the result */
return HAL_FLASH_Program(TYPEPROGRAM_HALFWORD, PAGE1_BASE_ADDRESS, VALID_PAGE);
}
else { /* First EEPROM access (Page0&1 are erased) or invalid state -> format EEPROM */
/* Erase both Page0 and Page1 and set Page0 as valid page */
/* As the last operation, simply return the result */
return EE_Format();
}
break;
case RECEIVE_DATA:
if (PageStatus1 == VALID_PAGE) { /* Page0 receive, Page1 valid */
/* Transfer data from Page1 to Page0 */
int16_t x = -1;
for (uint16_t VarIdx = 0; VarIdx < NB_OF_VAR; VarIdx++) {
if (( *(__IO uint16_t*)(PAGE0_BASE_ADDRESS + 6)) == VirtAddVarTab[VarIdx])
x = VarIdx;
if (VarIdx != x) {
/* Read the last variables' updates */
uint16_t ReadStatus = EE_ReadVariable(VirtAddVarTab[VarIdx], &DataVar);
/* In case variable corresponding to the virtual address was found */
if (ReadStatus != 0x1) {
/* Transfer the variable to the Page0 */
uint16_t EepromStatus = EE_VerifyPageFullWriteVariable(VirtAddVarTab[VarIdx], DataVar);
/* If program operation was failed, a Flash error code is returned */
if (EepromStatus != HAL_OK) return EepromStatus;
}
}
}
/* Mark Page0 as valid */
FlashStatus = HAL_FLASH_Program(TYPEPROGRAM_HALFWORD, PAGE0_BASE_ADDRESS, VALID_PAGE);
/* If program operation was failed, a Flash error code is returned */
if (FlashStatus != HAL_OK) return FlashStatus;
pEraseInit.Sector = PAGE1_ID;
pEraseInit.NbSectors = 1;
pEraseInit.VoltageRange = VOLTAGE_RANGE;
/* Erase Page1 */
if (!EE_VerifyPageFullyErased(PAGE1_BASE_ADDRESS)) {
/* As the last operation, simply return the result */
return HAL_FLASHEx_Erase(&pEraseInit, &SectorError);
}
}
else if (PageStatus1 == ERASED) { /* Page0 receive, Page1 erased */
pEraseInit.Sector = PAGE1_ID;
pEraseInit.NbSectors = 1;
pEraseInit.VoltageRange = VOLTAGE_RANGE;
/* Erase Page1 */
if (!EE_VerifyPageFullyErased(PAGE1_BASE_ADDRESS)) {
HAL_StatusTypeDef fStat = HAL_FLASHEx_Erase(&pEraseInit, &SectorError);
/* If erase operation was failed, a Flash error code is returned */
if (fStat != HAL_OK) return fStat;
}
/* Mark Page0 as valid */
/* As the last operation, simply return the result */
return HAL_FLASH_Program(TYPEPROGRAM_HALFWORD, PAGE0_BASE_ADDRESS, VALID_PAGE);
}
else { /* Invalid state -> format eeprom */
/* Erase both Page0 and Page1 and set Page0 as valid page */
/* As the last operation, simply return the result */
return EE_Format();
}
break;
case VALID_PAGE:
if (PageStatus1 == VALID_PAGE) { /* Invalid state -> format eeprom */
/* Erase both Page0 and Page1 and set Page0 as valid page */
FlashStatus = EE_Format();
/* If erase/program operation was failed, a Flash error code is returned */
if (FlashStatus != HAL_OK) return FlashStatus;
}
else if (PageStatus1 == ERASED) { /* Page0 valid, Page1 erased */
pEraseInit.Sector = PAGE1_ID;
pEraseInit.NbSectors = 1;
pEraseInit.VoltageRange = VOLTAGE_RANGE;
/* Erase Page1 */
if (!EE_VerifyPageFullyErased(PAGE1_BASE_ADDRESS)) {
FlashStatus = HAL_FLASHEx_Erase(&pEraseInit, &SectorError);
/* If erase operation was failed, a Flash error code is returned */
if (FlashStatus != HAL_OK) return FlashStatus;
}
}
else { /* Page0 valid, Page1 receive */
/* Transfer data from Page0 to Page1 */
int16_t x = -1;
for (uint16_t VarIdx = 0; VarIdx < NB_OF_VAR; VarIdx++) {
if ((*(__IO uint16_t*)(PAGE1_BASE_ADDRESS + 6)) == VirtAddVarTab[VarIdx])
x = VarIdx;
if (VarIdx != x) {
/* Read the last variables' updates */
uint16_t ReadStatus = EE_ReadVariable(VirtAddVarTab[VarIdx], &DataVar);
/* In case variable corresponding to the virtual address was found */
if (ReadStatus != 0x1) {
/* Transfer the variable to the Page1 */
uint16_t EepromStatus = EE_VerifyPageFullWriteVariable(VirtAddVarTab[VarIdx], DataVar);
/* If program operation was failed, a Flash error code is returned */
if (EepromStatus != HAL_OK) return EepromStatus;
}
}
}
/* Mark Page1 as valid */
FlashStatus = HAL_FLASH_Program(TYPEPROGRAM_HALFWORD, PAGE1_BASE_ADDRESS, VALID_PAGE);
/* If program operation was failed, a Flash error code is returned */
if (FlashStatus != HAL_OK) return FlashStatus;
pEraseInit.Sector = PAGE0_ID;
pEraseInit.NbSectors = 1;
pEraseInit.VoltageRange = VOLTAGE_RANGE;
/* Erase Page0 */
if (!EE_VerifyPageFullyErased(PAGE0_BASE_ADDRESS)) {
/* As the last operation, simply return the result */
return HAL_FLASHEx_Erase(&pEraseInit, &SectorError);
}
}
break;
default: /* Any other state -> format eeprom */
/* Erase both Page0 and Page1 and set Page0 as valid page */
/* As the last operation, simply return the result */
return EE_Format();
}
return HAL_OK;
}
/**
* @brief Verify if specified page is fully erased.
* @param Address: page address
* This parameter can be one of the following values:
* @arg PAGE0_BASE_ADDRESS: Page0 base address
* @arg PAGE1_BASE_ADDRESS: Page1 base address
* @retval page fully erased status:
* - 0: if Page not erased
* - 1: if Page erased
*/
uint16_t EE_VerifyPageFullyErased(uint32_t Address) {
uint32_t ReadStatus = 1;
/* Check each active page address starting from end */
while (Address <= PAGE0_END_ADDRESS) {
/* Get the current location content to be compared with virtual address */
uint16_t AddressValue = (*(__IO uint16_t*)Address);
/* Compare the read address with the virtual address */
if (AddressValue != ERASED) {
/* In case variable value is read, reset ReadStatus flag */
ReadStatus = 0;
break;
}
/* Next address location */
Address += 4;
}
/* Return ReadStatus value: (0: Page not erased, 1: Sector erased) */
return ReadStatus;
}
/**
* @brief Returns the last stored variable data, if found, which correspond to
* the passed virtual address
* @param VirtAddress: Variable virtual address
* @param Data: Global variable contains the read variable value
* @retval Success or error status:
* - 0: if variable was found
* - 1: if the variable was not found
* - NO_VALID_PAGE: if no valid page was found.
*/
uint16_t EE_ReadVariable(uint16_t VirtAddress, uint16_t* Data) {
uint16_t ReadStatus = 1;
/* Get active Page for read operation */
uint16_t ValidPage = EE_FindValidPage(READ_FROM_VALID_PAGE);
/* Check if there is no valid page */
if (ValidPage == NO_VALID_PAGE) return NO_VALID_PAGE;
/* Get the valid Page start and end Addresses */
uint32_t PageStartAddress = uint32_t(EEPROM_START_ADDRESS) + uint32_t(ValidPage * (PAGE_SIZE)),
Address = PageStartAddress + PAGE_SIZE - 2;
/* Check each active page address starting from end */
while (Address > PageStartAddress + 2) {
/* Get the current location content to be compared with virtual address */
uint16_t AddressValue = (*(__IO uint16_t*)Address);
/* Compare the read address with the virtual address */
if (AddressValue == VirtAddress) {
/* Get content of Address-2 which is variable value */
*Data = (*(__IO uint16_t*)(Address - 2));
/* In case variable value is read, reset ReadStatus flag */
ReadStatus = 0;
break;
}
else /* Next address location */
Address -= 4;
}
/* Return ReadStatus value: (0: variable exist, 1: variable doesn't exist) */
return ReadStatus;
}
/**
* @brief Writes/upadtes variable data in EEPROM.
* @param VirtAddress: Variable virtual address
* @param Data: 16 bit data to be written
* @retval Success or error status:
* - FLASH_COMPLETE: on success
* - PAGE_FULL: if valid page is full
* - NO_VALID_PAGE: if no valid page was found
* - Flash error code: on write Flash error
*/
uint16_t EE_WriteVariable(uint16_t VirtAddress, uint16_t Data) {
/* Write the variable virtual address and value in the EEPROM */
uint16_t Status = EE_VerifyPageFullWriteVariable(VirtAddress, Data);
/* In case the EEPROM active page is full */
if (Status == PAGE_FULL) /* Perform Page transfer */
Status = EE_PageTransfer(VirtAddress, Data);
/* Return last operation status */
return Status;
}
/**
* @brief Erases PAGE and PAGE1 and writes VALID_PAGE header to PAGE
* @param None
* @retval Status of the last operation (Flash write or erase) done during
* EEPROM formatting
*/
static HAL_StatusTypeDef EE_Format() {
FLASH_EraseInitTypeDef pEraseInit;
pEraseInit.TypeErase = FLASH_TYPEERASE_SECTORS;
pEraseInit.Sector = PAGE0_ID;
pEraseInit.NbSectors = 1;
pEraseInit.VoltageRange = VOLTAGE_RANGE;
HAL_StatusTypeDef FlashStatus; // = HAL_OK
/* Erase Page0 */
if (!EE_VerifyPageFullyErased(PAGE0_BASE_ADDRESS)) {
uint32_t SectorError;
FlashStatus = HAL_FLASHEx_Erase(&pEraseInit, &SectorError);
/* If erase operation was failed, a Flash error code is returned */
if (FlashStatus != HAL_OK) return FlashStatus;
}
/* Set Page0 as valid page: Write VALID_PAGE at Page0 base address */
FlashStatus = HAL_FLASH_Program(TYPEPROGRAM_HALFWORD, PAGE0_BASE_ADDRESS, VALID_PAGE);
/* If program operation was failed, a Flash error code is returned */
if (FlashStatus != HAL_OK) return FlashStatus;
pEraseInit.Sector = PAGE1_ID;
/* Erase Page1 */
if (!EE_VerifyPageFullyErased(PAGE1_BASE_ADDRESS)) {
/* As the last operation, just return the result code */
uint32_t SectorError;
return HAL_FLASHEx_Erase(&pEraseInit, &SectorError);
}
return HAL_OK;
}
/**
* @brief Find valid Page for write or read operation
* @param Operation: operation to achieve on the valid page.
* This parameter can be one of the following values:
* @arg READ_FROM_VALID_PAGE: read operation from valid page
* @arg WRITE_IN_VALID_PAGE: write operation from valid page
* @retval Valid page number (PAGE or PAGE1) or NO_VALID_PAGE in case
* of no valid page was found
*/
static uint16_t EE_FindValidPage(uint8_t Operation) {
/* Get Page0 and Page1 actual status */
uint16_t PageStatus0 = (*(__IO uint16_t*)PAGE0_BASE_ADDRESS),
PageStatus1 = (*(__IO uint16_t*)PAGE1_BASE_ADDRESS);
/* Write or read operation */
switch (Operation) {
case WRITE_IN_VALID_PAGE: /* ---- Write operation ---- */
if (PageStatus1 == VALID_PAGE) {
/* Page0 receiving data */
return (PageStatus0 == RECEIVE_DATA) ? PAGE0 : PAGE1;
}
else if (PageStatus0 == VALID_PAGE) {
/* Page1 receiving data */
return (PageStatus1 == RECEIVE_DATA) ? PAGE1 : PAGE0;
}
else
return NO_VALID_PAGE; /* No valid Page */
case READ_FROM_VALID_PAGE: /* ---- Read operation ---- */
if (PageStatus0 == VALID_PAGE)
return PAGE0; /* Page0 valid */
else if (PageStatus1 == VALID_PAGE)
return PAGE1; /* Page1 valid */
else
return NO_VALID_PAGE; /* No valid Page */
default:
return PAGE0; /* Page0 valid */
}
}
/**
* @brief Verify if active page is full and Writes variable in EEPROM.
* @param VirtAddress: 16 bit virtual address of the variable
* @param Data: 16 bit data to be written as variable value
* @retval Success or error status:
* - FLASH_COMPLETE: on success
* - PAGE_FULL: if valid page is full
* - NO_VALID_PAGE: if no valid page was found
* - Flash error code: on write Flash error
*/
static uint16_t EE_VerifyPageFullWriteVariable(uint16_t VirtAddress, uint16_t Data) {
/* Get valid Page for write operation */
uint16_t ValidPage = EE_FindValidPage(WRITE_IN_VALID_PAGE);
/* Check if there is no valid page */
if (ValidPage == NO_VALID_PAGE) return NO_VALID_PAGE;
/* Get the valid Page start and end Addresses */
uint32_t Address = uint32_t(EEPROM_START_ADDRESS) + uint32_t(ValidPage * (PAGE_SIZE)),
PageEndAddress = Address + PAGE_SIZE - 1;
/* Check each active page address starting from begining */
while (Address < PageEndAddress) {
/* Verify if Address and Address+2 contents are 0xFFFFFFFF */
if ((*(__IO uint32_t*)Address) == 0xFFFFFFFF) {
/* Set variable data */
HAL_StatusTypeDef FlashStatus = HAL_FLASH_Program(TYPEPROGRAM_HALFWORD, Address, Data);
/* If program operation was failed, a Flash error code is returned */
if (FlashStatus != HAL_OK) return FlashStatus;
/* Set variable virtual address, return status */
return HAL_FLASH_Program(TYPEPROGRAM_HALFWORD, Address + 2, VirtAddress);
}
else /* Next address location */
Address += 4;
}
/* Return PAGE_FULL in case the valid page is full */
return PAGE_FULL;
}
/**
* @brief Transfers last updated variables data from the full Page to
* an empty one.
* @param VirtAddress: 16 bit virtual address of the variable
* @param Data: 16 bit data to be written as variable value
* @retval Success or error status:
* - FLASH_COMPLETE: on success
* - PAGE_FULL: if valid page is full
* - NO_VALID_PAGE: if no valid page was found
* - Flash error code: on write Flash error
*/
static uint16_t EE_PageTransfer(uint16_t VirtAddress, uint16_t Data) {
/* Get active Page for read operation */
uint16_t ValidPage = EE_FindValidPage(READ_FROM_VALID_PAGE);
uint32_t NewPageAddress = EEPROM_START_ADDRESS;
uint16_t OldPageId = 0;
if (ValidPage == PAGE1) { /* Page1 valid */
/* New page address where variable will be moved to */
NewPageAddress = PAGE0_BASE_ADDRESS;
/* Old page ID where variable will be taken from */
OldPageId = PAGE1_ID;
}
else if (ValidPage == PAGE0) { /* Page0 valid */
/* New page address where variable will be moved to */
NewPageAddress = PAGE1_BASE_ADDRESS;
/* Old page ID where variable will be taken from */
OldPageId = PAGE0_ID;
}
else
return NO_VALID_PAGE; /* No valid Page */
/* Set the new Page status to RECEIVE_DATA status */
HAL_StatusTypeDef FlashStatus = HAL_FLASH_Program(TYPEPROGRAM_HALFWORD, NewPageAddress, RECEIVE_DATA);
/* If program operation was failed, a Flash error code is returned */
if (FlashStatus != HAL_OK) return FlashStatus;
/* Write the variable passed as parameter in the new active page */
uint16_t EepromStatus = EE_VerifyPageFullWriteVariable(VirtAddress, Data);
/* If program operation was failed, a Flash error code is returned */
if (EepromStatus != HAL_OK) return EepromStatus;
/* Transfer process: transfer variables from old to the new active page */
for (uint16_t VarIdx = 0; VarIdx < NB_OF_VAR; VarIdx++) {
if (VirtAddVarTab[VarIdx] != VirtAddress) { /* Check each variable except the one passed as parameter */
/* Read the other last variable updates */
uint16_t ReadStatus = EE_ReadVariable(VirtAddVarTab[VarIdx], &DataVar);
/* In case variable corresponding to the virtual address was found */
if (ReadStatus != 0x1) {
/* Transfer the variable to the new active page */
EepromStatus = EE_VerifyPageFullWriteVariable(VirtAddVarTab[VarIdx], DataVar);
/* If program operation was failed, a Flash error code is returned */
if (EepromStatus != HAL_OK) return EepromStatus;
}
}
}
FLASH_EraseInitTypeDef pEraseInit;
pEraseInit.TypeErase = TYPEERASE_SECTORS;
pEraseInit.Sector = OldPageId;
pEraseInit.NbSectors = 1;
pEraseInit.VoltageRange = VOLTAGE_RANGE;
/* Erase the old Page: Set old Page status to ERASED status */
uint32_t SectorError;
FlashStatus = HAL_FLASHEx_Erase(&pEraseInit, &SectorError);
/* If erase operation was failed, a Flash error code is returned */
if (FlashStatus != HAL_OK) return FlashStatus;
/* Set new Page status to VALID_PAGE status */
/* As the last operation, just return the result code */
return HAL_FLASH_Program(TYPEPROGRAM_HALFWORD, NewPageAddress, VALID_PAGE);
}
#endif // FLASH_EEPROM_EMULATION
#endif // STM32GENERIC && (STM32F4 || STM32F7)
/**
* @}
*/
/******************* (C) COPYRIGHT 2011 STMicroelectronics *****END OF FILE****/

114
Marlin/src/HAL/STM32_F4_F7/eeprom_emul.h

@ -1,114 +0,0 @@
/******************************************************************************
* @file eeprom_emul.h
* @author MCD Application Team
* @version V1.2.6
* @date 04-November-2016
* @brief This file contains all the functions prototypes for the EEPROM
* emulation firmware library.
******************************************************************************
* @attention
*
* Copyright © 2016 STMicroelectronics International N.V.
* All rights reserved.</center></h2>
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted, provided that the following conditions are met:
*
* 1. Redistribution of source code must retain the above copyright notice,
* this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright notice,
* this list of conditions and the following disclaimer in the documentation
* and/or other materials provided with the distribution.
* 3. Neither the name of STMicroelectronics nor the names of other
* contributors to this software may be used to endorse or promote products
* derived from this software without specific written permission.
* 4. This software, including modifications and/or derivative works of this
* software, must execute solely and exclusively on microcontroller or
* microprocessor devices manufactured by or for STMicroelectronics.
* 5. Redistribution and use of this software other than as permitted under
* this license is void and will automatically terminate your rights under
* this license.
*
* THIS SOFTWARE IS PROVIDED BY STMICROELECTRONICS AND CONTRIBUTORS "AS IS"
* AND ANY EXPRESS, IMPLIED OR STATUTORY WARRANTIES, INCLUDING, BUT NOT
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY, FITNESS FOR A
* PARTICULAR PURPOSE AND NON-INFRINGEMENT OF THIRD PARTY INTELLECTUAL PROPERTY
* RIGHTS ARE DISCLAIMED TO THE FULLEST EXTENT PERMITTED BY LAW. IN NO EVENT
* SHALL STMICROELECTRONICS OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT
* LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA,
* OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF
* LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING
* NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE,
* EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
*
******************************************************************************/
#pragma once
// ------------------------
// Includes
// ------------------------
#include "../../inc/MarlinConfig.h"
/* Exported constants --------------------------------------------------------*/
/* EEPROM emulation firmware error codes */
#define EE_OK uint32_t(HAL_OK)
#define EE_ERROR uint32_t(HAL_ERROR)
#define EE_BUSY uint32_t(HAL_BUSY)
#define EE_TIMEOUT uint32_t(HAL_TIMEOUT)
/* Define the size of the sectors to be used */
#define PAGE_SIZE uint32_t(0x4000) /* Page size = 16KByte */
/* Device voltage range supposed to be [2.7V to 3.6V], the operation will
be done by word */
#define VOLTAGE_RANGE uint8_t(VOLTAGE_RANGE_3)
/* EEPROM start address in Flash */
#ifdef STM32F7
#define EEPROM_START_ADDRESS uint32_t(0x08100000) /* EEPROM emulation start address:
from sector2 : after 16KByte of used
Flash memory */
#else
#define EEPROM_START_ADDRESS uint32_t(0x08078000) /* EEPROM emulation start address:
after 480KByte of used Flash memory */
#endif
/* Pages 0 and 1 base and end addresses */
#define PAGE0_BASE_ADDRESS uint32_t(EEPROM_START_ADDRESS + 0x0000)
#define PAGE0_END_ADDRESS uint32_t(EEPROM_START_ADDRESS + PAGE_SIZE - 1)
#define PAGE0_ID FLASH_SECTOR_1
#define PAGE1_BASE_ADDRESS uint32_t(EEPROM_START_ADDRESS + 0x4000)
#define PAGE1_END_ADDRESS uint32_t(EEPROM_START_ADDRESS + 2 * (PAGE_SIZE) - 1)
#define PAGE1_ID FLASH_SECTOR_2
/* Used Flash pages for EEPROM emulation */
#define PAGE0 uint16_t(0x0000)
#define PAGE1 uint16_t(0x0001) /* Page nb between PAGE0_BASE_ADDRESS & PAGE1_BASE_ADDRESS*/
/* No valid page define */
#define NO_VALID_PAGE uint16_t(0x00AB)
/* Page status definitions */
#define ERASED uint16_t(0xFFFF) /* Page is empty */
#define RECEIVE_DATA uint16_t(0xEEEE) /* Page is marked to receive data */
#define VALID_PAGE uint16_t(0x0000) /* Page containing valid data */
/* Valid pages in read and write defines */
#define READ_FROM_VALID_PAGE uint8_t(0x00)
#define WRITE_IN_VALID_PAGE uint8_t(0x01)
/* Page full define */
#define PAGE_FULL uint8_t(0x80)
/* Variables' number */
#define NB_OF_VAR uint16_t(4096)
/* Exported functions ------------------------------------------------------- */
uint16_t EE_Initialize();
uint16_t EE_ReadVariable(uint16_t VirtAddress, uint16_t* Data);
uint16_t EE_WriteVariable(uint16_t VirtAddress, uint16_t Data);
/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/

111
Marlin/src/HAL/STM32_F4_F7/eeprom_flash.cpp

@ -1,111 +0,0 @@
/**
* Marlin 3D Printer Firmware
* Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
*
* This program is free software: you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation, either version 3 of the License, or
* (at your option) any later version.
*
* This program is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with this program. If not, see <https://www.gnu.org/licenses/>.
*
*/
#if defined(STM32GENERIC) && (defined(STM32F4) || defined(STM32F7))
#include "../../inc/MarlinConfig.h"
#if ENABLED(FLASH_EEPROM_EMULATION)
#include "../shared/eeprom_api.h"
#include "eeprom_emul.h"
// FLASH_FLAG_PGSERR (Programming Sequence Error) was renamed to
// FLASH_FLAG_ERSERR (Erasing Sequence Error) in STM32F4/7
#ifdef STM32F7
#define FLASH_FLAG_PGSERR FLASH_FLAG_ERSERR
#else
//#define FLASH_FLAG_PGSERR FLASH_FLAG_ERSERR
#endif
void ee_write_byte(uint8_t *pos, unsigned char value) {
HAL_FLASH_Unlock();
__HAL_FLASH_CLEAR_FLAG(FLASH_FLAG_EOP | FLASH_FLAG_OPERR | FLASH_FLAG_WRPERR |FLASH_FLAG_PGAERR | FLASH_FLAG_PGPERR | FLASH_FLAG_PGSERR);
const unsigned eeprom_address = (unsigned)pos;
if (EE_WriteVariable(eeprom_address, uint16_t(value)) != EE_OK)
for (;;) HAL_Delay(1); // Spin forever until watchdog reset
HAL_FLASH_Lock();
}
uint8_t ee_read_byte(uint8_t *pos) {
uint16_t data = 0xFF;
const unsigned eeprom_address = (unsigned)pos;
(void)EE_ReadVariable(eeprom_address, &data); // Data unchanged on error
return uint8_t(data);
}
#ifndef MARLIN_EEPROM_SIZE
#error "MARLIN_EEPROM_SIZE is required for Flash-based EEPROM."
#endif
size_t PersistentStore::capacity() { return MARLIN_EEPROM_SIZE; }
bool PersistentStore::access_finish() { return true; }
bool PersistentStore::access_start() {
static bool ee_initialized = false;
if (!ee_initialized) {
HAL_FLASH_Unlock();
__HAL_FLASH_CLEAR_FLAG(FLASH_FLAG_EOP | FLASH_FLAG_OPERR | FLASH_FLAG_WRPERR |FLASH_FLAG_PGAERR | FLASH_FLAG_PGPERR | FLASH_FLAG_PGSERR);
/* EEPROM Init */
if (EE_Initialize() != EE_OK)
for (;;) HAL_Delay(1); // Spin forever until watchdog reset
HAL_FLASH_Lock();
ee_initialized = true;
}
return true;
}
bool PersistentStore::write_data(int &pos, const uint8_t *value, size_t size, uint16_t *crc) {
while (size--) {
uint8_t * const p = (uint8_t * const)pos;
uint8_t v = *value;
// EEPROM has only ~100,000 write cycles,
// so only write bytes that have changed!
if (v != ee_read_byte(p)) {
ee_write_byte(p, v);
if (ee_read_byte(p) != v) {
SERIAL_ECHO_MSG(STR_ERR_EEPROM_WRITE);
return true;
}
}
crc16(crc, &v, 1);
pos++;
value++;
}
return false;
}
bool PersistentStore::read_data(int &pos, uint8_t *value, size_t size, uint16_t *crc, const bool writing/*=true*/) {
do {
uint8_t c = ee_read_byte((uint8_t*)pos);
if (writing) *value = c;
crc16(crc, &c, 1);
pos++;
value++;
} while (--size);
return false;
}
#endif // FLASH_EEPROM_EMULATION
#endif // STM32GENERIC && (STM32F4 || STM32F7)

77
Marlin/src/HAL/STM32_F4_F7/eeprom_wired.cpp

@ -1,77 +0,0 @@
/**
* Marlin 3D Printer Firmware
*
* Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
* Copyright (c) 2016 Bob Cousins bobcousins42@googlemail.com
* Copyright (c) 2015-2016 Nico Tonnhofer wurstnase.reprap@gmail.com
* Copyright (c) 2016 Victor Perez victor_pv@hotmail.com
*
* This program is free software: you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation, either version 3 of the License, or
* (at your option) any later version.
*
* This program is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with this program. If not, see <https://www.gnu.org/licenses/>.
*
*/
#if defined(STM32GENERIC) && (defined(STM32F4) || defined(STM32F7))
#include "../../inc/MarlinConfig.h"
#if USE_WIRED_EEPROM
/**
* PersistentStore for Arduino-style EEPROM interface
* with simple implementations supplied by Marlin.
*/
#include "../shared/eeprom_if.h"
#include "../shared/eeprom_api.h"
#ifndef MARLIN_EEPROM_SIZE
#error "MARLIN_EEPROM_SIZE is required for I2C / SPI EEPROM."
#endif
size_t PersistentStore::capacity() { return MARLIN_EEPROM_SIZE; }
bool PersistentStore::access_start() { eeprom_init(); return true; }
bool PersistentStore::access_finish() { return true; }
bool PersistentStore::write_data(int &pos, const uint8_t *value, size_t size, uint16_t *crc) {
while (size--) {
uint8_t * const p = (uint8_t * const)pos;
uint8_t v = *value;
// EEPROM has only ~100,000 write cycles,
// so only write bytes that have changed!
if (v != eeprom_read_byte(p)) {
eeprom_write_byte(p, v);
if (eeprom_read_byte(p) != v) {
SERIAL_ECHO_MSG(STR_ERR_EEPROM_WRITE);
return true;
}
}
crc16(crc, &v, 1);
pos++;
value++;
}
return false;
}
bool PersistentStore::read_data(int &pos, uint8_t *value, size_t size, uint16_t *crc, const bool writing/*=true*/) {
do {
uint8_t c = eeprom_read_byte((uint8_t*)pos);
if (writing) *value = c;
crc16(crc, &c, 1);
pos++;
value++;
} while (--size);
return false;
}
#endif // USE_WIRED_EEPROM
#endif // STM32GENERIC && (STM32F4 || STM32F7)

49
Marlin/src/HAL/STM32_F4_F7/endstop_interrupts.h

@ -1,49 +0,0 @@
/**
* Marlin 3D Printer Firmware
* Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
*
* Based on Sprinter and grbl.
* Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm
* Copyright (c) 2017 Victor Perez
*
* This program is free software: you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation, either version 3 of the License, or
* (at your option) any later version.
*
* This program is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with this program. If not, see <https://www.gnu.org/licenses/>.
*
*/
#pragma once
#include "../../module/endstops.h"
// One ISR for all EXT-Interrupts
void endstop_ISR() { endstops.update(); }
void setup_endstop_interrupts() {
#define _ATTACH(P) attachInterrupt(P, endstop_ISR, CHANGE)
TERN_(HAS_X_MAX, _ATTACH(X_MAX_PIN));
TERN_(HAS_X_MIN, _ATTACH(X_MIN_PIN));
TERN_(HAS_Y_MAX, _ATTACH(Y_MAX_PIN));
TERN_(HAS_Y_MIN, _ATTACH(Y_MIN_PIN));
TERN_(HAS_Z_MAX, _ATTACH(Z_MAX_PIN));
TERN_(HAS_Z_MIN, _ATTACH(Z_MIN_PIN));
TERN_(HAS_X2_MAX, _ATTACH(X2_MAX_PIN));
TERN_(HAS_X2_MIN, _ATTACH(X2_MIN_PIN));
TERN_(HAS_Y2_MAX, _ATTACH(Y2_MAX_PIN));
TERN_(HAS_Y2_MIN, _ATTACH(Y2_MIN_PIN));
TERN_(HAS_Z2_MAX, _ATTACH(Z2_MAX_PIN));
TERN_(HAS_Z2_MIN, _ATTACH(Z2_MIN_PIN));
TERN_(HAS_Z3_MAX, _ATTACH(Z3_MAX_PIN));
TERN_(HAS_Z3_MIN, _ATTACH(Z3_MIN_PIN));
TERN_(HAS_Z4_MAX, _ATTACH(Z4_MAX_PIN));
TERN_(HAS_Z4_MIN, _ATTACH(Z4_MIN_PIN));
TERN_(HAS_Z_MIN_PROBE_PIN, _ATTACH(Z_MIN_PROBE_PIN));
}

310
Marlin/src/HAL/STM32_F4_F7/fastio.h

@ -1,310 +0,0 @@
/**
* Marlin 3D Printer Firmware
* Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
*
* Based on Sprinter and grbl.
* Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm
* Copyright (c) 2017 Victor Perez
*
* This program is free software: you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation, either version 3 of the License, or
* (at your option) any later version.
*
* This program is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with this program. If not, see <https://www.gnu.org/licenses/>.
*
*/
#pragma once
/**
* Fast I/O interfaces for STM32F4/7
* These use GPIO functions instead of Direct Port Manipulation, as on AVR.
*/
#ifndef PWM
#define PWM OUTPUT
#endif
#define READ(IO) digitalRead(IO)
#define WRITE(IO,V) digitalWrite(IO,V)
#define _GET_MODE(IO)
#define _SET_MODE(IO,M) pinMode(IO, M)
#define _SET_OUTPUT(IO) pinMode(IO, OUTPUT) /*!< Output Push Pull Mode & GPIO_NOPULL */
#define OUT_WRITE(IO,V) do{ _SET_OUTPUT(IO); WRITE(IO,V); }while(0)
#define SET_INPUT(IO) _SET_MODE(IO, INPUT) /*!< Input Floating Mode */
#define SET_INPUT_PULLUP(IO) _SET_MODE(IO, INPUT_PULLUP) /*!< Input with Pull-up activation */
#define SET_INPUT_PULLDOWN(IO) _SET_MODE(IO, INPUT_PULLDOWN) /*!< Input with Pull-down activation */
#define SET_OUTPUT(IO) OUT_WRITE(IO, LOW)
#define SET_PWM(IO) _SET_MODE(IO, PWM)
#define TOGGLE(IO) OUT_WRITE(IO, !READ(IO))
#define IS_INPUT(IO)
#define IS_OUTPUT(IO)
#define PWM_PIN(P) true
// digitalRead/Write wrappers
#define extDigitalRead(IO) digitalRead(IO)
#define extDigitalWrite(IO,V) digitalWrite(IO,V)
//
// Pins Definitions
//
#define PORTA 0
#define PORTB 1
#define PORTC 2
#define PORTD 3
#define PORTE 4
#define PORTF 5
#define PORTG 6
#define _STM32_PIN(P,PN) ((PORT##P * 16) + PN)
#undef PA0
#define PA0 _STM32_PIN(A, 0)
#undef PA1
#define PA1 _STM32_PIN(A, 1)
#undef PA2
#define PA2 _STM32_PIN(A, 2)
#undef PA3
#define PA3 _STM32_PIN(A, 3)
#undef PA4
#define PA4 _STM32_PIN(A, 4)
#undef PA5
#define PA5 _STM32_PIN(A, 5)
#undef PA6
#define PA6 _STM32_PIN(A, 6)
#undef PA7
#define PA7 _STM32_PIN(A, 7)
#undef PA8
#define PA8 _STM32_PIN(A, 8)
#undef PA9
#define PA9 _STM32_PIN(A, 9)
#undef PA10
#define PA10 _STM32_PIN(A, 10)
#undef PA11
#define PA11 _STM32_PIN(A, 11)
#undef PA12
#define PA12 _STM32_PIN(A, 12)
#undef PA13
#define PA13 _STM32_PIN(A, 13)
#undef PA14
#define PA14 _STM32_PIN(A, 14)
#undef PA15
#define PA15 _STM32_PIN(A, 15)
#undef PB0
#define PB0 _STM32_PIN(B, 0)
#undef PB1
#define PB1 _STM32_PIN(B, 1)
#undef PB2
#define PB2 _STM32_PIN(B, 2)
#undef PB3
#define PB3 _STM32_PIN(B, 3)
#undef PB4
#define PB4 _STM32_PIN(B, 4)
#undef PB5
#define PB5 _STM32_PIN(B, 5)
#undef PB6
#define PB6 _STM32_PIN(B, 6)
#undef PB7
#define PB7 _STM32_PIN(B, 7)
#undef PB8
#define PB8 _STM32_PIN(B, 8)
#undef PB9
#define PB9 _STM32_PIN(B, 9)
#undef PB10
#define PB10 _STM32_PIN(B, 10)
#undef PB11
#define PB11 _STM32_PIN(B, 11)
#undef PB12
#define PB12 _STM32_PIN(B, 12)
#undef PB13
#define PB13 _STM32_PIN(B, 13)
#undef PB14
#define PB14 _STM32_PIN(B, 14)
#undef PB15
#define PB15 _STM32_PIN(B, 15)
#undef PC0
#define PC0 _STM32_PIN(C, 0)
#undef PC1
#define PC1 _STM32_PIN(C, 1)
#undef PC2
#define PC2 _STM32_PIN(C, 2)
#undef PC3
#define PC3 _STM32_PIN(C, 3)
#undef PC4
#define PC4 _STM32_PIN(C, 4)
#undef PC5
#define PC5 _STM32_PIN(C, 5)
#undef PC6
#define PC6 _STM32_PIN(C, 6)
#undef PC7
#define PC7 _STM32_PIN(C, 7)
#undef PC8
#define PC8 _STM32_PIN(C, 8)
#undef PC9
#define PC9 _STM32_PIN(C, 9)
#undef PC10
#define PC10 _STM32_PIN(C, 10)
#undef PC11
#define PC11 _STM32_PIN(C, 11)
#undef PC12
#define PC12 _STM32_PIN(C, 12)
#undef PC13
#define PC13 _STM32_PIN(C, 13)
#undef PC14
#define PC14 _STM32_PIN(C, 14)
#undef PC15
#define PC15 _STM32_PIN(C, 15)
#undef PD0
#define PD0 _STM32_PIN(D, 0)
#undef PD1
#define PD1 _STM32_PIN(D, 1)
#undef PD2
#define PD2 _STM32_PIN(D, 2)
#undef PD3
#define PD3 _STM32_PIN(D, 3)
#undef PD4
#define PD4 _STM32_PIN(D, 4)
#undef PD5
#define PD5 _STM32_PIN(D, 5)
#undef PD6
#define PD6 _STM32_PIN(D, 6)
#undef PD7
#define PD7 _STM32_PIN(D, 7)
#undef PD8
#define PD8 _STM32_PIN(D, 8)
#undef PD9
#define PD9 _STM32_PIN(D, 9)
#undef PD10
#define PD10 _STM32_PIN(D, 10)
#undef PD11
#define PD11 _STM32_PIN(D, 11)
#undef PD12
#define PD12 _STM32_PIN(D, 12)
#undef PD13
#define PD13 _STM32_PIN(D, 13)
#undef PD14
#define PD14 _STM32_PIN(D, 14)
#undef PD15
#define PD15 _STM32_PIN(D, 15)
#undef PE0
#define PE0 _STM32_PIN(E, 0)
#undef PE1
#define PE1 _STM32_PIN(E, 1)
#undef PE2
#define PE2 _STM32_PIN(E, 2)
#undef PE3
#define PE3 _STM32_PIN(E, 3)
#undef PE4
#define PE4 _STM32_PIN(E, 4)
#undef PE5
#define PE5 _STM32_PIN(E, 5)
#undef PE6
#define PE6 _STM32_PIN(E, 6)
#undef PE7
#define PE7 _STM32_PIN(E, 7)
#undef PE8
#define PE8 _STM32_PIN(E, 8)
#undef PE9
#define PE9 _STM32_PIN(E, 9)
#undef PE10
#define PE10 _STM32_PIN(E, 10)
#undef PE11
#define PE11 _STM32_PIN(E, 11)
#undef PE12
#define PE12 _STM32_PIN(E, 12)
#undef PE13
#define PE13 _STM32_PIN(E, 13)
#undef PE14
#define PE14 _STM32_PIN(E, 14)
#undef PE15
#define PE15 _STM32_PIN(E, 15)
#ifdef STM32F7
#undef PORTF
#define PORTF 5
#undef PF0
#define PF0 _STM32_PIN(F, 0)
#undef PF1
#define PF1 _STM32_PIN(F, 1)
#undef PF2
#define PF2 _STM32_PIN(F, 2)
#undef PF3
#define PF3 _STM32_PIN(F, 3)
#undef PF4
#define PF4 _STM32_PIN(F, 4)
#undef PF5
#define PF5 _STM32_PIN(F, 5)
#undef PF6
#define PF6 _STM32_PIN(F, 6)
#undef PF7
#define PF7 _STM32_PIN(F, 7)
#undef PF8
#define PF8 _STM32_PIN(F, 8)
#undef PF9
#define PF9 _STM32_PIN(F, 9)
#undef PF10
#define PF10 _STM32_PIN(F, 10)
#undef PF11
#define PF11 _STM32_PIN(F, 11)
#undef PF12
#define PF12 _STM32_PIN(F, 12)
#undef PF13
#define PF13 _STM32_PIN(F, 13)
#undef PF14
#define PF14 _STM32_PIN(F, 14)
#undef PF15
#define PF15 _STM32_PIN(F, 15)
#undef PORTG
#define PORTG 6
#undef PG0
#define PG0 _STM32_PIN(G, 0)
#undef PG1
#define PG1 _STM32_PIN(G, 1)
#undef PG2
#define PG2 _STM32_PIN(G, 2)
#undef PG3
#define PG3 _STM32_PIN(G, 3)
#undef PG4
#define PG4 _STM32_PIN(G, 4)
#undef PG5
#define PG5 _STM32_PIN(G, 5)
#undef PG6
#define PG6 _STM32_PIN(G, 6)
#undef PG7
#define PG7 _STM32_PIN(G, 7)
#undef PG8
#define PG8 _STM32_PIN(G, 8)
#undef PG9
#define PG9 _STM32_PIN(G, 9)
#undef PG10
#define PG10 _STM32_PIN(G, 10)
#undef PG11
#define PG11 _STM32_PIN(G, 11)
#undef PG12
#define PG12 _STM32_PIN(G, 12)
#undef PG13
#define PG13 _STM32_PIN(G, 13)
#undef PG14
#define PG14 _STM32_PIN(G, 14)
#undef PG15
#define PG15 _STM32_PIN(G, 15)
#endif // STM32GENERIC && STM32F7

26
Marlin/src/HAL/STM32_F4_F7/inc/Conditionals_LCD.h

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

22
Marlin/src/HAL/STM32_F4_F7/inc/Conditionals_adv.h

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

29
Marlin/src/HAL/STM32_F4_F7/inc/Conditionals_post.h

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

41
Marlin/src/HAL/STM32_F4_F7/inc/SanityCheck.h

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

27
Marlin/src/HAL/STM32_F4_F7/pinsDebug.h

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

35
Marlin/src/HAL/STM32_F4_F7/spi_pins.h

@ -1,35 +0,0 @@
/**
* Marlin 3D Printer Firmware
* Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
*
* This program is free software: you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation, either version 3 of the License, or
* (at your option) any later version.
*
* This program is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with this program. If not, see <https://www.gnu.org/licenses/>.
*
*/
#pragma once
/**
* Define SPI Pins: SCK, MISO, MOSI, SS
*/
#ifndef SCK_PIN
#define SCK_PIN PA5
#endif
#ifndef MISO_PIN
#define MISO_PIN PA6
#endif
#ifndef MOSI_PIN
#define MOSI_PIN PA7
#endif
#ifndef SS_PIN
#define SS_PIN PA8
#endif

28
Marlin/src/HAL/STM32_F4_F7/timers.h

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

57
Marlin/src/HAL/STM32_F4_F7/watchdog.cpp

@ -1,57 +0,0 @@
/**
* Marlin 3D Printer Firmware
* Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
*
* Based on Sprinter and grbl.
* Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm
*
* This program is free software: you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation, either version 3 of the License, or
* (at your option) any later version.
*
* This program is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with this program. If not, see <https://www.gnu.org/licenses/>.
*
*/
#if defined(STM32GENERIC) && (defined(STM32F4) || defined(STM32F7))
#include "../../inc/MarlinConfig.h"
#if ENABLED(USE_WATCHDOG)
#include "watchdog.h"
#define WDT_TIMEOUT_COUNT TERN(WATCHDOG_DURATION_8S, 8192, 4096) // 4 or 8 second timeout
IWDG_HandleTypeDef hiwdg;
void watchdog_init() {
hiwdg.Instance = IWDG;
hiwdg.Init.Prescaler = IWDG_PRESCALER_32; // 32kHz LSI clock and 32x prescalar = 1024Hz IWDG clock
hiwdg.Init.Reload = WDT_TIMEOUT_COUNT - 1;
if (HAL_IWDG_Init(&hiwdg) != HAL_OK) {
//Error_Handler();
}
else {
#if PIN_EXISTS(LED) && DISABLED(PINS_DEBUGGING)
TOGGLE(LED_PIN); // heartbeat indicator
#endif
}
}
void HAL_watchdog_refresh() {
/* Refresh IWDG: reload counter */
if (HAL_IWDG_Refresh(&hiwdg) != HAL_OK) {
/* Refresh Error */
//Error_Handler();
}
}
#endif // USE_WATCHDOG
#endif // STM32GENERIC && (STM32F4 || STM32F7)

27
Marlin/src/HAL/STM32_F4_F7/watchdog.h

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

2
Marlin/src/HAL/platforms.h

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

11
Marlin/src/HAL/shared/backtrace/unwmemaccess.cpp

@ -74,17 +74,6 @@
#define START_FLASH_ADDR 0x08000000 #define START_FLASH_ADDR 0x08000000
#define END_FLASH_ADDR 0x08080000 #define END_FLASH_ADDR 0x08080000
#elif MB(THE_BORG)
// For STM32F765 in BORG
// SRAM (0x20000000 - 0x20080000) (512kb)
// FLASH (0x08000000 - 0x08100000) (1024kb)
//
#define START_SRAM_ADDR 0x20000000
#define END_SRAM_ADDR 0x20080000
#define START_FLASH_ADDR 0x08000000
#define END_FLASH_ADDR 0x08100000
#elif MB(REMRAM_V1, NUCLEO_F767ZI) #elif MB(REMRAM_V1, NUCLEO_F767ZI)
// For STM32F765VI in RemRam v1 // For STM32F765VI in RemRam v1

2
Marlin/src/HAL/shared/servo.h

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

50
Marlin/src/core/boards.h

@ -329,6 +329,7 @@
#define BOARD_TRIGORILLA_PRO 4037 // Trigorilla Pro (STM32F103ZET6) #define BOARD_TRIGORILLA_PRO 4037 // Trigorilla Pro (STM32F103ZET6)
#define BOARD_FLY_MINI 4038 // FLY MINI (STM32F103RCT6) #define BOARD_FLY_MINI 4038 // FLY MINI (STM32F103RCT6)
#define BOARD_FLSUN_HISPEED 4039 // FLSUN HiSpeedV1 (STM32F103VET6) #define BOARD_FLSUN_HISPEED 4039 // FLSUN HiSpeedV1 (STM32F103VET6)
#define BOARD_BEAST 4040 // STM32F103RET6 Libmaple-based controller
// //
// ARM Cortex-M4F // ARM Cortex-M4F
@ -341,37 +342,34 @@
// STM32 ARM Cortex-M4F // STM32 ARM Cortex-M4F
// //
#define BOARD_BEAST 4200 // STM32F4xxVxT6 Libmaple-based STM32F4 controller #define BOARD_ARMED 4200 // Arm'ed STM32F4-based controller
#define BOARD_GENERIC_STM32F4 4201 // STM32 STM32GENERIC-based STM32F4 controller #define BOARD_RUMBA32_V1_0 4201 // RUMBA32 STM32F446VET6 based controller from Aus3D
#define BOARD_ARMED 4202 // Arm'ed STM32F4-based controller #define BOARD_RUMBA32_V1_1 4202 // RUMBA32 STM32F446VET6 based controller from Aus3D
#define BOARD_RUMBA32_V1_0 4203 // RUMBA32 STM32F446VET6 based controller from Aus3D #define BOARD_RUMBA32_MKS 4203 // RUMBA32 STM32F446VET6 based controller from Makerbase
#define BOARD_RUMBA32_V1_1 4204 // RUMBA32 STM32F446VET6 based controller from Aus3D #define BOARD_BLACK_STM32F407VE 4204 // BLACK_STM32F407VE
#define BOARD_RUMBA32_MKS 4205 // RUMBA32 STM32F446VET6 based controller from Makerbase #define BOARD_BLACK_STM32F407ZE 4205 // BLACK_STM32F407ZE
#define BOARD_BLACK_STM32F407VE 4206 // BLACK_STM32F407VE #define BOARD_STEVAL_3DP001V1 4206 // STEVAL-3DP001V1 3D PRINTER BOARD
#define BOARD_BLACK_STM32F407ZE 4207 // BLACK_STM32F407ZE #define BOARD_BTT_SKR_PRO_V1_1 4207 // BigTreeTech SKR Pro v1.1 (STM32F407ZG)
#define BOARD_STEVAL_3DP001V1 4208 // STEVAL-3DP001V1 3D PRINTER BOARD #define BOARD_BTT_SKR_PRO_V1_2 4208 // BigTreeTech SKR Pro v1.2 (STM32F407ZG)
#define BOARD_BTT_SKR_PRO_V1_1 4209 // BigTreeTech SKR Pro v1.1 (STM32F407ZG) #define BOARD_BTT_BTT002_V1_0 4209 // BigTreeTech BTT002 v1.0 (STM32F407VG)
#define BOARD_BTT_SKR_PRO_V1_2 4210 // BigTreeTech SKR Pro v1.2 (STM32F407ZG) #define BOARD_BTT_GTR_V1_0 4210 // BigTreeTech GTR v1.0 (STM32F407IGT)
#define BOARD_BTT_BTT002_V1_0 4211 // BigTreeTech BTT002 v1.0 (STM32F407VG) #define BOARD_LERDGE_K 4211 // Lerdge K (STM32F407ZG)
#define BOARD_BTT_GTR_V1_0 4212 // BigTreeTech GTR v1.0 (STM32F407IGT) #define BOARD_LERDGE_S 4212 // Lerdge S (STM32F407VE)
#define BOARD_LERDGE_K 4213 // Lerdge K (STM32F407ZG) #define BOARD_LERDGE_X 4213 // Lerdge X (STM32F407VE)
#define BOARD_LERDGE_S 4214 // Lerdge S (STM32F407VE) #define BOARD_VAKE403D 4214 // VAkE 403D (STM32F446VET6)
#define BOARD_LERDGE_X 4215 // Lerdge X (STM32F407VE) #define BOARD_FYSETC_S6 4215 // FYSETC S6 board
#define BOARD_VAKE403D 4216 // VAkE 403D (STM32F446VET6) #define BOARD_FYSETC_S6_V2_0 4216 // FYSETC S6 v2.0 board
#define BOARD_FYSETC_S6 4217 // FYSETC S6 board #define BOARD_FLYF407ZG 4217 // FLYF407ZG board (STM32F407ZG)
#define BOARD_FYSETC_S6_V2_0 4218 // FYSETC S6 v2.0 board #define BOARD_MKS_ROBIN2 4218 // MKS_ROBIN2 (STM32F407ZE)
#define BOARD_FLYF407ZG 4219 // FLYF407ZG board (STM32F407ZG)
#define BOARD_MKS_ROBIN2 4220 // MKS_ROBIN2 (STM32F407ZE)
// //
// ARM Cortex M7 // ARM Cortex M7
// //
#define BOARD_THE_BORG 5000 // THE-BORG (Power outputs: Hotend0, Hotend1, Bed, Fan) #define BOARD_REMRAM_V1 5000 // RemRam v1
#define BOARD_REMRAM_V1 5001 // RemRam v1 #define BOARD_TEENSY41 5001 // Teensy 4.1
#define BOARD_TEENSY41 5002 // Teensy 4.1 #define BOARD_T41U5XBB 5002 // T41U5XBB Teensy 4.1 breakout board
#define BOARD_T41U5XBB 5003 // T41U5XBB Teensy 4.1 breakout board #define BOARD_NUCLEO_F767ZI 5003 // ST NUCLEO-F767ZI Dev Board
#define BOARD_NUCLEO_F767ZI 5004 // ST NUCLEO-F767ZI Dev Board
// //
// Espressif ESP32 WiFi // Espressif ESP32 WiFi

4
Marlin/src/core/macros.h

@ -61,11 +61,7 @@
#define _O3 __attribute__((optimize("O3"))) #define _O3 __attribute__((optimize("O3")))
#ifndef UNUSED #ifndef UNUSED
#if defined(ARDUINO_ARCH_STM32) && !defined(STM32GENERIC)
#define UNUSED(X) (void)X
#else
#define UNUSED(x) ((void)(x)) #define UNUSED(x) ((void)(x))
#endif
#endif #endif
// Clock speed factors // Clock speed factors

6
Marlin/src/module/stepper/TMC26X.h

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

18
Marlin/src/pins/pins.h

@ -594,6 +594,8 @@
#include "stm32f1/pins_FLY_MINI.h" // STM32F1 env:FLY_MINI #include "stm32f1/pins_FLY_MINI.h" // STM32F1 env:FLY_MINI
#elif MB(FLSUN_HISPEED) #elif MB(FLSUN_HISPEED)
#include "stm32f1/pins_FLSUN_HISPEED.h" // STM32F1 env:flsun_hispeed #include "stm32f1/pins_FLSUN_HISPEED.h" // STM32F1 env:flsun_hispeed
#elif MB(BEAST)
#include "stm32f1/pins_BEAST.h" // STM32F1 env:STM32F103RE
// //
// ARM Cortex-M4F // ARM Cortex-M4F
@ -608,10 +610,6 @@
// STM32 ARM Cortex-M4F // STM32 ARM Cortex-M4F
// //
#elif MB(BEAST)
#include "stm32f4/pins_BEAST.h" // STM32F4 env:STM32F4
#elif MB(GENERIC_STM32F4)
#include "stm32f4/pins_GENERIC_STM32F4.h" // STM32F4 env:STM32F4
#elif MB(ARMED) #elif MB(ARMED)
#include "stm32f4/pins_ARMED.h" // STM32F4 env:ARMED #include "stm32f4/pins_ARMED.h" // STM32F4 env:ARMED
#elif MB(RUMBA32_V1_0) #elif MB(RUMBA32_V1_0)
@ -633,13 +631,13 @@
#elif MB(BTT_BTT002_V1_0) #elif MB(BTT_BTT002_V1_0)
#include "stm32f4/pins_BTT_BTT002_V1_0.h" // STM32F4 env:BIGTREE_BTT002 #include "stm32f4/pins_BTT_BTT002_V1_0.h" // STM32F4 env:BIGTREE_BTT002
#elif MB(LERDGE_K) #elif MB(LERDGE_K)
#include "stm32f4/pins_LERDGE_K.h" // STM32F4 env:STM32F4 #include "stm32f4/pins_LERDGE_K.h" // STM32F4 env:LERDGEK
#elif MB(LERDGE_S) #elif MB(LERDGE_S)
#include "stm32f4/pins_LERDGE_S.h" // STM32F4 env:LERDGE_S #include "stm32f4/pins_LERDGE_S.h" // STM32F4 env:LERDGES
#elif MB(LERDGE_X) #elif MB(LERDGE_X)
#include "stm32f4/pins_LERDGE_X.h" // STM32F4 env:LERDGE_X #include "stm32f4/pins_LERDGE_X.h" // STM32F4 env:LERDGEX
#elif MB(VAKE403D) #elif MB(VAKE403D)
#include "stm32f4/pins_VAKE403D.h" // STM32F4 env:STM32F4 #include "stm32f4/pins_VAKE403D.h" // STM32F4
#elif MB(FYSETC_S6) #elif MB(FYSETC_S6)
#include "stm32f4/pins_FYSETC_S6.h" // STM32F4 env:FYSETC_S6 #include "stm32f4/pins_FYSETC_S6.h" // STM32F4 env:FYSETC_S6
#elif MB(FLYF407ZG) #elif MB(FLYF407ZG)
@ -653,10 +651,8 @@
// ARM Cortex M7 // ARM Cortex M7
// //
#elif MB(THE_BORG)
#include "stm32f7/pins_THE_BORG.h" // STM32F7 env:STM32F7
#elif MB(REMRAM_V1) #elif MB(REMRAM_V1)
#include "stm32f7/pins_REMRAM_V1.h" // STM32F7 env:STM32F7 #include "stm32f7/pins_REMRAM_V1.h" // STM32F7 env:REMRAM_V1
#elif MB(NUCLEO_F767ZI) #elif MB(NUCLEO_F767ZI)
#include "stm32f7/pins_NUCLEO_F767ZI.h" // STM32F7 env:NUCLEO_F767ZI #include "stm32f7/pins_NUCLEO_F767ZI.h" // STM32F7 env:NUCLEO_F767ZI
#elif MB(TEENSY41) #elif MB(TEENSY41)

4
Marlin/src/pins/stm32f4/pins_BEAST.h → Marlin/src/pins/stm32f1/pins_BEAST.h

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

197
Marlin/src/pins/stm32f4/pins_GENERIC_STM32F4.h

@ -1,197 +0,0 @@
/**
* Marlin 3D Printer Firmware
* Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
*
* Based on Sprinter and grbl.
* Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm
*
* This program is free software: you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation, either version 3 of the License, or
* (at your option) any later version.
*
* This program is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with this program. If not, see <https://www.gnu.org/licenses/>.
*
*/
#pragma once
/**
* To build with Arduino IDE use "Discovery F407VG"
* To build with PlatformIO use environment "STM32F4"
*/
#if NOT_TARGET(STM32F4, STM32F4xx)
#error "Oops! Select an STM32F4 board in 'Tools > Board.'"
#elif HOTENDS > 2 || E_STEPPERS > 2
#error "STM32F4 supports up to 2 hotends / E-steppers."
#endif
#define BOARD_INFO_NAME "Misc. STM32F4"
#define DEFAULT_MACHINE_NAME "STM32F407VET6"
//#define I2C_EEPROM
#ifndef MARLIN_EEPROM_SIZE
#define MARLIN_EEPROM_SIZE 0x1000 // 4KB
#endif
// Ignore temp readings during development.
//#define BOGUS_TEMPERATURE_GRACE_PERIOD 2000
//
// Limit Switches
//
#define X_MIN_PIN PE0
#define X_MAX_PIN -1
#define Y_MIN_PIN PE1
#define Y_MAX_PIN -1
#define Z_MIN_PIN PE14
#define Z_MAX_PIN -1
//
// Z Probe (when not Z_MIN_PIN)
//
//#ifndef Z_MIN_PROBE_PIN
// #define Z_MIN_PROBE_PIN PA4
//#endif
//
// Steppers
//
#define X_STEP_PIN PD3
#define X_DIR_PIN PD2
#define X_ENABLE_PIN PD0
//#ifndef X_CS_PIN
// #define X_CS_PIN PD1
//#endif
#define Y_STEP_PIN PE11
#define Y_DIR_PIN PE10
#define Y_ENABLE_PIN PE13
//#ifndef Y_CS_PIN
// #define Y_CS_PIN PE12
//#endif
#define Z_STEP_PIN PD6
#define Z_DIR_PIN PD7
#define Z_ENABLE_PIN PD4
//#ifndef Z_CS_PIN
// #define Z_CS_PIN PD5
//#endif
#define E0_STEP_PIN PB5
#define E0_DIR_PIN PB6
#define E0_ENABLE_PIN PB3
//#ifndef E0_CS_PIN
// #define E0_CS_PIN PB4
//#endif
#define E1_STEP_PIN PE4
#define E1_DIR_PIN PE2
#define E1_ENABLE_PIN PE3
//#ifndef E1_CS_PIN
// #define E1_CS_PIN PE5
//#endif
#define SCK_PIN PA5
#define MISO_PIN PA6
#define MOSI_PIN PA7
//
// Temperature Sensors
//
#define TEMP_0_PIN PC0 // Analog Input
#define TEMP_1_PIN PC1 // Analog Input
#define TEMP_BED_PIN PC2 // Analog Input
//
// Heaters / Fans
//
#define HEATER_0_PIN PA1
#define HEATER_1_PIN PA2
#define HEATER_BED_PIN PA0
#ifndef FAN_PIN
#define FAN_PIN PC6
#endif
#define FAN1_PIN PC7
#define FAN2_PIN PC8
#ifndef E0_AUTO_FAN_PIN
#define E0_AUTO_FAN_PIN PC7
#endif
//
// Misc. Functions
//
//#define CASE_LIGHT_PIN_CI PF13
//#define CASE_LIGHT_PIN_DO PF14
//#define NEOPIXEL_PIN PF13
//
// Průša i3 MK2 Multi Material Multiplexer Support
//
//#define E_MUX0_PIN PG3
//#define E_MUX1_PIN PG4
//
// Servos
//
//#define SERVO0_PIN PE13
//#define SERVO1_PIN PE14
#define SDSS PE7
#define SS_PIN PE7
#define LED_PIN PB7 //Alive
#define PS_ON_PIN PA10
#define KILL_PIN PA8
#define PWR_LOSS PA4 //Power loss / nAC_FAULT
//
// LCD / Controller
//
#define SD_DETECT_PIN PA15
#define BEEPER_PIN PC9
#define LCD_PINS_RS PE9
#define LCD_PINS_ENABLE PE8
#define LCD_PINS_D4 PB12
#define LCD_PINS_D5 PB13
#define LCD_PINS_D6 PB14
#define LCD_PINS_D7 PB15
#define BTN_EN1 PC4
#define BTN_EN2 PC5
#define BTN_ENC PC3
//
// Filament runout
//
#define FIL_RUNOUT_PIN PA3
//
// ST7920 Delays
//
#if HAS_MARLINUI_U8GLIB
#ifndef BOARD_ST7920_DELAY_1
#define BOARD_ST7920_DELAY_1 DELAY_NS(96)
#endif
#ifndef BOARD_ST7920_DELAY_2
#define BOARD_ST7920_DELAY_2 DELAY_NS(48)
#endif
#ifndef BOARD_ST7920_DELAY_3
#define BOARD_ST7920_DELAY_3 DELAY_NS(715)
#endif
#endif

183
Marlin/src/pins/stm32f7/pins_THE_BORG.h

@ -1,183 +0,0 @@
/**
* Marlin 3D Printer Firmware
* Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
*
* Based on Sprinter and grbl.
* Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm
*
* This program is free software: you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation, either version 3 of the License, or
* (at your option) any later version.
*
* This program is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with this program. If not, see <https://www.gnu.org/licenses/>.
*
*/
#pragma once
#if NOT_TARGET(STM32F7)
#error "Oops! Select an STM32F7 board in 'Tools > Board.'"
#elif HOTENDS > 3 || E_STEPPERS > 3
#error "The-Borg supports up to 3 hotends / E-steppers."
#endif
#define BOARD_INFO_NAME "The-Borge"
#define DEFAULT_MACHINE_NAME BOARD_INFO_NAME
#ifndef MARLIN_EEPROM_SIZE
#define MARLIN_EEPROM_SIZE 0x1000
#endif
// Ignore temp readings during development.
//#define BOGUS_TEMPERATURE_GRACE_PERIOD 2000
//
// Limit Switches
//
#define X_MIN_PIN PE9
#define X_MAX_PIN PE10
#define Y_MIN_PIN PE7
#define Y_MAX_PIN PE8
#define Z_MIN_PIN PF15
#define Z_MAX_PIN PG0
#define E_MIN_PIN PE2
#define E_MAX_PIN PE3
//
// Z Probe (when not Z_MIN_PIN)
//
#ifndef Z_MIN_PROBE_PIN
#define Z_MIN_PROBE_PIN PA4
#endif
//
// Steppers
//
#define STEPPER_ENABLE_PIN PE0
#define X_STEP_PIN PC6 // 96, 39 in Arduino
#define X_DIR_PIN PC7
#define X_ENABLE_PIN PC8
#define Y_STEP_PIN PD9
#define Y_DIR_PIN PD10
#define Y_ENABLE_PIN PD11
#define Z_STEP_PIN PE15
#define Z_DIR_PIN PG1
#define Z_ENABLE_PIN PD8
#define E0_STEP_PIN PB1
#define E0_DIR_PIN PB2
#define E0_ENABLE_PIN PE11
#define E1_STEP_PIN PC4
#define E1_DIR_PIN PC5
#define E1_ENABLE_PIN PB0
#define E2_STEP_PIN PC13
#define E2_DIR_PIN PC14
#define E2_ENABLE_PIN PC15
#define Z2_STEP_PIN PC13
#define Z2_DIR_PIN PC14
#define Z2_ENABLE_PIN PC15
#define SCK_PIN PA5
#define MISO_PIN PA6
#define MOSI_PIN PA7
#define SPI1_SCK_PIN PA5
#define SPI1_MISO_PIN PA6
#define SPI1_MOSI_PIN PA7
#define SPI6_SCK_PIN PG13
#define SPI6_MISO_PIN PG12
#define SPI6_MOSI_PIN PG14
//
// Temperature Sensors
//
#define TEMP_0_PIN PC3 // Analog Input
#define TEMP_1_PIN PC2 // Analog Input
#define TEMP_2_PIN PC1 // Analog Input
#define TEMP_3_PIN PC0 // Analog Input
#define TEMP_BED_PIN PF10 // Analog Input
#define TEMP_5_PIN PE12 // Analog Input, Probe temp
//
// Heaters / Fans
//
#define HEATER_0_PIN PD15
#define HEATER_1_PIN PD14
#define HEATER_BED_PIN PF6
#ifndef FAN_PIN
#define FAN_PIN PD13
#endif
#define FAN1_PIN PA0
#define FAN2_PIN PA1
#ifndef E0_AUTO_FAN_PIN
#define E0_AUTO_FAN_PIN PA1
#endif
//
// Misc. Functions
//
//#define CASE_LIGHT_PIN_CI PF13
//#define CASE_LIGHT_PIN_DO PF14
//#define NEOPIXEL_PIN PF13
//
// Průša i3 MK2 Multi Material Multiplexer Support
//
#define E_MUX0_PIN PG3
#define E_MUX1_PIN PG4
//
// Servos
//
#define SERVO0_PIN PE13
#define SERVO1_PIN PE14
#define SDSS PA8
#define SS_PIN PA8
#define LED_PIN PA2 // Alive
#define PS_ON_PIN PA3
#define KILL_PIN -1 //PD5 // EXP2-10
#define PWR_LOSS PG5 // Power loss / nAC_FAULT
//
// MAX7219_DEBUG
//
#define MAX7219_CLK_PIN PG10 // EXP1-1
#define MAX7219_DIN_PIN PD7 // EXP1-3
#define MAX7219_LOAD_PIN PD1 // EXP1-5
//
// LCD / Controller
//
//#define SD_DETECT_PIN -1 //PB6) // EXP2-4
#define BEEPER_PIN PG10 // EXP1-1
#define LCD_PINS_RS PG9 // EXP1-4
#define LCD_PINS_ENABLE PD7 // EXP1-3
#define LCD_PINS_D4 PD1 // EXP1-5
#define LCD_PINS_D5 PF0 // EXP1-6
#define LCD_PINS_D6 PD3 // EXP1-7
#define LCD_PINS_D7 PD4 // EXP1-8
#define BTN_EN1 PD6 // EXP2-5
#define BTN_EN2 PD0 // EXP2-3
#define BTN_ENC PG11 // EXP1-2

2
buildroot/tests/BIGTREE_SKR_PRO-tests

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

2
buildroot/tests/STM32F7-tests → buildroot/tests/REMRAM_V1-tests

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

1
buildroot/tests/STM32F103RC_btt-tests

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

16
buildroot/tests/STM32F4-tests

@ -1,16 +0,0 @@
#!/usr/bin/env bash
#
# Build tests for STM32F4 disco_f407vg
#
# exit on first failure
set -e
#
# Build with the default configurations
#
use_example_configs STM32/STM32F4
exec_test $1 $2 "STM32F4 Default Configuration" "$3"
# clean up
restore_configs

17
platformio.ini

@ -863,22 +863,13 @@ lib_deps = ${common_stm32f1.lib_deps}
USBComposite for STM32F1@0.91 USBComposite for STM32F1@0.91
# #
# STM32F4 with STM32GENERIC # REMRAM_V1
# #
[env:STM32F4] [env:REMRAM_V1]
platform = ${common_stm32.platform}
board = disco_f407vg
build_flags = ${common.build_flags} -DUSE_STM32GENERIC -DSTM32GENERIC -DSTM32F4 -DMENU_USB_SERIAL -DMENU_SERIAL=SerialUSB -DHAL_IWDG_MODULE_ENABLED
src_filter = ${common.default_src_filter} +<src/HAL/STM32_F4_F7> -<src/HAL/STM32_F4_F7/STM32F7>
#
# STM32F7 with STM32GENERIC
#
[env:STM32F7]
platform = ${common_stm32.platform} platform = ${common_stm32.platform}
extends = common_stm32
board = remram_v1 board = remram_v1
build_flags = ${common.build_flags} -DUSE_STM32GENERIC -DSTM32GENERIC -DSTM32F7 -DMENU_USB_SERIAL -DMENU_SERIAL=SerialUSB -DHAL_IWDG_MODULE_ENABLED build_flags = ${common_stm32.build_flags}
src_filter = ${common.default_src_filter} +<src/HAL/STM32_F4_F7> -<src/HAL/STM32_F4_F7/STM32F4>
# #
# ST NUCLEO-F767ZI Development Board # ST NUCLEO-F767ZI Development Board

Loading…
Cancel
Save