From 315cb6d001a4c5a9f7ba30831f97565518a13ad9 Mon Sep 17 00:00:00 2001 From: thinkyhead Date: Mon, 23 Nov 2020 00:11:32 +0000 Subject: [PATCH 01/47] [cron] Bump distribution date (2020-11-23) --- Marlin/src/inc/Version.h | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/Marlin/src/inc/Version.h b/Marlin/src/inc/Version.h index 213b389e1635..73897eed0e17 100644 --- a/Marlin/src/inc/Version.h +++ b/Marlin/src/inc/Version.h @@ -42,7 +42,7 @@ * version was tagged. */ #ifndef STRING_DISTRIBUTION_DATE - #define STRING_DISTRIBUTION_DATE "2020-11-22" + #define STRING_DISTRIBUTION_DATE "2020-11-23" #endif /** From 9dedd121bf789b5289380978979e2aed5ce58b38 Mon Sep 17 00:00:00 2001 From: Jason Smith Date: Sun, 22 Nov 2020 16:20:33 -0800 Subject: [PATCH 02/47] Fix UBL manual mesh adjust behavior (#20248) --- Marlin/src/feature/bedlevel/ubl/ubl_G29.cpp | 4 +--- 1 file changed, 1 insertion(+), 3 deletions(-) diff --git a/Marlin/src/feature/bedlevel/ubl/ubl_G29.cpp b/Marlin/src/feature/bedlevel/ubl/ubl_G29.cpp index e8524da36886..94bec99194b7 100644 --- a/Marlin/src/feature/bedlevel/ubl/ubl_G29.cpp +++ b/Marlin/src/feature/bedlevel/ubl/ubl_G29.cpp @@ -949,7 +949,7 @@ g29_repetition_cnt = 1; // do exactly one mesh location. Otherwise use what the parser decided. #if ENABLED(UBL_MESH_EDIT_MOVES_Z) - const float h_offset = parser.seenval('H') ? parser.value_linear_units() : 0; + const float h_offset = parser.seenval('H') ? parser.value_linear_units() : MANUAL_PROBE_START_Z; if (!WITHIN(h_offset, 0, 10)) { SERIAL_ECHOLNPGM("Offset out of bounds. (0 to 10mm)\n"); return; @@ -970,8 +970,6 @@ do_blocking_move_to_xy_z(pos, Z_CLEARANCE_BETWEEN_PROBES); // Move to the given XY with probe clearance - TERN_(UBL_MESH_EDIT_MOVES_Z, do_blocking_move_to_z(h_offset)); // Move Z to the given 'H' offset - MeshFlags done_flags{0}; const xy_int8_t &lpos = location.pos; do { From 6f272e13c5ce132c0bd7fdc2401ceadad5f3b06c Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Sun, 22 Nov 2020 18:44:17 -0600 Subject: [PATCH 03/47] Allow Status Message without LCD (#20246) --- Marlin/src/gcode/temp/M303.cpp | 2 +- Marlin/src/inc/Conditionals_LCD.h | 4 + Marlin/src/lcd/marlinui.cpp | 213 ++++++++++++++++-------------- Marlin/src/lcd/marlinui.h | 47 +++---- 4 files changed, 143 insertions(+), 123 deletions(-) diff --git a/Marlin/src/gcode/temp/M303.cpp b/Marlin/src/gcode/temp/M303.cpp index 52e34fc47357..a066ddc88df5 100644 --- a/Marlin/src/gcode/temp/M303.cpp +++ b/Marlin/src/gcode/temp/M303.cpp @@ -77,7 +77,7 @@ void GcodeSuite::M303() { KEEPALIVE_STATE(NOT_BUSY); #endif - ui.set_status_P(GET_TEXT(MSG_PID_AUTOTUNE)); + LCD_MESSAGEPGM(MSG_PID_AUTOTUNE); thermalManager.PID_autotune(temp, e, c, u); ui.reset_status(); } diff --git a/Marlin/src/inc/Conditionals_LCD.h b/Marlin/src/inc/Conditionals_LCD.h index 952ff2bbd6f9..9c080ee2869d 100644 --- a/Marlin/src/inc/Conditionals_LCD.h +++ b/Marlin/src/inc/Conditionals_LCD.h @@ -472,6 +472,10 @@ #endif #endif +#if EITHER(HAS_DISPLAY, GLOBAL_STATUS_MESSAGE) + #define HAS_STATUS_MESSAGE 1 +#endif + #if IS_ULTIPANEL && DISABLED(NO_LCD_MENUS) #define HAS_LCD_MENU 1 #endif diff --git a/Marlin/src/lcd/marlinui.cpp b/Marlin/src/lcd/marlinui.cpp index acf35afb1807..241d3a171213 100644 --- a/Marlin/src/lcd/marlinui.cpp +++ b/Marlin/src/lcd/marlinui.cpp @@ -1332,59 +1332,16 @@ void MarlinUI::update() { #endif // HAS_WIRED_LCD -#if HAS_DISPLAY - - #if ENABLED(EXTENSIBLE_UI) - #include "extui/ui_api.h" - #endif +#if HAS_STATUS_MESSAGE //////////////////////////////////////////// - /////////////// Status Line //////////////// + ////////////// Status Message ////////////// //////////////////////////////////////////// - #if ENABLED(STATUS_MESSAGE_SCROLLING) - void MarlinUI::advance_status_scroll() { - // Advance by one UTF8 code-word - if (status_scroll_offset < utf8_strlen(status_message)) - while (!START_OF_UTF8_CHAR(status_message[++status_scroll_offset])); - else - status_scroll_offset = 0; - } - char* MarlinUI::status_and_len(uint8_t &len) { - char *out = status_message + status_scroll_offset; - len = utf8_strlen(out); - return out; - } + #if ENABLED(EXTENSIBLE_UI) + #include "extui/ui_api.h" #endif - void MarlinUI::finish_status(const bool persist) { - - #if !(ENABLED(LCD_PROGRESS_BAR) && (PROGRESS_MSG_EXPIRE) > 0) - UNUSED(persist); - #endif - - #if ENABLED(LCD_PROGRESS_BAR) || BOTH(FILAMENT_LCD_DISPLAY, SDSUPPORT) - const millis_t ms = millis(); - #endif - - #if ENABLED(LCD_PROGRESS_BAR) && !IS_TFTGLCD_PANEL - progress_bar_ms = ms; - #if PROGRESS_MSG_EXPIRE > 0 - expire_status_ms = persist ? 0 : ms + PROGRESS_MSG_EXPIRE; - #endif - #endif - - #if BOTH(FILAMENT_LCD_DISPLAY, SDSUPPORT) - next_filament_display = ms + 5000UL; // Show status message for 5s - #endif - - #if BOTH(HAS_WIRED_LCD, STATUS_MESSAGE_SCROLLING) - status_scroll_offset = 0; - #endif - - TERN_(EXTENSIBLE_UI, ExtUI::onStatusChanged(status_message)); - } - bool MarlinUI::has_status() { return (status_message[0] != '\0'); } void MarlinUI::set_status(const char * const message, const bool persist) { @@ -1414,16 +1371,45 @@ void MarlinUI::update() { finish_status(persist); } - #include + /** + * Reset the status message + */ + void MarlinUI::reset_status(const bool no_welcome) { + #if SERVICE_INTERVAL_1 > 0 + static PGMSTR(service1, "> " SERVICE_NAME_1 "!"); + #endif + #if SERVICE_INTERVAL_2 > 0 + static PGMSTR(service2, "> " SERVICE_NAME_2 "!"); + #endif + #if SERVICE_INTERVAL_3 > 0 + static PGMSTR(service3, "> " SERVICE_NAME_3 "!"); + #endif + PGM_P msg; + if (printingIsPaused()) + msg = GET_TEXT(MSG_PRINT_PAUSED); + #if ENABLED(SDSUPPORT) + else if (IS_SD_PRINTING()) + return set_status(card.longest_filename(), true); + #endif + else if (print_job_timer.isRunning()) + msg = GET_TEXT(MSG_PRINTING); - void MarlinUI::status_printf_P(const uint8_t level, PGM_P const fmt, ...) { - if (level < alert_level) return; - alert_level = level; - va_list args; - va_start(args, fmt); - vsnprintf_P(status_message, MAX_MESSAGE_LENGTH, fmt, args); - va_end(args); - finish_status(level > 0); + #if SERVICE_INTERVAL_1 > 0 + else if (print_job_timer.needsService(1)) msg = service1; + #endif + #if SERVICE_INTERVAL_2 > 0 + else if (print_job_timer.needsService(2)) msg = service2; + #endif + #if SERVICE_INTERVAL_3 > 0 + else if (print_job_timer.needsService(3)) msg = service3; + #endif + + else if (!no_welcome) + msg = GET_TEXT(WELCOME_MSG); + else + return; + + set_status_P(msg, -1); } void MarlinUI::set_status_P(PGM_P const message, int8_t level) { @@ -1459,51 +1445,76 @@ void MarlinUI::update() { TERN_(HAS_LCD_MENU, return_to_status()); } - PGM_P print_paused = GET_TEXT(MSG_PRINT_PAUSED); + #include - /** - * Reset the status message - */ - void MarlinUI::reset_status(const bool no_welcome) { - PGM_P printing = GET_TEXT(MSG_PRINTING); - PGM_P welcome = GET_TEXT(WELCOME_MSG); - #if SERVICE_INTERVAL_1 > 0 - static PGMSTR(service1, "> " SERVICE_NAME_1 "!"); - #endif - #if SERVICE_INTERVAL_2 > 0 - static PGMSTR(service2, "> " SERVICE_NAME_2 "!"); - #endif - #if SERVICE_INTERVAL_3 > 0 - static PGMSTR(service3, "> " SERVICE_NAME_3 "!"); - #endif - PGM_P msg; - if (printingIsPaused()) - msg = print_paused; - #if ENABLED(SDSUPPORT) - else if (IS_SD_PRINTING()) - return set_status(card.longest_filename(), true); - #endif - else if (print_job_timer.isRunning()) - msg = printing; + void MarlinUI::status_printf_P(const uint8_t level, PGM_P const fmt, ...) { + if (level < alert_level) return; + alert_level = level; + va_list args; + va_start(args, fmt); + vsnprintf_P(status_message, MAX_MESSAGE_LENGTH, fmt, args); + va_end(args); + finish_status(level > 0); + } - #if SERVICE_INTERVAL_1 > 0 - else if (print_job_timer.needsService(1)) msg = service1; - #endif - #if SERVICE_INTERVAL_2 > 0 - else if (print_job_timer.needsService(2)) msg = service2; - #endif - #if SERVICE_INTERVAL_3 > 0 - else if (print_job_timer.needsService(3)) msg = service3; - #endif + void MarlinUI::finish_status(const bool persist) { - else if (!no_welcome) - msg = welcome; - else - return; + #if HAS_SPI_LCD - set_status_P(msg, -1); + #if !(ENABLED(LCD_PROGRESS_BAR) && (PROGRESS_MSG_EXPIRE) > 0) + UNUSED(persist); + #endif + + #if ENABLED(LCD_PROGRESS_BAR) || BOTH(FILAMENT_LCD_DISPLAY, SDSUPPORT) + const millis_t ms = millis(); + #endif + + #if ENABLED(LCD_PROGRESS_BAR) + progress_bar_ms = ms; + #if PROGRESS_MSG_EXPIRE > 0 + expire_status_ms = persist ? 0 : ms + PROGRESS_MSG_EXPIRE; + #endif + #endif + + #if BOTH(FILAMENT_LCD_DISPLAY, SDSUPPORT) + next_filament_display = ms + 5000UL; // Show status message for 5s + #endif + + #if ENABLED(STATUS_MESSAGE_SCROLLING) + status_scroll_offset = 0; + #endif + + #endif + + TERN_(EXTENSIBLE_UI, ExtUI::onStatusChanged(status_message)); } + #if ENABLED(STATUS_MESSAGE_SCROLLING) + + void MarlinUI::advance_status_scroll() { + // Advance by one UTF8 code-word + if (status_scroll_offset < utf8_strlen(status_message)) + while (!START_OF_UTF8_CHAR(status_message[++status_scroll_offset])); + else + status_scroll_offset = 0; + } + + char* MarlinUI::status_and_len(uint8_t &len) { + char *out = status_message + status_scroll_offset; + len = utf8_strlen(out); + return out; + } + + #endif + +#endif + +#if HAS_DISPLAY + + #if ENABLED(SDSUPPORT) + extern bool wait_for_user, wait_for_heatup; + #endif + void MarlinUI::abort_print() { #if ENABLED(SDSUPPORT) wait_for_heatup = wait_for_user = false; @@ -1514,7 +1525,7 @@ void MarlinUI::update() { #endif TERN_(HOST_PROMPT_SUPPORT, host_prompt_open(PROMPT_INFO, PSTR("UI Aborted"), DISMISS_STR)); print_job_timer.stop(); - set_status_P(GET_TEXT(MSG_PRINT_ABORTED)); + LCD_MESSAGEPGM(MSG_PRINT_ABORTED); TERN_(HAS_LCD_MENU, return_to_status()); } @@ -1530,7 +1541,7 @@ void MarlinUI::update() { TERN_(HOST_PROMPT_SUPPORT, host_prompt_open(PROMPT_PAUSE_RESUME, PSTR("UI Pause"), PSTR("Resume"))); - set_status_P(print_paused); + LCD_MESSAGEPGM(MSG_PRINT_PAUSED); #if ENABLED(PARK_HEAD_ON_PAUSE) TERN_(HAS_WIRED_LCD, lcd_pause_show_message(PAUSE_MESSAGE_PARKING, PAUSE_MODE_PAUSE_PRINT)); // Show message immediately to let user know about pause in progress @@ -1615,6 +1626,10 @@ void MarlinUI::update() { #if ENABLED(SDSUPPORT) + #if ENABLED(EXTENSIBLE_UI) + #include "extui/ui_api.h" + #endif + void MarlinUI::media_changed(const uint8_t old_status, const uint8_t status) { if (old_status == status) { TERN_(EXTENSIBLE_UI, ExtUI::onMediaError()); // Failed to mount/unmount @@ -1629,7 +1644,7 @@ void MarlinUI::update() { quick_feedback(); goto_screen(MEDIA_MENU_GATEWAY); #else - set_status_P(GET_TEXT(MSG_MEDIA_INSERTED)); + LCD_MESSAGEPGM(MSG_MEDIA_INSERTED); #endif } } @@ -1637,7 +1652,7 @@ void MarlinUI::update() { if (old_status < 2) { TERN_(EXTENSIBLE_UI, ExtUI::onMediaRemoved()); // ExtUI response #if PIN_EXISTS(SD_DETECT) - set_status_P(GET_TEXT(MSG_MEDIA_REMOVED)); + LCD_MESSAGEPGM(MSG_MEDIA_REMOVED); #if HAS_LCD_MENU if (!defer_return_to_status) return_to_status(); #endif diff --git a/Marlin/src/lcd/marlinui.h b/Marlin/src/lcd/marlinui.h index 3311f55ed575..ccf995bd7131 100644 --- a/Marlin/src/lcd/marlinui.h +++ b/Marlin/src/lcd/marlinui.h @@ -373,17 +373,9 @@ class MarlinUI { static constexpr uint8_t get_progress_percent() { return 0; } #endif - #if HAS_DISPLAY - - static void init(); - static void update(); - static void set_alert_status_P(PGM_P const message); - + #if HAS_STATUS_MESSAGE static char status_message[]; - static bool has_status(); - static uint8_t alert_level; // Higher levels block lower levels - static inline void reset_alert_level() { alert_level = 0; } #if ENABLED(STATUS_MESSAGE_SCROLLING) static uint8_t status_scroll_offset; @@ -391,6 +383,28 @@ class MarlinUI { static char* status_and_len(uint8_t &len); #endif + static bool has_status(); + static void reset_status(const bool no_welcome=false); + static void set_status(const char* const message, const bool persist=false); + static void set_status_P(PGM_P const message, const int8_t level=0); + static void status_printf_P(const uint8_t level, PGM_P const fmt, ...); + static void set_alert_status_P(PGM_P const message); + static inline void reset_alert_level() { alert_level = 0; } + #else + static constexpr bool has_status() { return false; } + static inline void reset_status(const bool=false) {} + static void set_status(const char* message, const bool=false); + static void set_status_P(PGM_P message, const int8_t=0); + static void status_printf_P(const uint8_t, PGM_P message, ...); + static inline void set_alert_status_P(PGM_P const) {} + static inline void reset_alert_level() {} + #endif + + #if HAS_DISPLAY + + static void init(); + static void update(); + static void abort_print(); static void pause_print(); static void resume_print(); @@ -481,25 +495,12 @@ class MarlinUI { static bool get_blink(); static void kill_screen(PGM_P const lcd_error, PGM_P const lcd_component); static void draw_kill_screen(); - static void set_status(const char* const message, const bool persist=false); - static void set_status_P(PGM_P const message, const int8_t level=0); - static void status_printf_P(const uint8_t level, PGM_P const fmt, ...); - static void reset_status(const bool no_welcome=false); #else // No LCD - // Send status to host as a notification - static void set_status(const char* message, const bool=false); - static void set_status_P(PGM_P message, const int8_t=0); - static void status_printf_P(const uint8_t, PGM_P message, ...); - static inline void init() {} static inline void update() {} static inline void return_to_status() {} - static inline void set_alert_status_P(PGM_P const) {} - static inline void reset_status(const bool=false) {} - static inline void reset_alert_level() {} - static constexpr bool has_status() { return false; } #endif @@ -702,7 +703,7 @@ class MarlinUI { private: - #if HAS_DISPLAY + #if HAS_STATUS_MESSAGE static void finish_status(const bool persist); #endif From 58eaad703a5e369ab3bf6a1d325b8775d89ede0d Mon Sep 17 00:00:00 2001 From: Jason Smith Date: Sun, 22 Nov 2020 16:47:52 -0800 Subject: [PATCH 04/47] Fix dummy thermistors for Bed, Chamber, Probe (#20247) --- Marlin/src/inc/Conditionals_post.h | 15 +++++++++++---- Marlin/src/module/temperature.cpp | 18 +++++++++--------- Marlin/src/module/temperature.h | 6 +++--- 3 files changed, 23 insertions(+), 16 deletions(-) diff --git a/Marlin/src/inc/Conditionals_post.h b/Marlin/src/inc/Conditionals_post.h index 4f4787855cbf..35fd92e10b76 100644 --- a/Marlin/src/inc/Conditionals_post.h +++ b/Marlin/src/inc/Conditionals_post.h @@ -1774,12 +1774,19 @@ #define HAS_TEMP_ADC_CHAMBER 1 #endif -#if HAS_HOTEND && ANY(HAS_TEMP_ADC_0, HEATER_0_USES_MAX6675, HEATER_0_DUMMY_THERMISTOR) +#define HAS_TEMP(N) ANY(HAS_TEMP_ADC_##N, HEATER_##N##_USES_MAX6675, HEATER_##N##_DUMMY_THERMISTOR) +#if HAS_HOTEND && HAS_TEMP(0) #define HAS_TEMP_HOTEND 1 #endif -#define HAS_TEMP_BED HAS_TEMP_ADC_BED -#define HAS_TEMP_PROBE HAS_TEMP_ADC_PROBE -#define HAS_TEMP_CHAMBER HAS_TEMP_ADC_CHAMBER +#if HAS_TEMP(BED) + #define HAS_TEMP_BED 1 +#endif +#if HAS_TEMP(PROBE) + #define HAS_TEMP_PROBE 1 +#endif +#if HAS_TEMP(CHAMBER) + #define HAS_TEMP_CHAMBER 1 +#endif #if ENABLED(JOYSTICK) #if PIN_EXISTS(JOY_X) diff --git a/Marlin/src/module/temperature.cpp b/Marlin/src/module/temperature.cpp index d9ce6e151e62..d704ebc85bfd 100644 --- a/Marlin/src/module/temperature.cpp +++ b/Marlin/src/module/temperature.cpp @@ -1839,13 +1839,13 @@ void Temperature::init() { #if HAS_JOY_ADC_EN SET_INPUT_PULLUP(JOY_EN_PIN); #endif - #if HAS_HEATED_BED + #if HAS_TEMP_ADC_BED HAL_ANALOG_SELECT(TEMP_BED_PIN); #endif - #if HAS_TEMP_CHAMBER + #if HAS_TEMP_ADC_CHAMBER HAL_ANALOG_SELECT(TEMP_CHAMBER_PIN); #endif - #if HAS_TEMP_PROBE + #if HAS_TEMP_ADC_PROBE HAL_ANALOG_SELECT(TEMP_PROBE_PIN); #endif #if ENABLED(FILAMENT_WIDTH_SENSOR) @@ -2355,9 +2355,9 @@ void Temperature::update_raw_temperatures() { TERN_(HAS_TEMP_ADC_5, temp_hotend[5].update()); TERN_(HAS_TEMP_ADC_6, temp_hotend[6].update()); TERN_(HAS_TEMP_ADC_7, temp_hotend[7].update()); - TERN_(HAS_HEATED_BED, temp_bed.update()); - TERN_(HAS_TEMP_CHAMBER, temp_chamber.update()); - TERN_(HAS_TEMP_PROBE, temp_probe.update()); + TERN_(HAS_TEMP_ADC_BED, temp_bed.update()); + TERN_(HAS_TEMP_ADC_CHAMBER, temp_chamber.update()); + TERN_(HAS_TEMP_ADC_PROBE, temp_probe.update()); TERN_(HAS_JOY_ADC_X, joystick.x.update()); TERN_(HAS_JOY_ADC_Y, joystick.y.update()); @@ -2822,17 +2822,17 @@ void Temperature::tick() { case MeasureTemp_0: ACCUMULATE_ADC(temp_hotend[0]); break; #endif - #if HAS_HEATED_BED + #if HAS_TEMP_ADC_BED case PrepareTemp_BED: HAL_START_ADC(TEMP_BED_PIN); break; case MeasureTemp_BED: ACCUMULATE_ADC(temp_bed); break; #endif - #if HAS_TEMP_CHAMBER + #if HAS_TEMP_ADC_CHAMBER case PrepareTemp_CHAMBER: HAL_START_ADC(TEMP_CHAMBER_PIN); break; case MeasureTemp_CHAMBER: ACCUMULATE_ADC(temp_chamber); break; #endif - #if HAS_TEMP_PROBE + #if HAS_TEMP_ADC_PROBE case PrepareTemp_PROBE: HAL_START_ADC(TEMP_PROBE_PIN); break; case MeasureTemp_PROBE: ACCUMULATE_ADC(temp_probe); break; #endif diff --git a/Marlin/src/module/temperature.h b/Marlin/src/module/temperature.h index edaa1c53843a..33f38c303608 100644 --- a/Marlin/src/module/temperature.h +++ b/Marlin/src/module/temperature.h @@ -89,13 +89,13 @@ enum ADCSensorState : char { #if HAS_TEMP_ADC_0 PrepareTemp_0, MeasureTemp_0, #endif - #if HAS_HEATED_BED + #if HAS_TEMP_ADC_BED PrepareTemp_BED, MeasureTemp_BED, #endif - #if HAS_TEMP_CHAMBER + #if HAS_TEMP_ADC_CHAMBER PrepareTemp_CHAMBER, MeasureTemp_CHAMBER, #endif - #if HAS_TEMP_PROBE + #if HAS_TEMP_ADC_PROBE PrepareTemp_PROBE, MeasureTemp_PROBE, #endif #if HAS_TEMP_ADC_1 From a4e1132048ae980185c87b9bcee58fa87ad8fd36 Mon Sep 17 00:00:00 2001 From: Jason Smith Date: Mon, 23 Nov 2020 03:07:43 -0800 Subject: [PATCH 05/47] Fix Z4 in ENABLE/DISABLE_AXIS_Z (#20256) This was accidentally broken in PR #20218 --- Marlin/src/module/stepper/indirection.h | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/Marlin/src/module/stepper/indirection.h b/Marlin/src/module/stepper/indirection.h index 04cebc216fec..d14bfc7329c8 100644 --- a/Marlin/src/module/stepper/indirection.h +++ b/Marlin/src/module/stepper/indirection.h @@ -859,8 +859,8 @@ void reset_stepper_drivers(); // Called by settings.load / settings.reset #define DISABLE_AXIS_X() if (SHOULD_DISABLE(x)) { DISABLE_STEPPER_X(); DISABLE_STEPPER_X2(); AFTER_CHANGE(x, false); FORGET_AXIS(X_AXIS); } #define ENABLE_AXIS_Y() if (SHOULD_ENABLE(y)) { ENABLE_STEPPER_Y(); ENABLE_STEPPER_Y2(); AFTER_CHANGE(y, true); } #define DISABLE_AXIS_Y() if (SHOULD_DISABLE(y)) { DISABLE_STEPPER_Y(); DISABLE_STEPPER_Y2(); AFTER_CHANGE(y, false); FORGET_AXIS(Y_AXIS); } -#define ENABLE_AXIS_Z() if (SHOULD_ENABLE(z)) { ENABLE_STEPPER_Z(); ENABLE_STEPPER_Z2(); ENABLE_STEPPER_Z3(); AFTER_CHANGE(z, true); } -#define DISABLE_AXIS_Z() if (SHOULD_DISABLE(z)) { DISABLE_STEPPER_Z(); DISABLE_STEPPER_Z2(); DISABLE_STEPPER_Z3(); AFTER_CHANGE(z, false); FORGET_AXIS(Z_AXIS); Z_RESET(); } +#define ENABLE_AXIS_Z() if (SHOULD_ENABLE(z)) { ENABLE_STEPPER_Z(); ENABLE_STEPPER_Z2(); ENABLE_STEPPER_Z3(); ENABLE_STEPPER_Z4(); AFTER_CHANGE(z, true); } +#define DISABLE_AXIS_Z() if (SHOULD_DISABLE(z)) { DISABLE_STEPPER_Z(); DISABLE_STEPPER_Z2(); DISABLE_STEPPER_Z3(); DISABLE_STEPPER_Z4(); AFTER_CHANGE(z, false); FORGET_AXIS(Z_AXIS); Z_RESET(); } #define FORGET_AXIS(A) TERN(HOME_AFTER_DEACTIVATE, set_axis_never_homed(A), CBI(axis_known_position, A)) From 94fea59e9d37c4117a844538b9a618e686b13dd1 Mon Sep 17 00:00:00 2001 From: thinkyhead Date: Tue, 24 Nov 2020 00:11:40 +0000 Subject: [PATCH 06/47] [cron] Bump distribution date (2020-11-24) --- Marlin/src/inc/Version.h | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/Marlin/src/inc/Version.h b/Marlin/src/inc/Version.h index 73897eed0e17..b8f5b8678ba4 100644 --- a/Marlin/src/inc/Version.h +++ b/Marlin/src/inc/Version.h @@ -42,7 +42,7 @@ * version was tagged. */ #ifndef STRING_DISTRIBUTION_DATE - #define STRING_DISTRIBUTION_DATE "2020-11-23" + #define STRING_DISTRIBUTION_DATE "2020-11-24" #endif /** From 62680bb356b4449661145ecbd6978d286c639a23 Mon Sep 17 00:00:00 2001 From: rdhoggattjr <64983896+rdhoggattjr@users.noreply.github.com> Date: Mon, 23 Nov 2020 23:02:54 -0600 Subject: [PATCH 07/47] LCD position in current units (#20145) --- Marlin/src/gcode/host/M114.cpp | 7 +-- Marlin/src/gcode/parser.h | 4 ++ Marlin/src/lcd/dogm/status_screen_DOGM.cpp | 35 ++++++++++---- Marlin/src/lcd/language/language_en.h | 3 ++ Marlin/src/lcd/menu/menu_motion.cpp | 55 +++++++++++++--------- 5 files changed, 69 insertions(+), 35 deletions(-) diff --git a/Marlin/src/gcode/host/M114.cpp b/Marlin/src/gcode/host/M114.cpp index 85a38f6462a8..75356ff66fee 100644 --- a/Marlin/src/gcode/host/M114.cpp +++ b/Marlin/src/gcode/host/M114.cpp @@ -55,7 +55,6 @@ } void report_current_position_detail() { - // Position as sent by G-code SERIAL_ECHOPGM("\nLogical:"); report_xyz(current_position.asLogical()); @@ -81,11 +80,7 @@ #if IS_KINEMATIC // Kinematics applied to the leveled position - #if IS_SCARA - SERIAL_ECHOPGM("ScaraK: "); - #else - SERIAL_ECHOPGM("DeltaK: "); - #endif + SERIAL_ECHOPGM(TERN(IS_SCARA, "ScaraK: ", "DeltaK: ")); inverse_kinematics(leveled); // writes delta[] report_xyz(delta); #endif diff --git a/Marlin/src/gcode/parser.h b/Marlin/src/gcode/parser.h index 69bbdaf02d39..8633d2b1e9db 100644 --- a/Marlin/src/gcode/parser.h +++ b/Marlin/src/gcode/parser.h @@ -329,6 +329,10 @@ class GCodeParser { #endif + static inline bool using_inch_units() { return mm_to_linear_unit(1.0f) != 1.0f; } + + #define IN_TO_MM(I) ((I) * 25.4f) + #define MM_TO_IN(M) ((M) / 25.4f) #define LINEAR_UNIT(V) parser.mm_to_linear_unit(V) #define VOLUMETRIC_UNIT(V) parser.mm_to_volumetric_unit(V) diff --git a/Marlin/src/lcd/dogm/status_screen_DOGM.cpp b/Marlin/src/lcd/dogm/status_screen_DOGM.cpp index 9fef6258268c..882b2fef506a 100644 --- a/Marlin/src/lcd/dogm/status_screen_DOGM.cpp +++ b/Marlin/src/lcd/dogm/status_screen_DOGM.cpp @@ -38,10 +38,11 @@ #include "../../module/motion.h" #include "../../module/temperature.h" +#include "../../gcode/parser.h" // for units (and volumetric) + #if ENABLED(FILAMENT_LCD_DISPLAY) #include "../../feature/filwidth.h" #include "../../module/planner.h" - #include "../../gcode/parser.h" #endif #if HAS_CUTTER @@ -67,6 +68,11 @@ #define X_LABEL_POS 3 #define X_VALUE_POS 11 #define XYZ_SPACING 37 + +#define X_LABEL_POS_IN (X_LABEL_POS - 2) +#define X_VALUE_POS_IN (X_VALUE_POS - 5) +#define XYZ_SPACING_IN (XYZ_SPACING + 9) + #define XYZ_BASELINE (30 + INFO_FONT_ASCENT) #define EXTRAS_BASELINE (40 + INFO_FONT_ASCENT) #define STATUS_BASELINE (LCD_PIXEL_HEIGHT - INFO_FONT_DESCENT) @@ -370,10 +376,12 @@ FORCE_INLINE void _draw_centered_temp(const int16_t temp, const uint8_t tx, cons // Homed and known, display constantly. // FORCE_INLINE void _draw_axis_value(const AxisEnum axis, const char *value, const bool blink) { + const bool is_inch = parser.using_inch_units(); const AxisEnum a = TERN(LCD_SHOW_E_TOTAL, axis == E_AXIS ? X_AXIS : axis, axis); - const uint8_t offs = (XYZ_SPACING) * a; - lcd_put_wchar(X_LABEL_POS + offs, XYZ_BASELINE, axis_codes[axis]); - lcd_moveto(X_VALUE_POS + offs, XYZ_BASELINE); + const uint8_t offs = a * (is_inch ? XYZ_SPACING_IN : XYZ_SPACING); + lcd_put_wchar((is_inch ? X_LABEL_POS_IN : X_LABEL_POS) + offs, XYZ_BASELINE, axis_codes[axis]); + lcd_moveto((is_inch ? X_VALUE_POS_IN : X_VALUE_POS) + offs, XYZ_BASELINE); + if (blink) lcd_put_u8str(value); else { @@ -390,9 +398,16 @@ FORCE_INLINE void _draw_axis_value(const AxisEnum axis, const char *value, const } } +/** + * Draw the Status Screen for a 128x64 DOGM (U8glib) display. + * + * Called as needed to update the current display stripe. + * Use the PAGE_CONTAINS macros to avoid pointless draw calls. + */ void MarlinUI::draw_status_screen() { + constexpr int xystorage = TERN(INCH_MODE_SUPPORT, 8, 5); + static char xstring[TERN(LCD_SHOW_E_TOTAL, 12, xystorage)], ystring[xystorage], zstring[8]; - static char xstring[TERN(LCD_SHOW_E_TOTAL, 12, 5)], ystring[5], zstring[8]; #if ENABLED(FILAMENT_LCD_DISPLAY) static char wstring[5], mstring[4]; #endif @@ -439,7 +454,8 @@ void MarlinUI::draw_status_screen() { #endif const xyz_pos_t lpos = current_position.asLogical(); - strcpy(zstring, ftostr52sp(lpos.z)); + const bool is_inch = parser.using_inch_units(); + strcpy(zstring, is_inch ? ftostr42_52(LINEAR_UNIT(lpos.z)) : ftostr52sp(lpos.z)); if (show_e_total) { #if ENABLED(LCD_SHOW_E_TOTAL) @@ -448,8 +464,8 @@ void MarlinUI::draw_status_screen() { #endif } else { - strcpy(xstring, ftostr4sign(lpos.x)); - strcpy(ystring, ftostr4sign(lpos.y)); + strcpy(xstring, is_inch ? ftostr53_63(LINEAR_UNIT(lpos.x)) : ftostr4sign(lpos.x)); + strcpy(ystring, is_inch ? ftostr53_63(LINEAR_UNIT(lpos.y)) : ftostr4sign(lpos.y)); } #if ENABLED(FILAMENT_LCD_DISPLAY) @@ -854,6 +870,9 @@ void MarlinUI::draw_status_screen() { } } +/** + * Draw the Status Message area + */ void MarlinUI::draw_status_message(const bool blink) { // Get the UTF8 character count of the string diff --git a/Marlin/src/lcd/language/language_en.h b/Marlin/src/lcd/language/language_en.h index 0355f2f51249..04487fa13f27 100644 --- a/Marlin/src/lcd/language/language_en.h +++ b/Marlin/src/lcd/language/language_en.h @@ -258,6 +258,9 @@ namespace Language_en { PROGMEM Language_Str MSG_MOVE_01MM = _UxGT("Move 0.1mm"); PROGMEM Language_Str MSG_MOVE_1MM = _UxGT("Move 1mm"); PROGMEM Language_Str MSG_MOVE_10MM = _UxGT("Move 10mm"); + PROGMEM Language_Str MSG_MOVE_0001IN = _UxGT("Move 0.001in"); + PROGMEM Language_Str MSG_MOVE_001IN = _UxGT("Move 0.01in"); + PROGMEM Language_Str MSG_MOVE_01IN = _UxGT("Move 0.1in"); PROGMEM Language_Str MSG_SPEED = _UxGT("Speed"); PROGMEM Language_Str MSG_BED_Z = _UxGT("Bed Z"); PROGMEM Language_Str MSG_NOZZLE = _UxGT("Nozzle"); diff --git a/Marlin/src/lcd/menu/menu_motion.cpp b/Marlin/src/lcd/menu/menu_motion.cpp index c681842e903d..468af3273c18 100644 --- a/Marlin/src/lcd/menu/menu_motion.cpp +++ b/Marlin/src/lcd/menu/menu_motion.cpp @@ -32,6 +32,7 @@ #include "menu_addon.h" #include "../../module/motion.h" +#include "../../gcode/parser.h" // for inch support #if ENABLED(DELTA) #include "../../module/delta.h" @@ -95,7 +96,12 @@ static void _lcd_move_xyz(PGM_P const name, const AxisEnum axis) { ui.manual_move.processing ? destination[axis] : current_position[axis] + TERN0(IS_KINEMATIC, ui.manual_move.offset), axis ); - MenuEditItemBase::draw_edit_screen(name, ui.manual_move.menu_scale >= 0.1f ? ftostr41sign(pos) : ftostr63(pos)); + if (parser.using_inch_units()) { + const float imp_pos = LINEAR_UNIT(pos); + MenuEditItemBase::draw_edit_screen(name, ftostr63(imp_pos)); + } + else + MenuEditItemBase::draw_edit_screen(name, ui.manual_move.menu_scale >= 0.1f ? ftostr41sign(pos) : ftostr63(pos)); } } void lcd_move_x() { _lcd_move_xyz(GET_TEXT(MSG_MOVE_X), X_AXIS); } @@ -165,26 +171,33 @@ void _menu_move_distance(const AxisEnum axis, const screenFunc_t func, const int } BACK_ITEM(MSG_MOVE_AXIS); - SUBMENU(MSG_MOVE_10MM, []{ _goto_manual_move(10); }); - SUBMENU(MSG_MOVE_1MM, []{ _goto_manual_move( 1); }); - SUBMENU(MSG_MOVE_01MM, []{ _goto_manual_move( 0.1f); }); - if (axis == Z_AXIS && (SHORT_MANUAL_Z_MOVE) > 0.0f && (SHORT_MANUAL_Z_MOVE) < 0.1f) { - // Determine digits needed right of decimal - constexpr uint8_t digs = !UNEAR_ZERO((SHORT_MANUAL_Z_MOVE) * 1000 - int((SHORT_MANUAL_Z_MOVE) * 1000)) ? 4 : - !UNEAR_ZERO((SHORT_MANUAL_Z_MOVE) * 100 - int((SHORT_MANUAL_Z_MOVE) * 100)) ? 3 : 2; - PGM_P const label = GET_TEXT(MSG_MOVE_Z_DIST); - char tmp[strlen_P(label) + 10 + 1], numstr[10]; - sprintf_P(tmp, label, dtostrf(SHORT_MANUAL_Z_MOVE, 1, digs, numstr)); - - #if DISABLED(HAS_GRAPHICAL_TFT) - extern const char NUL_STR[]; - SUBMENU_P(NUL_STR, []{ _goto_manual_move(float(SHORT_MANUAL_Z_MOVE)); }); - MENU_ITEM_ADDON_START(0 + ENABLED(HAS_MARLINUI_HD44780)); - lcd_put_u8str(tmp); - MENU_ITEM_ADDON_END(); - #else - SUBMENU_P(tmp, []{ _goto_manual_move(float(SHORT_MANUAL_Z_MOVE)); }); - #endif + if (parser.using_inch_units()) { + SUBMENU(MSG_MOVE_01IN, []{ _goto_manual_move(IN_TO_MM(0.100f)); }); + SUBMENU(MSG_MOVE_001IN, []{ _goto_manual_move(IN_TO_MM(0.010f)); }); + SUBMENU(MSG_MOVE_0001IN, []{ _goto_manual_move(IN_TO_MM(0.001f)); }); + } + else { + SUBMENU(MSG_MOVE_10MM, []{ _goto_manual_move(10); }); + SUBMENU(MSG_MOVE_1MM, []{ _goto_manual_move( 1); }); + SUBMENU(MSG_MOVE_01MM, []{ _goto_manual_move( 0.1f); }); + if (axis == Z_AXIS && (SHORT_MANUAL_Z_MOVE) > 0.0f && (SHORT_MANUAL_Z_MOVE) < 0.1f) { + // Determine digits needed right of decimal + constexpr uint8_t digs = !UNEAR_ZERO((SHORT_MANUAL_Z_MOVE) * 1000 - int((SHORT_MANUAL_Z_MOVE) * 1000)) ? 4 : + !UNEAR_ZERO((SHORT_MANUAL_Z_MOVE) * 100 - int((SHORT_MANUAL_Z_MOVE) * 100)) ? 3 : 2; + PGM_P const label = GET_TEXT(MSG_MOVE_Z_DIST); + char tmp[strlen_P(label) + 10 + 1], numstr[10]; + sprintf_P(tmp, label, dtostrf(SHORT_MANUAL_Z_MOVE, 1, digs, numstr)); + + #if DISABLED(HAS_GRAPHICAL_TFT) + extern const char NUL_STR[]; + SUBMENU_P(NUL_STR, []{ _goto_manual_move(float(SHORT_MANUAL_Z_MOVE)); }); + MENU_ITEM_ADDON_START(0 + ENABLED(HAS_MARLINUI_HD44780)); + lcd_put_u8str(tmp); + MENU_ITEM_ADDON_END(); + #else + SUBMENU_P(tmp, []{ _goto_manual_move(float(SHORT_MANUAL_Z_MOVE)); }); + #endif + } } END_MENU(); } From ef12425befc39fbb6ecedfc1b2db278ca43f86c9 Mon Sep 17 00:00:00 2001 From: ellensp Date: Wed, 25 Nov 2020 11:14:22 +1300 Subject: [PATCH 08/47] Set "lcd_move_e" index to fix the label (#20263) --- Marlin/src/lcd/menu/menu_motion.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/Marlin/src/lcd/menu/menu_motion.cpp b/Marlin/src/lcd/menu/menu_motion.cpp index 468af3273c18..478608e9b313 100644 --- a/Marlin/src/lcd/menu/menu_motion.cpp +++ b/Marlin/src/lcd/menu/menu_motion.cpp @@ -205,7 +205,7 @@ void _menu_move_distance(const AxisEnum axis, const screenFunc_t func, const int #if E_MANUAL inline void _goto_menu_move_distance_e() { - ui.goto_screen([]{ _menu_move_distance(E_AXIS, []{ lcd_move_e(); }, -1); }); + ui.goto_screen([]{ _menu_move_distance(E_AXIS, []{ lcd_move_e(TERN_(MULTI_MANUAL, active_extruder)); }, -1); }); } inline void _menu_move_distance_e_maybe() { From 4258ff1a689705e1c002d354a17a6fc2f6b2564f Mon Sep 17 00:00:00 2001 From: pseudex Date: Tue, 24 Nov 2020 23:20:06 +0100 Subject: [PATCH 09/47] Allow cold Filament Load/Unload with M302 P1 (#20262) Co-authored-by: Scott Lahteine --- Marlin/src/feature/pause.cpp | 6 +++--- 1 file changed, 3 insertions(+), 3 deletions(-) diff --git a/Marlin/src/feature/pause.cpp b/Marlin/src/feature/pause.cpp index 024338f2422e..1593b0cc572e 100644 --- a/Marlin/src/feature/pause.cpp +++ b/Marlin/src/feature/pause.cpp @@ -142,10 +142,10 @@ static bool ensure_safe_temperature(const bool wait=true, const PauseMode mode=P #endif UNUSED(mode); - if (wait) - return thermalManager.wait_for_hotend(active_extruder); + if (wait) return thermalManager.wait_for_hotend(active_extruder); - wait_for_heatup = true; // Allow interruption by Emergency Parser M108 + // Allow interruption by Emergency Parser M108 + wait_for_heatup = TERN1(PREVENT_COLD_EXTRUSION, !thermalManager.allow_cold_extrude); while (wait_for_heatup && ABS(thermalManager.degHotend(active_extruder) - thermalManager.degTargetHotend(active_extruder)) > TEMP_WINDOW) idle(); wait_for_heatup = false; From e9431b5445e23ebef657a90a25fce2b424511c17 Mon Sep 17 00:00:00 2001 From: Jason Smith Date: Tue, 24 Nov 2020 14:27:59 -0800 Subject: [PATCH 10/47] No Z_MULTI_ENDSTOPS when HOMING_Z_WITH_PROBE (#20254) --- Marlin/src/inc/SanityCheck.h | 2 ++ buildroot/tests/DUE-tests | 7 +------ 2 files changed, 3 insertions(+), 6 deletions(-) diff --git a/Marlin/src/inc/SanityCheck.h b/Marlin/src/inc/SanityCheck.h index 072bb26bfe7a..0dfa3058411c 100644 --- a/Marlin/src/inc/SanityCheck.h +++ b/Marlin/src/inc/SanityCheck.h @@ -2006,6 +2006,8 @@ static_assert(hbm[Z_AXIS] >= 0, "HOMING_BUMP_MM.Z must be greater than or equal #error "Enable USE_ZMIN_PLUG when homing Z to MIN." #elif Z_HOME_DIR > 0 && ENABLED(USE_PROBE_FOR_Z_HOMING) #error "Z_HOME_DIR must be -1 when homing Z with the probe." +#elif BOTH(HOMING_Z_WITH_PROBE, Z_MULTI_ENDSTOPS) + #error "Z_MULTI_ENDSTOPS is incompatible with USE_PROBE_FOR_Z_HOMING." #elif Z_HOME_DIR > 0 && DISABLED(USE_ZMAX_PLUG) #error "Enable USE_ZMAX_PLUG when homing Z to MAX." #endif diff --git a/buildroot/tests/DUE-tests b/buildroot/tests/DUE-tests index ccb49bf4828b..009688ce210f 100755 --- a/buildroot/tests/DUE-tests +++ b/buildroot/tests/DUE-tests @@ -41,14 +41,9 @@ exec_test $1 $2 "RAMPS4DUE_EFB with ABL (Bilinear), ExtUI, S-Curve, many options restore_configs opt_set MOTHERBOARD BOARD_RADDS opt_enable USE_XMAX_PLUG USE_YMAX_PLUG ENDSTOPPULLUPS BLTOUCH AUTO_BED_LEVELING_BILINEAR \ - Z_MULTI_ENDSTOPS Z_STEPPER_AUTO_ALIGN Z_STEPPER_ALIGN_KNOWN_STEPPER_POSITIONS \ - Z_SAFE_HOMING + Z_STEPPER_AUTO_ALIGN Z_STEPPER_ALIGN_KNOWN_STEPPER_POSITIONS Z_SAFE_HOMING #TOUCH_UI_FTDI_EVE LCD_ALEPHOBJECTS_CLCD_UI OTHER_PIN_LAYOUT opt_set NUM_Z_STEPPER_DRIVERS 3 -opt_add Z2_MAX_ENDSTOP_INVERTING false -opt_add Z3_MAX_ENDSTOP_INVERTING false -opt_add Z2_MAX_PIN 2 -opt_add Z3_MAX_PIN 3 pins_set ramps/RAMPS X_MAX_PIN -1 pins_set ramps/RAMPS Y_MAX_PIN -1 exec_test $1 $2 "RADDS with ABL (Bilinear), Triple Z Axis, Z_STEPPER_AUTO_ALIGN" "$3" From 296a2ad7e45d88a10db4b3305ea183e5c0c177a5 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Tue, 24 Nov 2020 17:38:13 -0600 Subject: [PATCH 11/47] Consistent Probe XY offset type --- Marlin/src/gcode/calibrate/G76_M192_M871.cpp | 2 +- Marlin/src/module/probe.cpp | 2 +- Marlin/src/module/probe.h | 6 +++--- 3 files changed, 5 insertions(+), 5 deletions(-) diff --git a/Marlin/src/gcode/calibrate/G76_M192_M871.cpp b/Marlin/src/gcode/calibrate/G76_M192_M871.cpp index 38f17869fb45..8ffada5c0310 100644 --- a/Marlin/src/gcode/calibrate/G76_M192_M871.cpp +++ b/Marlin/src/gcode/calibrate/G76_M192_M871.cpp @@ -144,7 +144,7 @@ void GcodeSuite::G76() { const xyz_pos_t parkpos = temp_comp.park_point, probe_pos_xyz = xyz_pos_t(temp_comp.measure_point) + xyz_pos_t({ 0.0f, 0.0f, PTC_PROBE_HEATING_OFFSET }), - noz_pos_xyz = probe_pos_xyz - xy_pos_t(probe.offset_xy); // Nozzle position based on probe position + noz_pos_xyz = probe_pos_xyz - probe.offset_xy; // Nozzle position based on probe position if (do_bed_cal || do_probe_cal) { // Ensure park position is reachable diff --git a/Marlin/src/module/probe.cpp b/Marlin/src/module/probe.cpp index ff80063d658d..f02b90915063 100644 --- a/Marlin/src/module/probe.cpp +++ b/Marlin/src/module/probe.cpp @@ -89,7 +89,7 @@ Probe probe; xyz_pos_t Probe::offset; // Initialized by settings.load() #if HAS_PROBE_XY_OFFSET - const xyz_pos_t &Probe::offset_xy = Probe::offset; + const xy_pos_t &Probe::offset_xy = xy_pos_t(Probe::offset); #endif #if ENABLED(Z_PROBE_SLED) diff --git a/Marlin/src/module/probe.h b/Marlin/src/module/probe.h index 63229242b5da..cac106fed681 100644 --- a/Marlin/src/module/probe.h +++ b/Marlin/src/module/probe.h @@ -112,9 +112,9 @@ class Probe { FORCE_INLINE static bool good_bounds(const xy_pos_t &lf, const xy_pos_t &rb) { return ( #if IS_KINEMATIC - can_reach(lf.x, 0) && can_reach(rb.x, 0) && can_reach(0, lf.y) && can_reach(0, rb.y) + can_reach(lf.x, 0) && can_reach(rb.x, 0) && can_reach(0, lf.y) && can_reach(0, rb.y) #else - can_reach(lf) && can_reach(rb) + can_reach(lf) && can_reach(rb) #endif ); } @@ -122,7 +122,7 @@ class Probe { // Use offset_xy for read only access // More optimal the XY offset is known to always be zero. #if HAS_PROBE_XY_OFFSET - static const xyz_pos_t &offset_xy; + static const xy_pos_t &offset_xy; #else static constexpr xy_pos_t offset_xy = xy_pos_t({ 0, 0 }); // See #16767 #endif From b28b2ca26674219d6654cd287bb9da30c91b2231 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Tue, 24 Nov 2020 17:53:26 -0600 Subject: [PATCH 12/47] Cosmetic G29 ABL tweak --- Marlin/src/gcode/bedlevel/abl/G29.cpp | 5 +++-- 1 file changed, 3 insertions(+), 2 deletions(-) diff --git a/Marlin/src/gcode/bedlevel/abl/G29.cpp b/Marlin/src/gcode/bedlevel/abl/G29.cpp index f387dd9bd814..9999d92e223b 100644 --- a/Marlin/src/gcode/bedlevel/abl/G29.cpp +++ b/Marlin/src/gcode/bedlevel/abl/G29.cpp @@ -656,8 +656,9 @@ G29_TYPE GcodeSuite::G29() { #elif ENABLED(AUTO_BED_LEVELING_BILINEAR) - z_values[meshCount.x][meshCount.y] = measured_z + zoffset; - TERN_(EXTENSIBLE_UI, ExtUI::onMeshUpdate(meshCount, z_values[meshCount.x][meshCount.y])); + const float z = measured_z + zoffset; + z_values[meshCount.x][meshCount.y] = z; + TERN_(EXTENSIBLE_UI, ExtUI::onMeshUpdate(meshCount, z)); #endif From 0eae28a6637ad5f3b960a5b7c6fdd4bed3b1e6d3 Mon Sep 17 00:00:00 2001 From: thinkyhead Date: Wed, 25 Nov 2020 00:11:42 +0000 Subject: [PATCH 13/47] [cron] Bump distribution date (2020-11-25) --- Marlin/src/inc/Version.h | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/Marlin/src/inc/Version.h b/Marlin/src/inc/Version.h index b8f5b8678ba4..4007c237e306 100644 --- a/Marlin/src/inc/Version.h +++ b/Marlin/src/inc/Version.h @@ -42,7 +42,7 @@ * version was tagged. */ #ifndef STRING_DISTRIBUTION_DATE - #define STRING_DISTRIBUTION_DATE "2020-11-24" + #define STRING_DISTRIBUTION_DATE "2020-11-25" #endif /** From e38abef720c419262b89b21467857565aa10ebdf Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Tue, 24 Nov 2020 18:29:11 -0600 Subject: [PATCH 14/47] Update TOUCH_UI_LULZBOT_BIO wrappers --- .../screens/advanced_settings_menu.cpp | 5 +-- .../screens/bio_advanced_settings.cpp | 4 +-- .../screens/bio_confirm_home_e.cpp | 5 +-- .../screens/bio_confirm_home_xyz.cpp | 5 +-- .../screens/bio_main_menu.cpp | 4 +-- .../screens/bio_printing_dialog_box.cpp | 10 ++---- .../screens/bio_tune_menu.cpp | 4 +-- .../ftdi_eve_touch_ui/screens/main_menu.cpp | 32 ++++--------------- .../ftdi_eve_touch_ui/screens/tune_menu.cpp | 2 +- 9 files changed, 25 insertions(+), 46 deletions(-) diff --git a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/advanced_settings_menu.cpp b/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/advanced_settings_menu.cpp index 1b7d04331459..3ffc88c385fb 100644 --- a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/advanced_settings_menu.cpp +++ b/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/advanced_settings_menu.cpp @@ -22,7 +22,7 @@ #include "../config.h" -#if ENABLED(TOUCH_UI_FTDI_EVE) && !defined(TOUCH_UI_LULZBOT_BIO) +#if ENABLED(TOUCH_UI_FTDI_EVE) && DISABLED(TOUCH_UI_LULZBOT_BIO) #include "screens.h" @@ -152,4 +152,5 @@ bool AdvancedSettingsMenu::onTouchEnd(uint8_t tag) { } return true; } -#endif // TOUCH_UI_FTDI_EVE + +#endif // TOUCH_UI_FTDI_EVE && !TOUCH_UI_LULZBOT_BIO diff --git a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/bio_advanced_settings.cpp b/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/bio_advanced_settings.cpp index b2611be2509e..196f26fe22b2 100644 --- a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/bio_advanced_settings.cpp +++ b/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/bio_advanced_settings.cpp @@ -22,7 +22,7 @@ #include "../config.h" -#if ENABLED(TOUCH_UI_FTDI_EVE) && defined(TOUCH_UI_LULZBOT_BIO) +#if BOTH(TOUCH_UI_FTDI_EVE, TOUCH_UI_LULZBOT_BIO) #include "screens.h" @@ -134,4 +134,4 @@ bool AdvancedSettingsMenu::onTouchEnd(uint8_t tag) { return true; } -#endif // TOUCH_UI_FTDI_EVE +#endif // TOUCH_UI_FTDI_EVE && TOUCH_UI_LULZBOT_BIO diff --git a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/bio_confirm_home_e.cpp b/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/bio_confirm_home_e.cpp index 85885fb38837..3f6b4116f189 100644 --- a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/bio_confirm_home_e.cpp +++ b/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/bio_confirm_home_e.cpp @@ -22,7 +22,7 @@ #include "../config.h" -#if ENABLED(TOUCH_UI_FTDI_EVE) && defined(TOUCH_UI_LULZBOT_BIO) +#if BOTH(TOUCH_UI_FTDI_EVE, TOUCH_UI_LULZBOT_BIO) #include "screens.h" @@ -53,4 +53,5 @@ bool BioConfirmHomeE::onTouchEnd(uint8_t tag) { } return true; } -#endif // TOUCH_UI_FTDI_EVE + +#endif // TOUCH_UI_FTDI_EVE && TOUCH_UI_LULZBOT_BIO diff --git a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/bio_confirm_home_xyz.cpp b/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/bio_confirm_home_xyz.cpp index 102631f18ed3..f712fdfff9ab 100644 --- a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/bio_confirm_home_xyz.cpp +++ b/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/bio_confirm_home_xyz.cpp @@ -22,7 +22,7 @@ #include "../config.h" -#if ENABLED(TOUCH_UI_FTDI_EVE) && defined(TOUCH_UI_LULZBOT_BIO) +#if BOTH(TOUCH_UI_FTDI_EVE, TOUCH_UI_LULZBOT_BIO) #include "screens.h" @@ -52,4 +52,5 @@ bool BioConfirmHomeXYZ::onTouchEnd(uint8_t tag) { } return true; } -#endif // TOUCH_UI_FTDI_EVE + +#endif // TOUCH_UI_FTDI_EVE && TOUCH_UI_LULZBOT_BIO diff --git a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/bio_main_menu.cpp b/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/bio_main_menu.cpp index 5ddc2d02aea1..dacbaf686642 100644 --- a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/bio_main_menu.cpp +++ b/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/bio_main_menu.cpp @@ -22,7 +22,7 @@ #include "../config.h" -#if ENABLED(TOUCH_UI_FTDI_EVE) && defined(TOUCH_UI_LULZBOT_BIO) +#if BOTH(TOUCH_UI_FTDI_EVE, TOUCH_UI_LULZBOT_BIO) #include "screens.h" @@ -85,4 +85,4 @@ bool MainMenu::onTouchEnd(uint8_t tag) { return true; } -#endif // TOUCH_UI_FTDI_EVE +#endif // TOUCH_UI_FTDI_EVE && TOUCH_UI_LULZBOT_BIO diff --git a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/bio_printing_dialog_box.cpp b/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/bio_printing_dialog_box.cpp index fc6dc5ee57bd..38426377034e 100644 --- a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/bio_printing_dialog_box.cpp +++ b/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/bio_printing_dialog_box.cpp @@ -22,7 +22,7 @@ #include "../config.h" -#if ENABLED(TOUCH_UI_FTDI_EVE) && defined(TOUCH_UI_LULZBOT_BIO) +#if BOTH(TOUCH_UI_FTDI_EVE, TOUCH_UI_LULZBOT_BIO) #include "screens.h" @@ -78,11 +78,7 @@ void BioPrintingDialogBox::draw_interaction_buttons(draw_mode_t what) { .font(font_medium) .colors(isPrinting() ? action_btn : normal_btn) .tag(2).button(BTN_POS(1,9), BTN_SIZE(1,1), F("Menu")) - #if ENABLED(SDSUPPORT) - .enabled(isPrinting() ? isPrintingFromMedia() : 1) - #else - .enabled(isPrinting() ? 0 : 1) - #endif + .enabled(isPrinting() ? TERN0(SDSUPPORT, isPrintingFromMedia()) : 1) .tag(3) .colors(isPrinting() ? normal_btn : action_btn) .button( BTN_POS(2,9), BTN_SIZE(1,1), isPrinting() ? F("Cancel") : F("Back")); @@ -152,4 +148,4 @@ void BioPrintingDialogBox::show() { GOTO_SCREEN(BioPrintingDialogBox); } -#endif // TOUCH_UI_FTDI_EVE +#endif // TOUCH_UI_FTDI_EVE && TOUCH_UI_LULZBOT_BIO diff --git a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/bio_tune_menu.cpp b/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/bio_tune_menu.cpp index 9723abba0998..ceea3742b0d6 100644 --- a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/bio_tune_menu.cpp +++ b/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/bio_tune_menu.cpp @@ -22,7 +22,7 @@ #include "../config.h" -#if ENABLED(TOUCH_UI_FTDI_EVE) && defined(TOUCH_UI_LULZBOT_BIO) +#if BOTH(TOUCH_UI_FTDI_EVE, TOUCH_UI_LULZBOT_BIO) #include "screens.h" @@ -76,4 +76,4 @@ bool TuneMenu::onTouchEnd(uint8_t tag) { return true; } -#endif // TOUCH_UI_FTDI_EVE +#endif // TOUCH_UI_FTDI_EVE && TOUCH_UI_LULZBOT_BIO diff --git a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/main_menu.cpp b/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/main_menu.cpp index 17e15afc5ccd..85006566bb18 100644 --- a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/main_menu.cpp +++ b/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/main_menu.cpp @@ -23,7 +23,7 @@ #include "../config.h" -#if ENABLED(TOUCH_UI_FTDI_EVE) && !defined(TOUCH_UI_LULZBOT_BIO) +#if ENABLED(TOUCH_UI_FTDI_EVE) && DISABLED(TOUCH_UI_LULZBOT_BIO) #include "screens.h" @@ -75,34 +75,14 @@ void MainMenu::onRedraw(draw_mode_t what) { 1 #endif ) - .tag(3).button( CLEAN_NOZZLE_POS, GET_TEXT_F( - #if ENABLED(TOUCH_UI_COCOA_PRESS) - MSG_PREHEAT_1 - #else - MSG_CLEAN_NOZZLE - #endif - )) + .tag(3).button( CLEAN_NOZZLE_POS, GET_TEXT_F(TERN(TOUCH_UI_COCOA_PRESS, MSG_PREHEAT_1, MSG_CLEAN_NOZZLE))) .tag(4).button( MOVE_AXIS_POS, GET_TEXT_F(MSG_MOVE_AXIS)) .tag(5).button( DISABLE_STEPPERS_POS, GET_TEXT_F(MSG_DISABLE_STEPPERS)) .tag(6).button( TEMPERATURE_POS, GET_TEXT_F(MSG_TEMPERATURE)) - .enabled( - #if DISABLED(TOUCH_UI_LULZBOT_BIO) - 1 - #endif - ) - .tag(7).button( FILAMENTCHANGE_POS, GET_TEXT_F( - #if ENABLED(TOUCH_UI_COCOA_PRESS) - MSG_CASE_LIGHT - #else - MSG_FILAMENTCHANGE - #endif - )) + .enabled(IF_DISABLED(TOUCH_UI_LULZBOT_BIO, 1)) + .tag(7).button( FILAMENTCHANGE_POS, GET_TEXT_F(TERN(TOUCH_UI_COCOA_PRESS, MSG_CASE_LIGHT, MSG_FILAMENTCHANGE)) .tag(8).button( ADVANCED_SETTINGS_POS, GET_TEXT_F(MSG_ADVANCED_SETTINGS)) - .enabled( - #ifdef HAS_LEVELING - 1 - #endif - ) + .enabled(TERN_(HAS_LEVELING, 1)) .tag(9).button( LEVELING_POS, GET_TEXT_F(MSG_LEVELING)) .tag(10).button( ABOUT_PRINTER_POS, GET_TEXT_F(MSG_INFO_MENU)) .colors(action_btn) @@ -140,4 +120,4 @@ bool MainMenu::onTouchEnd(uint8_t tag) { return true; } -#endif // TOUCH_UI_FTDI_EVE +#endif // TOUCH_UI_FTDI_EVE && !TOUCH_UI_LULZBOT_BIO diff --git a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/tune_menu.cpp b/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/tune_menu.cpp index 894b238ae01e..10cbb8af5333 100644 --- a/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/tune_menu.cpp +++ b/Marlin/src/lcd/extui/lib/ftdi_eve_touch_ui/screens/tune_menu.cpp @@ -22,7 +22,7 @@ #include "../config.h" -#if ENABLED(TOUCH_UI_FTDI_EVE) && !defined(TOUCH_UI_LULZBOT_BIO) +#if ENABLED(TOUCH_UI_FTDI_EVE) && DISABLED(TOUCH_UI_LULZBOT_BIO) #include "screens.h" From 2693e35caead85de734735c852de52bebbdc818b Mon Sep 17 00:00:00 2001 From: Victor Oliveira Date: Wed, 25 Nov 2020 01:08:35 -0300 Subject: [PATCH 15/47] add missing header to use HAS_SD_HOST_DRIVE (#20270) --- Marlin/src/HAL/STM32F1/msc_sd.cpp | 2 ++ 1 file changed, 2 insertions(+) diff --git a/Marlin/src/HAL/STM32F1/msc_sd.cpp b/Marlin/src/HAL/STM32F1/msc_sd.cpp index 44242358eeb8..ba722b8aebfe 100644 --- a/Marlin/src/HAL/STM32F1/msc_sd.cpp +++ b/Marlin/src/HAL/STM32F1/msc_sd.cpp @@ -13,6 +13,8 @@ * along with this program. If not, see . * */ +#include "../../inc/MarlinConfigPre.h" + #if defined(__STM32F1__) && HAS_SD_HOST_DRIVE #include "msc_sd.h" From 04c4c6004e752582235357b14aebdd5ff579f477 Mon Sep 17 00:00:00 2001 From: Victor Oliveira Date: Wed, 25 Nov 2020 02:39:49 -0300 Subject: [PATCH 16/47] Fix COLOR_UI without TOUCH_SCREEN_CALIBRATION (#20269) --- Marlin/src/lcd/tft_io/tft_io.h | 8 ++++++++ Marlin/src/lcd/tft_io/touch_calibration.h | 9 +-------- 2 files changed, 9 insertions(+), 8 deletions(-) diff --git a/Marlin/src/lcd/tft_io/tft_io.h b/Marlin/src/lcd/tft_io/tft_io.h index 63d6936ac0b8..50b0ce446383 100644 --- a/Marlin/src/lcd/tft_io/tft_io.h +++ b/Marlin/src/lcd/tft_io/tft_io.h @@ -71,6 +71,14 @@ // #define TFT_COLOR TFT_COLOR_RGB // #endif +#define TOUCH_ORIENTATION_NONE 0 +#define TOUCH_LANDSCAPE 1 +#define TOUCH_PORTRAIT 2 + +#ifndef TOUCH_ORIENTATION + #define TOUCH_ORIENTATION TOUCH_LANDSCAPE +#endif + #define SSD1963 0x5761 #define ST7735 0x89F0 #define ST7789 0x8552 diff --git a/Marlin/src/lcd/tft_io/touch_calibration.h b/Marlin/src/lcd/tft_io/touch_calibration.h index 5bebafffd250..93ed9aa6099a 100644 --- a/Marlin/src/lcd/tft_io/touch_calibration.h +++ b/Marlin/src/lcd/tft_io/touch_calibration.h @@ -19,6 +19,7 @@ #pragma once #include "../../inc/MarlinConfigPre.h" +#include "tft_io.h" #ifndef TOUCH_SCREEN_CALIBRATION_PRECISION #define TOUCH_SCREEN_CALIBRATION_PRECISION 80 @@ -28,14 +29,6 @@ #define TOUCH_SCREEN_HOLD_TO_CALIBRATE_MS 2500 #endif -#define TOUCH_ORIENTATION_NONE 0 -#define TOUCH_LANDSCAPE 1 -#define TOUCH_PORTRAIT 2 - -#ifndef TOUCH_ORIENTATION - #define TOUCH_ORIENTATION TOUCH_LANDSCAPE -#endif - typedef struct __attribute__((__packed__)) { int32_t x, y; int16_t offset_x, offset_y; From afe5027a399b10d9acbc469c5af87e0717f0a90c Mon Sep 17 00:00:00 2001 From: thinkyhead Date: Thu, 26 Nov 2020 00:11:33 +0000 Subject: [PATCH 17/47] [cron] Bump distribution date (2020-11-26) --- Marlin/src/inc/Version.h | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/Marlin/src/inc/Version.h b/Marlin/src/inc/Version.h index 4007c237e306..5fb065dc35d8 100644 --- a/Marlin/src/inc/Version.h +++ b/Marlin/src/inc/Version.h @@ -42,7 +42,7 @@ * version was tagged. */ #ifndef STRING_DISTRIBUTION_DATE - #define STRING_DISTRIBUTION_DATE "2020-11-25" + #define STRING_DISTRIBUTION_DATE "2020-11-26" #endif /** From 649965ae32eca5140ea66d1265a69576e2a2c669 Mon Sep 17 00:00:00 2001 From: swissnorp <67485708+swissnorp@users.noreply.github.com> Date: Thu, 26 Nov 2020 04:38:00 +0100 Subject: [PATCH 18/47] Probe Offset Wizard improvements (#20239) --- Marlin/Configuration_adv.h | 10 +- Marlin/src/gcode/calibrate/G28.cpp | 4 +- Marlin/src/inc/SanityCheck.h | 33 ++++--- Marlin/src/lcd/language/language_en.h | 2 + Marlin/src/lcd/marlinui.h | 2 +- Marlin/src/lcd/menu/menu.h | 2 +- Marlin/src/lcd/menu/menu_advanced.cpp | 2 +- Marlin/src/lcd/menu/menu_probe_offset.cpp | 114 ++++++++++++++-------- 8 files changed, 109 insertions(+), 60 deletions(-) diff --git a/Marlin/Configuration_adv.h b/Marlin/Configuration_adv.h index baa0433f19b9..7c8f2da948c6 100644 --- a/Marlin/Configuration_adv.h +++ b/Marlin/Configuration_adv.h @@ -1084,8 +1084,14 @@ #if HAS_BED_PROBE //#define PROBE_OFFSET_WIZARD #if ENABLED(PROBE_OFFSET_WIZARD) - #define PROBE_OFFSET_START -4.0 // Estimated nozzle-to-probe Z offset, plus a little extra - //#define PROBE_OFFSET_WIZARD_XY_POS XY_CENTER // Set a convenient position to do the measurement + // + // Enable to init the Probe Z-Offset when starting the Wizard. + // Use the estimated nozzle-to-probe Z offset, plus a little more. + // + //#define PROBE_OFFSET_WIZARD_START_Z -4.0 + + // Set a convenient position to do the calibration (probing point and nozzle/bed-distance) + //#define PROBE_OFFSET_WIZARD_XY_POS { X_CENTER, Y_CENTER } #endif #endif diff --git a/Marlin/src/gcode/calibrate/G28.cpp b/Marlin/src/gcode/calibrate/G28.cpp index c0bc179869e2..c4effe7d58b8 100644 --- a/Marlin/src/gcode/calibrate/G28.cpp +++ b/Marlin/src/gcode/calibrate/G28.cpp @@ -324,7 +324,7 @@ void GcodeSuite::G28() { ? 0 : (parser.seenval('R') ? parser.value_linear_units() : Z_HOMING_HEIGHT); - if (z_homing_height && (doX || doY || (ENABLED(Z_SAFE_HOMING) && doZ))) { + if (z_homing_height && (doX || doY || TERN0(Z_SAFE_HOMING, doZ))) { // Raise Z before homing any other axes and z is not already high enough (never lower z) if (DEBUGGING(LEVELING)) DEBUG_ECHOLNPAIR("Raise Z (before homing) by ", z_homing_height); do_z_clearance(z_homing_height, true, DISABLED(UNKNOWN_Z_NO_RAISE)); @@ -337,7 +337,7 @@ void GcodeSuite::G28() { #endif // Home Y (before X) - if (ENABLED(HOME_Y_BEFORE_X) && (doY || (ENABLED(CODEPENDENT_XY_HOMING) && doX))) + if (ENABLED(HOME_Y_BEFORE_X) && (doY || TERN0(CODEPENDENT_XY_HOMING, doX))) homeaxis(Y_AXIS); // Home X diff --git a/Marlin/src/inc/SanityCheck.h b/Marlin/src/inc/SanityCheck.h index 0dfa3058411c..9f4c10dd53e1 100644 --- a/Marlin/src/inc/SanityCheck.h +++ b/Marlin/src/inc/SanityCheck.h @@ -525,6 +525,8 @@ #error "EVENT_GCODE_SD_STOP is now EVENT_GCODE_SD_ABORT." #elif defined(GRAPHICAL_TFT_ROTATE_180) #error "GRAPHICAL_TFT_ROTATE_180 is now TFT_ROTATION set to TFT_ROTATE_180." +#elif defined(PROBE_OFFSET_START) + #error "PROBE_OFFSET_START is now PROBE_OFFSET_WIZARD_START_Z." #elif defined(POWER_LOSS_PULL) #error "POWER_LOSS_PULL is now specifically POWER_LOSS_PULL(UP|DOWN)." #elif defined(FIL_RUNOUT_INVERTING) @@ -1345,25 +1347,32 @@ static_assert(Y_MAX_LENGTH >= Y_BED_SIZE, "Movement bounds (Y_MIN_POS, Y_MAX_POS #error "Z_MIN_PROBE_PIN must be defined if Z_MIN_PROBE_USES_Z_MIN_ENDSTOP_PIN is not enabled." #endif + /** + * Check for improper NOZZLE_TO_PROBE_OFFSET + */ + constexpr xyz_pos_t sanity_nozzle_to_probe_offset = NOZZLE_TO_PROBE_OFFSET; #if ENABLED(NOZZLE_AS_PROBE) - constexpr float sanity_nozzle_to_probe_offset[] = NOZZLE_TO_PROBE_OFFSET; - static_assert(sanity_nozzle_to_probe_offset[0] == 0.0 && sanity_nozzle_to_probe_offset[1] == 0.0, - "NOZZLE_AS_PROBE requires the X,Y offsets in NOZZLE_TO_PROBE_OFFSET to be 0,0."); - #endif - - #if DISABLED(NOZZLE_AS_PROBE) - static_assert(PROBING_MARGIN >= 0, "PROBING_MARGIN must be >= 0."); - static_assert(PROBING_MARGIN_BACK >= 0, "PROBING_MARGIN_BACK must be >= 0."); + static_assert(sanity_nozzle_to_probe_offset.x == 0 && sanity_nozzle_to_probe_offset.y == 0, + "NOZZLE_AS_PROBE requires the XY offsets in NOZZLE_TO_PROBE_OFFSET to both be 0."); + #else + static_assert(sanity_nozzle_to_probe_offset.z <= 0.25, + "Are you sure your Probe triggers above the nozzle? Set a negative Z value in the NOZZLE_TO_PROBE_OFFSET."); + #ifdef PROBE_OFFSET_WIZARD_START_Z + static_assert(PROBE_OFFSET_WIZARD_START_Z <= 0.25, + "Are you sure your Probe triggers above the nozzle? Set a negative value for PROBE_OFFSET_WIZARD_START_Z."); + #endif + static_assert(PROBING_MARGIN >= 0, "PROBING_MARGIN must be >= 0."); + static_assert(PROBING_MARGIN_BACK >= 0, "PROBING_MARGIN_BACK must be >= 0."); static_assert(PROBING_MARGIN_FRONT >= 0, "PROBING_MARGIN_FRONT must be >= 0."); - static_assert(PROBING_MARGIN_LEFT >= 0, "PROBING_MARGIN_LEFT must be >= 0."); + static_assert(PROBING_MARGIN_LEFT >= 0, "PROBING_MARGIN_LEFT must be >= 0."); static_assert(PROBING_MARGIN_RIGHT >= 0, "PROBING_MARGIN_RIGHT must be >= 0."); #endif #define _MARGIN(A) TERN(IS_SCARA, SCARA_PRINTABLE_RADIUS, TERN(DELTA, DELTA_PRINTABLE_RADIUS, ((A##_BED_SIZE) / 2))) - static_assert(PROBING_MARGIN < _MARGIN(X), "PROBING_MARGIN is too large."); - static_assert(PROBING_MARGIN_BACK < _MARGIN(Y), "PROBING_MARGIN_BACK is too large."); + static_assert(PROBING_MARGIN < _MARGIN(X), "PROBING_MARGIN is too large."); + static_assert(PROBING_MARGIN_BACK < _MARGIN(Y), "PROBING_MARGIN_BACK is too large."); static_assert(PROBING_MARGIN_FRONT < _MARGIN(Y), "PROBING_MARGIN_FRONT is too large."); - static_assert(PROBING_MARGIN_LEFT < _MARGIN(X), "PROBING_MARGIN_LEFT is too large."); + static_assert(PROBING_MARGIN_LEFT < _MARGIN(X), "PROBING_MARGIN_LEFT is too large."); static_assert(PROBING_MARGIN_RIGHT < _MARGIN(X), "PROBING_MARGIN_RIGHT is too large."); #undef _MARGIN diff --git a/Marlin/src/lcd/language/language_en.h b/Marlin/src/lcd/language/language_en.h index 04487fa13f27..af0903b91612 100644 --- a/Marlin/src/lcd/language/language_en.h +++ b/Marlin/src/lcd/language/language_en.h @@ -673,6 +673,8 @@ namespace Language_en { PROGMEM Language_Str MSG_REHEATING = _UxGT("Reheating..."); PROGMEM Language_Str MSG_PROBE_WIZARD = _UxGT("Z Probe Wizard"); + PROGMEM Language_Str MSG_PROBE_WIZARD_PROBING = _UxGT("Probing Z Reference"); + PROGMEM Language_Str MSG_PROBE_WIZARD_MOVING = _UxGT("Moving to Probing Pos"); PROGMEM Language_Str MSG_SOUND = _UxGT("Sound"); diff --git a/Marlin/src/lcd/marlinui.h b/Marlin/src/lcd/marlinui.h index ccf995bd7131..8e968abda0af 100644 --- a/Marlin/src/lcd/marlinui.h +++ b/Marlin/src/lcd/marlinui.h @@ -624,7 +624,7 @@ class MarlinUI { // // Special handling if a move is underway // - #if EITHER(DELTA_CALIBRATION_MENU, DELTA_AUTO_CALIBRATION) || (ENABLED(LCD_BED_LEVELING) && EITHER(PROBE_MANUALLY, MESH_BED_LEVELING)) || (ENABLED(PROBE_OFFSET_WIZARD) && defined(PROBE_OFFSET_WIZARD_XY_POS)) + #if ANY(DELTA_CALIBRATION_MENU, DELTA_AUTO_CALIBRATION, PROBE_OFFSET_WIZARD) || (ENABLED(LCD_BED_LEVELING) && EITHER(PROBE_MANUALLY, MESH_BED_LEVELING)) #define LCD_HAS_WAIT_FOR_MOVE 1 static bool wait_for_move; #else diff --git a/Marlin/src/lcd/menu/menu.h b/Marlin/src/lcd/menu/menu.h index 5782d2070a15..cf2f6b163379 100644 --- a/Marlin/src/lcd/menu/menu.h +++ b/Marlin/src/lcd/menu/menu.h @@ -220,7 +220,7 @@ void _lcd_draw_homing(); #endif #if ENABLED(PROBE_OFFSET_WIZARD) - void home_and_goto_probe_offset_wizard(); + void goto_probe_offset_wizard(); #endif #if ENABLED(LCD_BED_LEVELING) || (HAS_LEVELING && DISABLED(SLIM_LCD_MENUS)) diff --git a/Marlin/src/lcd/menu/menu_advanced.cpp b/Marlin/src/lcd/menu/menu_advanced.cpp index 268573beb028..3f2a6da11b50 100644 --- a/Marlin/src/lcd/menu/menu_advanced.cpp +++ b/Marlin/src/lcd/menu/menu_advanced.cpp @@ -488,7 +488,7 @@ void menu_backlash(); EDIT_ITEM(LCD_Z_OFFSET_TYPE, MSG_ZPROBE_ZOFFSET, &probe.offset.z, Z_PROBE_OFFSET_RANGE_MIN, Z_PROBE_OFFSET_RANGE_MAX); #if ENABLED(PROBE_OFFSET_WIZARD) - SUBMENU(MSG_PROBE_WIZARD, home_and_goto_probe_offset_wizard); + SUBMENU(MSG_PROBE_WIZARD, goto_probe_offset_wizard); #endif END_MENU(); diff --git a/Marlin/src/lcd/menu/menu_probe_offset.cpp b/Marlin/src/lcd/menu/menu_probe_offset.cpp index 9f215500982d..f2b08afd79aa 100644 --- a/Marlin/src/lcd/menu/menu_probe_offset.cpp +++ b/Marlin/src/lcd/menu/menu_probe_offset.cpp @@ -28,12 +28,6 @@ #if ENABLED(PROBE_OFFSET_WIZARD) -#ifndef PROBE_OFFSET_START - #error "PROBE_OFFSET_WIZARD requires a PROBE_OFFSET_START with a negative value." -#else - static_assert(PROBE_OFFSET_START < 0, "PROBE_OFFSET_START must be < 0. Please update your configuration."); -#endif - #include "menu_item.h" #include "menu_addon.h" #include "../../gcode/queue.h" @@ -46,21 +40,20 @@ #endif // Global storage -float z_offset_backup, calculated_z_offset; +float z_offset_backup, calculated_z_offset, z_offset_ref; TERN_(HAS_LEVELING, bool leveling_was_active); -void prepare_for_calibration() { - z_offset_backup = probe.offset.z; - - // Disable soft endstops for free Z movement - SET_SOFT_ENDSTOP_LOOSE(true); - - // Disable leveling for raw planner motion - #if HAS_LEVELING - leveling_was_active = planner.leveling_active; - set_bed_leveling_enabled(false); - #endif +inline void z_clearance_move() { + do_z_clearance( + #ifdef Z_AFTER_HOMING + Z_AFTER_HOMING + #elif defined(Z_HOMING_HEIGHT) + Z_HOMING_HEIGHT + #else + 10 + #endif + ); } void set_offset_and_go_back(const float &z) { @@ -77,7 +70,7 @@ void _goto_manual_move_z(const float scale) { void probe_offset_wizard_menu() { START_MENU(); - calculated_z_offset = probe.offset.z + current_position.z; + calculated_z_offset = probe.offset.z + current_position.z - z_offset_ref; if (LCD_HEIGHT >= 4) STATIC_ITEM(MSG_MOVE_NOZZLE_TO_BED, SS_CENTER|SS_INVERT); @@ -92,7 +85,7 @@ void probe_offset_wizard_menu() { char tmp[20], numstr[10]; // Determine digits needed right of decimal const uint8_t digs = !UNEAR_ZERO((SHORT_MANUAL_Z_MOVE) * 1000 - int((SHORT_MANUAL_Z_MOVE) * 1000)) ? 4 : - !UNEAR_ZERO((SHORT_MANUAL_Z_MOVE) * 100 - int((SHORT_MANUAL_Z_MOVE) * 100)) ? 3 : 2; + !UNEAR_ZERO((SHORT_MANUAL_Z_MOVE) * 100 - int((SHORT_MANUAL_Z_MOVE) * 100)) ? 3 : 2; sprintf_P(tmp, GET_TEXT(MSG_MOVE_Z_DIST), dtostrf(SHORT_MANUAL_Z_MOVE, 1, digs, numstr)); #if DISABLED(HAS_GRAPHICAL_TFT) extern const char NUL_STR[]; @@ -107,47 +100,86 @@ void probe_offset_wizard_menu() { ACTION_ITEM(MSG_BUTTON_DONE, []{ set_offset_and_go_back(calculated_z_offset); - do_z_clearance(20.0 - #ifdef Z_AFTER_HOMING - - 20.0 + Z_AFTER_HOMING - #endif - ); + current_position.z = z_offset_ref; // Set Z to z_offset_ref, as we can expect it is at probe height + sync_plan_position(); + z_clearance_move(); // Raise Z as if it was homed }); ACTION_ITEM(MSG_BUTTON_CANCEL, []{ set_offset_and_go_back(z_offset_backup); + // If wizard-homing was done by probe with with PROBE_OFFSET_WIZARD_START_Z + #if EITHER(Z_MIN_PROBE_USES_Z_MIN_ENDSTOP_PIN, USE_PROBE_FOR_Z_HOMING) && defined(PROBE_OFFSET_WIZARD_START_Z) + set_axis_never_homed(Z_AXIS); // On cancel the Z position needs correction + queue.inject_P(PSTR("G28Z")); + #else // Otherwise do a Z clearance move like after Homing + z_clearance_move(); + #endif }); END_MENU(); } -#ifdef PROBE_OFFSET_WIZARD_XY_POS +void prepare_for_probe_offset_wizard() { + if (ui.wait_for_move) return; - #define HAS_PROBE_OFFSET_WIZARD_XY_POS 1 + #if defined(PROBE_OFFSET_WIZARD_XY_POS) || NONE(Z_MIN_PROBE_USES_Z_MIN_ENDSTOP_PIN, USE_PROBE_FOR_Z_HOMING) + if (ui.should_draw()) MenuItem_static::draw(1, GET_TEXT(MSG_PROBE_WIZARD_PROBING)); - inline void goto_probe_offset_wizard() { - if (ui.wait_for_move) return; + #ifndef PROBE_OFFSET_WIZARD_XY_POS + #define PROBE_OFFSET_WIZARD_XY_POS XY_CENTER + #endif + // Get X and Y from configuration, or use center constexpr xy_pos_t wizard_pos = PROBE_OFFSET_WIZARD_XY_POS; - current_position = wizard_pos; + + // Probe for Z reference ui.wait_for_move = true; - line_to_current_position(MMM_TO_MMS(HOMING_FEEDRATE_XY)); // Could invoke idle() + z_offset_ref = probe.probe_at_point(wizard_pos, PROBE_PT_STOW, 0, true); ui.wait_for_move = false; - ui.synchronize(); - prepare_for_calibration(); - probe.offset.z = PROBE_OFFSET_START; - ui.goto_screen(probe_offset_wizard_menu); - ui.defer_status_screen(); - } -#endif + #endif + + // Move Nozzle to Probing/Homing Position + ui.wait_for_move = true; + current_position += probe.offset_xy; + line_to_current_position(MMM_TO_MMS(HOMING_FEEDRATE_XY)); + ui.synchronize(GET_TEXT(MSG_PROBE_WIZARD_MOVING)); + ui.wait_for_move = false; + + // Go to Calibration Menu + ui.goto_screen(probe_offset_wizard_menu); + ui.defer_status_screen(); +} + +void goto_probe_offset_wizard() { + ui.defer_status_screen(); + set_all_unhomed(); + + // Store probe.offset.z for Case: Cancel + z_offset_backup = probe.offset.z; + + #ifdef PROBE_OFFSET_WIZARD_START_Z + probe.offset.z = PROBE_OFFSET_WIZARD_START_Z; + #endif + + // Store Bed-Leveling-State and disable + #if HAS_LEVELING + leveling_was_active = planner.leveling_active; + set_bed_leveling_enabled(false); + #endif -void home_and_goto_probe_offset_wizard() { + // Home all axes queue.inject_P(G28_STR); + ui.goto_screen([]{ _lcd_draw_homing(); - if (all_axes_homed()) - ui.goto_screen(TERN(HAS_PROBE_OFFSET_WIZARD_XY_POS, goto_probe_offset_wizard, probe_offset_wizard_menu)); + if (all_axes_homed()) { + SET_SOFT_ENDSTOP_LOOSE(true); // Disable soft endstops for free Z movement + z_offset_ref = 0; // Set Z Value for Wizard Position to 0 + ui.goto_screen(prepare_for_probe_offset_wizard); + ui.defer_status_screen(); + } }); + } #endif // PROBE_OFFSET_WIZARD From 18853defdd2189ee595c6f8c2e4d8a16e41f9ce1 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Wed, 25 Nov 2020 21:40:56 -0600 Subject: [PATCH 19/47] Reduce warnings, extern "C" cleanup (#20279) --- Marlin/src/HAL/AVR/HAL.h | 16 ++++++++++------ Marlin/src/HAL/DUE/HAL.h | 12 +++++++++--- Marlin/src/HAL/ESP32/HAL.h | 12 +++++++++--- Marlin/src/HAL/ESP32/timers.h | 8 +++++--- Marlin/src/HAL/HAL.h | 4 ++++ Marlin/src/HAL/LINUX/HAL.cpp | 17 ++++++----------- Marlin/src/HAL/LINUX/HAL.h | 12 +++++++++--- Marlin/src/HAL/LINUX/include/Arduino.h | 11 ++++++----- Marlin/src/HAL/LPC1768/HAL.cpp | 17 ++++++----------- Marlin/src/HAL/LPC1768/HAL.h | 12 +++++++++--- Marlin/src/HAL/LPC1768/MarlinSerial.cpp | 19 ++++--------------- Marlin/src/HAL/LPC1768/main.cpp | 12 ++++++------ Marlin/src/HAL/SAMD51/HAL.h | 12 +++++++++--- Marlin/src/HAL/STM32/HAL.h | 10 +++++++--- Marlin/src/HAL/STM32F1/HAL.h | 10 +++++++--- Marlin/src/HAL/STM32F1/timers.h | 6 ++++-- Marlin/src/HAL/STM32_F4_F7/HAL.h | 10 +++++++--- Marlin/src/HAL/STM32_F4_F7/STM32F4/timers.cpp | 8 +++----- Marlin/src/HAL/STM32_F4_F7/STM32F7/timers.cpp | 8 +++----- Marlin/src/HAL/TEENSY31_32/HAL.h | 16 ++++++++++------ Marlin/src/HAL/TEENSY31_32/timers.h | 4 ++-- Marlin/src/HAL/TEENSY35_36/HAL.h | 16 ++++++++++------ Marlin/src/HAL/TEENSY35_36/timers.h | 4 ++-- Marlin/src/HAL/TEENSY40_41/HAL.h | 16 ++++++++++------ Marlin/src/HAL/TEENSY40_41/timers.h | 10 ++++++---- Marlin/src/libs/duration_t.h | 10 +++++++--- 26 files changed, 170 insertions(+), 122 deletions(-) diff --git a/Marlin/src/HAL/AVR/HAL.h b/Marlin/src/HAL/AVR/HAL.h index ce15ed29fb3a..aa6a32132032 100644 --- a/Marlin/src/HAL/AVR/HAL.h +++ b/Marlin/src/HAL/AVR/HAL.h @@ -122,12 +122,16 @@ inline uint8_t HAL_get_reset_source() { return MCUSR; } inline void HAL_reboot() {} // reboot the board or restart the bootloader -#pragma GCC diagnostic push -#pragma GCC diagnostic ignored "-Wunused-function" -extern "C" { - int freeMemory(); -} -#pragma GCC diagnostic pop +#if GCC_VERSION <= 50000 + #pragma GCC diagnostic push + #pragma GCC diagnostic ignored "-Wunused-function" +#endif + +extern "C" int freeMemory(); + +#if GCC_VERSION <= 50000 + #pragma GCC diagnostic pop +#endif // ADC #ifdef DIDR2 diff --git a/Marlin/src/HAL/DUE/HAL.h b/Marlin/src/HAL/DUE/HAL.h index 88ace5957535..395ca4ccc971 100644 --- a/Marlin/src/HAL/DUE/HAL.h +++ b/Marlin/src/HAL/DUE/HAL.h @@ -153,10 +153,16 @@ void HAL_init(); // void _delay_ms(const int delay); -#pragma GCC diagnostic push -#pragma GCC diagnostic ignored "-Wunused-function" +#if GCC_VERSION <= 50000 + #pragma GCC diagnostic push + #pragma GCC diagnostic ignored "-Wunused-function" +#endif + int freeMemory(); -#pragma GCC diagnostic pop + +#if GCC_VERSION <= 50000 + #pragma GCC diagnostic pop +#endif #ifdef __cplusplus extern "C" { diff --git a/Marlin/src/HAL/ESP32/HAL.h b/Marlin/src/HAL/ESP32/HAL.h index ebc16c9525e7..5ef13e0c21d4 100644 --- a/Marlin/src/HAL/ESP32/HAL.h +++ b/Marlin/src/HAL/ESP32/HAL.h @@ -100,10 +100,16 @@ inline void HAL_reboot() {} // reboot the board or restart the bootloader void _delay_ms(int delay); -#pragma GCC diagnostic push -#pragma GCC diagnostic ignored "-Wunused-function" +#if GCC_VERSION <= 50000 + #pragma GCC diagnostic push + #pragma GCC diagnostic ignored "-Wunused-function" +#endif + int freeMemory(); -#pragma GCC diagnostic pop + +#if GCC_VERSION <= 50000 + #pragma GCC diagnostic pop +#endif void analogWrite(pin_t pin, int value); diff --git a/Marlin/src/HAL/ESP32/timers.h b/Marlin/src/HAL/ESP32/timers.h index 7d35186b1cda..98386e3980b9 100644 --- a/Marlin/src/HAL/ESP32/timers.h +++ b/Marlin/src/HAL/ESP32/timers.h @@ -91,9 +91,11 @@ typedef uint64_t hal_timer_t; #define HAL_PWM_TIMER_ISR() extern "C" void pwmTC_Handler() #endif -extern "C" void tempTC_Handler(); -extern "C" void stepTC_Handler(); -extern "C" void pwmTC_Handler(); +extern "C" { + void tempTC_Handler(); + void stepTC_Handler(); + void pwmTC_Handler(); +} // ------------------------ // Types diff --git a/Marlin/src/HAL/HAL.h b/Marlin/src/HAL/HAL.h index 5eca2f7eacfe..9eefda8fb1e2 100644 --- a/Marlin/src/HAL/HAL.h +++ b/Marlin/src/HAL/HAL.h @@ -23,6 +23,10 @@ #include "platforms.h" +#ifndef GCC_VERSION + #define GCC_VERSION (__GNUC__ * 10000 + __GNUC_MINOR__ * 100 + __GNUC_PATCHLEVEL__) +#endif + #include HAL_PATH(.,HAL.h) #ifdef SERIAL_PORT_2 diff --git a/Marlin/src/HAL/LINUX/HAL.cpp b/Marlin/src/HAL/LINUX/HAL.cpp index d7d7c2d2b4f0..ee9e31e140e8 100644 --- a/Marlin/src/HAL/LINUX/HAL.cpp +++ b/Marlin/src/HAL/LINUX/HAL.cpp @@ -27,18 +27,13 @@ HalSerial usb_serial; // U8glib required functions -extern "C" void u8g_xMicroDelay(uint16_t val) { - DELAY_US(val); -} -extern "C" void u8g_MicroDelay() { - u8g_xMicroDelay(1); -} -extern "C" void u8g_10MicroDelay() { - u8g_xMicroDelay(10); -} -extern "C" void u8g_Delay(uint16_t val) { - delay(val); +extern "C" { + void u8g_xMicroDelay(uint16_t val) { DELAY_US(val); } + void u8g_MicroDelay() { u8g_xMicroDelay(1); } + void u8g_10MicroDelay() { u8g_xMicroDelay(10); } + void u8g_Delay(uint16_t val) { delay(val); } } + //************************// // return free heap space diff --git a/Marlin/src/HAL/LINUX/HAL.h b/Marlin/src/HAL/LINUX/HAL.h index 1c8dbfd4dcfe..729f6c856e19 100644 --- a/Marlin/src/HAL/LINUX/HAL.h +++ b/Marlin/src/HAL/LINUX/HAL.h @@ -79,10 +79,16 @@ extern HalSerial usb_serial; inline void HAL_init() {} // Utility functions -#pragma GCC diagnostic push -#pragma GCC diagnostic ignored "-Wunused-function" +#if GCC_VERSION <= 50000 + #pragma GCC diagnostic push + #pragma GCC diagnostic ignored "-Wunused-function" +#endif + int freeMemory(); -#pragma GCC diagnostic pop + +#if GCC_VERSION <= 50000 + #pragma GCC diagnostic pop +#endif // ADC #define HAL_ADC_VREF 5.0 diff --git a/Marlin/src/HAL/LINUX/include/Arduino.h b/Marlin/src/HAL/LINUX/include/Arduino.h index e28b474ede96..6aeb0db58335 100644 --- a/Marlin/src/HAL/LINUX/include/Arduino.h +++ b/Marlin/src/HAL/LINUX/include/Arduino.h @@ -67,8 +67,11 @@ void cli(); // Disable void sei(); // Enable void attachInterrupt(uint32_t pin, void (*callback)(), uint32_t mode); void detachInterrupt(uint32_t pin); -extern "C" void GpioEnableInt(uint32_t port, uint32_t pin, uint32_t mode); -extern "C" void GpioDisableInt(uint32_t port, uint32_t pin); + +extern "C" { + void GpioEnableInt(uint32_t port, uint32_t pin, uint32_t mode); + void GpioDisableInt(uint32_t port, uint32_t pin); +} // Program Memory #define pgm_read_ptr(addr) (*((void**)(addr))) @@ -92,9 +95,7 @@ using std::memcpy; #define strlen_P strlen // Time functions -extern "C" { - void delay(const int milis); -} +extern "C" void delay(const int milis); void _delay_ms(const int delay); void delayMicroseconds(unsigned long); uint32_t millis(); diff --git a/Marlin/src/HAL/LPC1768/HAL.cpp b/Marlin/src/HAL/LPC1768/HAL.cpp index 939f1e8a9408..3614e953851c 100644 --- a/Marlin/src/HAL/LPC1768/HAL.cpp +++ b/Marlin/src/HAL/LPC1768/HAL.cpp @@ -32,18 +32,13 @@ uint32_t HAL_adc_reading = 0; // U8glib required functions -extern "C" void u8g_xMicroDelay(uint16_t val) { - DELAY_US(val); -} -extern "C" void u8g_MicroDelay() { - u8g_xMicroDelay(1); -} -extern "C" void u8g_10MicroDelay() { - u8g_xMicroDelay(10); -} -extern "C" void u8g_Delay(uint16_t val) { - delay(val); +extern "C" { + void u8g_xMicroDelay(uint16_t val) { DELAY_US(val); } + void u8g_MicroDelay() { u8g_xMicroDelay(1); } + void u8g_10MicroDelay() { u8g_xMicroDelay(10); } + void u8g_Delay(uint16_t val) { delay(val); } } + //************************// // return free heap space diff --git a/Marlin/src/HAL/LPC1768/HAL.h b/Marlin/src/HAL/LPC1768/HAL.h index cb637e715dda..51a13389b1e6 100644 --- a/Marlin/src/HAL/LPC1768/HAL.h +++ b/Marlin/src/HAL/LPC1768/HAL.h @@ -107,10 +107,16 @@ extern "C" volatile uint32_t _millis; // // Utility functions // -#pragma GCC diagnostic push -#pragma GCC diagnostic ignored "-Wunused-function" +#if GCC_VERSION <= 50000 + #pragma GCC diagnostic push + #pragma GCC diagnostic ignored "-Wunused-function" +#endif + int freeMemory(); -#pragma GCC diagnostic pop + +#if GCC_VERSION <= 50000 + #pragma GCC diagnostic pop +#endif // // ADC API diff --git a/Marlin/src/HAL/LPC1768/MarlinSerial.cpp b/Marlin/src/HAL/LPC1768/MarlinSerial.cpp index 5374e005d3da..baad3f8f26b7 100644 --- a/Marlin/src/HAL/LPC1768/MarlinSerial.cpp +++ b/Marlin/src/HAL/LPC1768/MarlinSerial.cpp @@ -26,30 +26,19 @@ #if USING_SERIAL_0 MarlinSerial MSerial(LPC_UART0); - extern "C" void UART0_IRQHandler() { - MSerial.IRQHandler(); - } + extern "C" void UART0_IRQHandler() { MSerial.IRQHandler(); } #endif - #if USING_SERIAL_1 MarlinSerial MSerial1((LPC_UART_TypeDef *) LPC_UART1); - extern "C" void UART1_IRQHandler() { - MSerial1.IRQHandler(); - } + extern "C" void UART1_IRQHandler() { MSerial1.IRQHandler(); } #endif - #if USING_SERIAL_2 MarlinSerial MSerial2(LPC_UART2); - extern "C" void UART2_IRQHandler() { - MSerial2.IRQHandler(); - } + extern "C" void UART2_IRQHandler() { MSerial2.IRQHandler(); } #endif - #if USING_SERIAL_3 MarlinSerial MSerial3(LPC_UART3); - extern "C" void UART3_IRQHandler() { - MSerial3.IRQHandler(); - } + extern "C" void UART3_IRQHandler() { MSerial3.IRQHandler(); } #endif #endif // TARGET_LPC1768 diff --git a/Marlin/src/HAL/LPC1768/main.cpp b/Marlin/src/HAL/LPC1768/main.cpp index 085b8ce04bcf..96faf54d7fd2 100644 --- a/Marlin/src/HAL/LPC1768/main.cpp +++ b/Marlin/src/HAL/LPC1768/main.cpp @@ -31,18 +31,18 @@ #include #include -extern "C" { - #include -} - #include "../../inc/MarlinConfig.h" #include "../../core/millis_t.h" #include "../../sd/cardreader.h" extern uint32_t MSC_SD_Init(uint8_t pdrv); -extern "C" int isLPC1769(); -extern "C" void disk_timerproc(); + +extern "C" { + #include + extern "C" int isLPC1769(); + extern "C" void disk_timerproc(); +} void SysTick_Callback() { disk_timerproc(); } diff --git a/Marlin/src/HAL/SAMD51/HAL.h b/Marlin/src/HAL/SAMD51/HAL.h index 7cb3635bd7c9..ff9310114641 100644 --- a/Marlin/src/HAL/SAMD51/HAL.h +++ b/Marlin/src/HAL/SAMD51/HAL.h @@ -135,10 +135,16 @@ void HAL_idletask(); // FORCE_INLINE void _delay_ms(const int delay_ms) { delay(delay_ms); } -#pragma GCC diagnostic push -#pragma GCC diagnostic ignored "-Wunused-function" +#if GCC_VERSION <= 50000 + #pragma GCC diagnostic push + #pragma GCC diagnostic ignored "-Wunused-function" +#endif + int freeMemory(); -#pragma GCC diagnostic pop + +#if GCC_VERSION <= 50000 + #pragma GCC diagnostic pop +#endif #ifdef __cplusplus extern "C" { diff --git a/Marlin/src/HAL/STM32/HAL.h b/Marlin/src/HAL/STM32/HAL.h index c92c8890ea96..16dc7a453994 100644 --- a/Marlin/src/HAL/STM32/HAL.h +++ b/Marlin/src/HAL/STM32/HAL.h @@ -140,15 +140,19 @@ void _delay_ms(const int delay); extern "C" char* _sbrk(int incr); -#pragma GCC diagnostic push -#pragma GCC diagnostic ignored "-Wunused-function" +#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(_sbrk(0)); } -#pragma GCC diagnostic pop +#if GCC_VERSION <= 50000 + #pragma GCC diagnostic pop +#endif // // ADC diff --git a/Marlin/src/HAL/STM32F1/HAL.h b/Marlin/src/HAL/STM32F1/HAL.h index 2880865dbbcc..06f75662cffa 100644 --- a/Marlin/src/HAL/STM32F1/HAL.h +++ b/Marlin/src/HAL/STM32F1/HAL.h @@ -189,8 +189,10 @@ inline void HAL_reboot() {} // reboot the board or restart the bootloader void _delay_ms(const int delay); -#pragma GCC diagnostic push -#pragma GCC diagnostic ignored "-Wunused-function" +#if GCC_VERSION <= 50000 + #pragma GCC diagnostic push + #pragma GCC diagnostic ignored "-Wunused-function" +#endif /* extern "C" { @@ -213,7 +215,9 @@ static int freeMemory() { return &top - reinterpret_cast(_sbrk(0)); } -#pragma GCC diagnostic pop +#if GCC_VERSION <= 50000 + #pragma GCC diagnostic pop +#endif // // ADC diff --git a/Marlin/src/HAL/STM32F1/timers.h b/Marlin/src/HAL/STM32F1/timers.h index 6f360f6bfc39..3e2e7775f1e3 100644 --- a/Marlin/src/HAL/STM32F1/timers.h +++ b/Marlin/src/HAL/STM32F1/timers.h @@ -129,8 +129,10 @@ timer_dev* get_timer_dev(int number); #define HAL_STEP_TIMER_ISR() extern "C" void stepTC_Handler() #endif -extern "C" void tempTC_Handler(); -extern "C" void stepTC_Handler(); +extern "C" { + void tempTC_Handler(); + void stepTC_Handler(); +} // ------------------------ // Public Variables diff --git a/Marlin/src/HAL/STM32_F4_F7/HAL.h b/Marlin/src/HAL/STM32_F4_F7/HAL.h index 00a65de7926f..85fbf098ff85 100644 --- a/Marlin/src/HAL/STM32_F4_F7/HAL.h +++ b/Marlin/src/HAL/STM32_F4_F7/HAL.h @@ -162,15 +162,19 @@ int freeMemory() { } */ -#pragma GCC diagnostic push -#pragma GCC diagnostic ignored "-Wunused-function" +#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(_sbrk(0)); } -#pragma GCC diagnostic pop +#if GCC_VERSION <= 50000 + #pragma GCC diagnostic pop +#endif // // ADC diff --git a/Marlin/src/HAL/STM32_F4_F7/STM32F4/timers.cpp b/Marlin/src/HAL/STM32_F4_F7/STM32F4/timers.cpp index dc41f891318d..8b753f72902e 100644 --- a/Marlin/src/HAL/STM32_F4_F7/STM32F4/timers.cpp +++ b/Marlin/src/HAL/STM32_F4_F7/STM32F4/timers.cpp @@ -79,11 +79,9 @@ void HAL_timer_start(const uint8_t timer_num, const uint32_t frequency) { HAL_TIM_Base_Start_IT(&TimerHandle[timer_num].handle); } -extern "C" void TIM5_IRQHandler() { - ((void(*)())TimerHandle[0].callback)(); -} -extern "C" void TIM7_IRQHandler() { - ((void(*)())TimerHandle[1].callback)(); +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) { diff --git a/Marlin/src/HAL/STM32_F4_F7/STM32F7/timers.cpp b/Marlin/src/HAL/STM32_F4_F7/STM32F7/timers.cpp index f7ded7454dd9..bc8f76af0987 100644 --- a/Marlin/src/HAL/STM32_F4_F7/STM32F7/timers.cpp +++ b/Marlin/src/HAL/STM32_F4_F7/STM32F7/timers.cpp @@ -83,11 +83,9 @@ void HAL_timer_start(const uint8_t timer_num, const uint32_t frequency) { } //forward the interrupt -extern "C" void TIM5_IRQHandler() { - ((void(*)())timerConfig[0].callback)(); -} -extern "C" void TIM7_IRQHandler() { - ((void(*)())timerConfig[1].callback)(); +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) { diff --git a/Marlin/src/HAL/TEENSY31_32/HAL.h b/Marlin/src/HAL/TEENSY31_32/HAL.h index 8ab358e9e1e5..9156aadb4de0 100644 --- a/Marlin/src/HAL/TEENSY31_32/HAL.h +++ b/Marlin/src/HAL/TEENSY31_32/HAL.h @@ -97,12 +97,16 @@ inline void HAL_reboot() {} // reboot the board or restart the bootloader FORCE_INLINE void _delay_ms(const int delay_ms) { delay(delay_ms); } -#pragma GCC diagnostic push -#pragma GCC diagnostic ignored "-Wunused-function" -extern "C" { - int freeMemory(); -} -#pragma GCC diagnostic pop +#if GCC_VERSION <= 50000 + #pragma GCC diagnostic push + #pragma GCC diagnostic ignored "-Wunused-function" +#endif + +extern "C" int freeMemory(); + +#if GCC_VERSION <= 50000 + #pragma GCC diagnostic pop +#endif // ADC diff --git a/Marlin/src/HAL/TEENSY31_32/timers.h b/Marlin/src/HAL/TEENSY31_32/timers.h index 135b32883084..61b86735967e 100644 --- a/Marlin/src/HAL/TEENSY31_32/timers.h +++ b/Marlin/src/HAL/TEENSY31_32/timers.h @@ -74,10 +74,10 @@ typedef uint32_t hal_timer_t; #define DISABLE_TEMPERATURE_INTERRUPT() HAL_timer_disable_interrupt(TEMP_TIMER_NUM) #ifndef HAL_STEP_TIMER_ISR - #define HAL_STEP_TIMER_ISR() extern "C" void ftm0_isr() //void TC3_Handler() + #define HAL_STEP_TIMER_ISR() extern "C" void ftm0_isr() //void TC3_Handler() #endif #ifndef HAL_TEMP_TIMER_ISR - #define HAL_TEMP_TIMER_ISR() extern "C" void ftm1_isr() //void TC4_Handler() + #define HAL_TEMP_TIMER_ISR() extern "C" void ftm1_isr() //void TC4_Handler() #endif void HAL_timer_start(const uint8_t timer_num, const uint32_t frequency); diff --git a/Marlin/src/HAL/TEENSY35_36/HAL.h b/Marlin/src/HAL/TEENSY35_36/HAL.h index 2b735d6224f4..04151e837861 100644 --- a/Marlin/src/HAL/TEENSY35_36/HAL.h +++ b/Marlin/src/HAL/TEENSY35_36/HAL.h @@ -103,12 +103,16 @@ inline void HAL_reboot() {} // reboot the board or restart the bootloader FORCE_INLINE void _delay_ms(const int delay_ms) { delay(delay_ms); } -#pragma GCC diagnostic push -#pragma GCC diagnostic ignored "-Wunused-function" -extern "C" { - int freeMemory(); -} -#pragma GCC diagnostic pop +#if GCC_VERSION <= 50000 + #pragma GCC diagnostic push + #pragma GCC diagnostic ignored "-Wunused-function" +#endif + +extern "C" int freeMemory(); + +#if GCC_VERSION <= 50000 + #pragma GCC diagnostic pop +#endif // ADC diff --git a/Marlin/src/HAL/TEENSY35_36/timers.h b/Marlin/src/HAL/TEENSY35_36/timers.h index 5c623cd80192..99269ac6571f 100644 --- a/Marlin/src/HAL/TEENSY35_36/timers.h +++ b/Marlin/src/HAL/TEENSY35_36/timers.h @@ -73,10 +73,10 @@ typedef uint32_t hal_timer_t; #define DISABLE_TEMPERATURE_INTERRUPT() HAL_timer_disable_interrupt(TEMP_TIMER_NUM) #ifndef HAL_STEP_TIMER_ISR - #define HAL_STEP_TIMER_ISR() extern "C" void ftm0_isr() //void TC3_Handler() + #define HAL_STEP_TIMER_ISR() extern "C" void ftm0_isr() //void TC3_Handler() #endif #ifndef HAL_TEMP_TIMER_ISR - #define HAL_TEMP_TIMER_ISR() extern "C" void ftm1_isr() //void TC4_Handler() + #define HAL_TEMP_TIMER_ISR() extern "C" void ftm1_isr() //void TC4_Handler() #endif void HAL_timer_start(const uint8_t timer_num, const uint32_t frequency); diff --git a/Marlin/src/HAL/TEENSY40_41/HAL.h b/Marlin/src/HAL/TEENSY40_41/HAL.h index 1e0043342dd6..28f511631eea 100644 --- a/Marlin/src/HAL/TEENSY40_41/HAL.h +++ b/Marlin/src/HAL/TEENSY40_41/HAL.h @@ -120,12 +120,16 @@ uint8_t HAL_get_reset_source(); FORCE_INLINE void _delay_ms(const int delay_ms) { delay(delay_ms); } -#pragma GCC diagnostic push -#pragma GCC diagnostic ignored "-Wunused-function" -extern "C" { - uint32_t freeMemory(); -} -#pragma GCC diagnostic pop +#if GCC_VERSION <= 50000 + #pragma GCC diagnostic push + #pragma GCC diagnostic ignored "-Wunused-function" +#endif + +extern "C" uint32_t freeMemory(); + +#if GCC_VERSION <= 50000 + #pragma GCC diagnostic pop +#endif // ADC diff --git a/Marlin/src/HAL/TEENSY40_41/timers.h b/Marlin/src/HAL/TEENSY40_41/timers.h index 7e4cd080cb88..556333d7f408 100644 --- a/Marlin/src/HAL/TEENSY40_41/timers.h +++ b/Marlin/src/HAL/TEENSY40_41/timers.h @@ -72,14 +72,16 @@ typedef uint32_t hal_timer_t; #define DISABLE_TEMPERATURE_INTERRUPT() HAL_timer_disable_interrupt(TEMP_TIMER_NUM) #ifndef HAL_STEP_TIMER_ISR - #define HAL_STEP_TIMER_ISR() extern "C" void stepTC_Handler() // GPT1_Handler() + #define HAL_STEP_TIMER_ISR() extern "C" void stepTC_Handler() // GPT1_Handler() #endif #ifndef HAL_TEMP_TIMER_ISR - #define HAL_TEMP_TIMER_ISR() extern "C" void tempTC_Handler() // GPT2_Handler() + #define HAL_TEMP_TIMER_ISR() extern "C" void tempTC_Handler() // GPT2_Handler() #endif -extern "C" void stepTC_Handler(); -extern "C" void tempTC_Handler(); +extern "C" { + void stepTC_Handler(); + void tempTC_Handler(); +} void HAL_timer_start(const uint8_t timer_num, const uint32_t frequency); diff --git a/Marlin/src/libs/duration_t.h b/Marlin/src/libs/duration_t.h index 9c1d72dfaff3..bd654b7bad1e 100644 --- a/Marlin/src/libs/duration_t.h +++ b/Marlin/src/libs/duration_t.h @@ -106,8 +106,10 @@ struct duration_t { return this->value; } - #pragma GCC diagnostic push - #pragma GCC diagnostic ignored "-Wformat-overflow" + #if GCC_VERSION <= 50000 + #pragma GCC diagnostic push + #pragma GCC diagnostic ignored "-Wformat-overflow" + #endif /** * @brief Formats the duration as a string @@ -167,5 +169,7 @@ struct duration_t { } } - #pragma GCC diagnostic pop + #if GCC_VERSION <= 50000 + #pragma GCC diagnostic pop + #endif }; From 3a396a25dc9e33be2c18a1bdc23600295e42c82e Mon Sep 17 00:00:00 2001 From: Jason Smith Date: Wed, 25 Nov 2020 22:37:18 -0800 Subject: [PATCH 20/47] Retire HAL for STM32F4 / F7 (#20153) --- .github/workflows/test-builds.yml | 21 +- Marlin/src/HAL/STM32/pinsDebug.h | 258 ++++- Marlin/src/HAL/STM32/pinsDebug_STM32GENERIC.h | 125 --- Marlin/src/HAL/STM32/pinsDebug_STM32duino.h | 273 ------ Marlin/src/HAL/STM32F1/pinsDebug.h | 104 +- Marlin/src/HAL/STM32_F4_F7/HAL.cpp | 95 -- Marlin/src/HAL/STM32_F4_F7/HAL.h | 203 ---- Marlin/src/HAL/STM32_F4_F7/HAL_SPI.cpp | 164 ---- Marlin/src/HAL/STM32_F4_F7/README.md | 6 - Marlin/src/HAL/STM32_F4_F7/STM32F4/README.md | 12 - Marlin/src/HAL/STM32_F4_F7/STM32F4/timers.cpp | 113 --- Marlin/src/HAL/STM32_F4_F7/STM32F4/timers.h | 134 --- Marlin/src/HAL/STM32_F4_F7/STM32F7/README.md | 27 - .../src/HAL/STM32_F4_F7/STM32F7/TMC2660.cpp | 898 ------------------ Marlin/src/HAL/STM32_F4_F7/STM32F7/TMC2660.h | 593 ------------ Marlin/src/HAL/STM32_F4_F7/STM32F7/timers.cpp | 127 --- Marlin/src/HAL/STM32_F4_F7/STM32F7/timers.h | 107 --- Marlin/src/HAL/STM32_F4_F7/Servo.cpp | 51 - Marlin/src/HAL/STM32_F4_F7/Servo.h | 41 - Marlin/src/HAL/STM32_F4_F7/eeprom_emul.cpp | 535 ----------- Marlin/src/HAL/STM32_F4_F7/eeprom_emul.h | 114 --- Marlin/src/HAL/STM32_F4_F7/eeprom_flash.cpp | 111 --- Marlin/src/HAL/STM32_F4_F7/eeprom_wired.cpp | 77 -- .../src/HAL/STM32_F4_F7/endstop_interrupts.h | 49 - Marlin/src/HAL/STM32_F4_F7/fastio.h | 310 ------ .../HAL/STM32_F4_F7/inc/Conditionals_LCD.h | 26 - .../HAL/STM32_F4_F7/inc/Conditionals_adv.h | 22 - .../HAL/STM32_F4_F7/inc/Conditionals_post.h | 29 - Marlin/src/HAL/STM32_F4_F7/inc/SanityCheck.h | 41 - Marlin/src/HAL/STM32_F4_F7/pinsDebug.h | 27 - Marlin/src/HAL/STM32_F4_F7/spi_pins.h | 35 - Marlin/src/HAL/STM32_F4_F7/timers.h | 28 - Marlin/src/HAL/STM32_F4_F7/watchdog.cpp | 57 -- Marlin/src/HAL/STM32_F4_F7/watchdog.h | 27 - Marlin/src/HAL/platforms.h | 2 - .../src/HAL/shared/backtrace/unwmemaccess.cpp | 11 - Marlin/src/HAL/shared/servo.h | 2 - Marlin/src/core/boards.h | 50 +- Marlin/src/core/macros.h | 6 +- Marlin/src/module/stepper/TMC26X.h | 6 +- Marlin/src/pins/pins.h | 18 +- .../pins/{stm32f4 => stm32f1}/pins_BEAST.h | 4 +- .../src/pins/stm32f4/pins_GENERIC_STM32F4.h | 197 ---- Marlin/src/pins/stm32f7/pins_THE_BORG.h | 183 ---- buildroot/tests/BIGTREE_SKR_PRO-tests | 2 +- .../tests/{STM32F7-tests => REMRAM_V1-tests} | 2 +- buildroot/tests/STM32F103RC_btt-tests | 1 + buildroot/tests/STM32F4-tests | 16 - platformio.ini | 17 +- 49 files changed, 399 insertions(+), 4958 deletions(-) delete mode 100644 Marlin/src/HAL/STM32/pinsDebug_STM32GENERIC.h delete mode 100644 Marlin/src/HAL/STM32/pinsDebug_STM32duino.h delete mode 100644 Marlin/src/HAL/STM32_F4_F7/HAL.cpp delete mode 100644 Marlin/src/HAL/STM32_F4_F7/HAL.h delete mode 100644 Marlin/src/HAL/STM32_F4_F7/HAL_SPI.cpp delete mode 100644 Marlin/src/HAL/STM32_F4_F7/README.md delete mode 100644 Marlin/src/HAL/STM32_F4_F7/STM32F4/README.md delete mode 100644 Marlin/src/HAL/STM32_F4_F7/STM32F4/timers.cpp delete mode 100644 Marlin/src/HAL/STM32_F4_F7/STM32F4/timers.h delete mode 100644 Marlin/src/HAL/STM32_F4_F7/STM32F7/README.md delete mode 100644 Marlin/src/HAL/STM32_F4_F7/STM32F7/TMC2660.cpp delete mode 100644 Marlin/src/HAL/STM32_F4_F7/STM32F7/TMC2660.h delete mode 100644 Marlin/src/HAL/STM32_F4_F7/STM32F7/timers.cpp delete mode 100644 Marlin/src/HAL/STM32_F4_F7/STM32F7/timers.h delete mode 100644 Marlin/src/HAL/STM32_F4_F7/Servo.cpp delete mode 100644 Marlin/src/HAL/STM32_F4_F7/Servo.h delete mode 100644 Marlin/src/HAL/STM32_F4_F7/eeprom_emul.cpp delete mode 100644 Marlin/src/HAL/STM32_F4_F7/eeprom_emul.h delete mode 100644 Marlin/src/HAL/STM32_F4_F7/eeprom_flash.cpp delete mode 100644 Marlin/src/HAL/STM32_F4_F7/eeprom_wired.cpp delete mode 100644 Marlin/src/HAL/STM32_F4_F7/endstop_interrupts.h delete mode 100644 Marlin/src/HAL/STM32_F4_F7/fastio.h delete mode 100644 Marlin/src/HAL/STM32_F4_F7/inc/Conditionals_LCD.h delete mode 100644 Marlin/src/HAL/STM32_F4_F7/inc/Conditionals_adv.h delete mode 100644 Marlin/src/HAL/STM32_F4_F7/inc/Conditionals_post.h delete mode 100644 Marlin/src/HAL/STM32_F4_F7/inc/SanityCheck.h delete mode 100644 Marlin/src/HAL/STM32_F4_F7/pinsDebug.h delete mode 100644 Marlin/src/HAL/STM32_F4_F7/spi_pins.h delete mode 100644 Marlin/src/HAL/STM32_F4_F7/timers.h delete mode 100644 Marlin/src/HAL/STM32_F4_F7/watchdog.cpp delete mode 100644 Marlin/src/HAL/STM32_F4_F7/watchdog.h rename Marlin/src/pins/{stm32f4 => stm32f1}/pins_BEAST.h (98%) delete mode 100644 Marlin/src/pins/stm32f4/pins_GENERIC_STM32F4.h delete mode 100644 Marlin/src/pins/stm32f7/pins_THE_BORG.h rename buildroot/tests/{STM32F7-tests => REMRAM_V1-tests} (89%) delete mode 100644 buildroot/tests/STM32F4-tests diff --git a/.github/workflows/test-builds.yml b/.github/workflows/test-builds.yml index d87d10569d57..53ffbe0c08b1 100644 --- a/.github/workflows/test-builds.yml +++ b/.github/workflows/test-builds.yml @@ -54,7 +54,7 @@ jobs: - sanguino1284p - sanguino644p - # Extended STM32 Environments + # STM32F1 (Maple) Environments - STM32F103RC_btt - STM32F103RC_btt_USB @@ -64,38 +64,37 @@ jobs: - STM32F103RC_meeb - jgaurora_a5s_a1 - STM32F103VE_longer + - mks_robin + - mks_robin_lite + - mks_robin_pro + - STM32F103RET6_creality + - mks_robin_nano35 + + # STM32 (ST) Environments + - STM32F407VE_black - STM32F401VE_STEVAL - BIGTREE_BTT002 - BIGTREE_SKR_PRO - BIGTREE_GTR_V1_0 - - mks_robin - mks_robin_stm32 - ARMED - FYSETC_S6 - STM32F070CB_malyan - STM32F070RB_malyan - malyan_M300 - - mks_robin_lite - FLYF407ZG - rumba32 - - mks_robin_pro - - STM32F103RET6_creality - LERDGEX - - mks_robin_nano35 - mks_robin_nano35_stm32 - NUCLEO_F767ZI + - REMRAM_V1 # Put lengthy tests last - LPC1768 - LPC1769 - # STM32 with non-STM framework. both broken for now. they should use HAL_STM32 which is working. - - #- STM32F4 - #- STM32F7 - # Non-working environment tests #- at90usb1286_cdc #- STM32F103CB_malyan diff --git a/Marlin/src/HAL/STM32/pinsDebug.h b/Marlin/src/HAL/STM32/pinsDebug.h index ec08e3fd753f..77c93ee41e36 100644 --- a/Marlin/src/HAL/STM32/pinsDebug.h +++ b/Marlin/src/HAL/STM32/pinsDebug.h @@ -18,17 +18,257 @@ */ #pragma once -#if !(defined(NUM_DIGITAL_PINS) || defined(BOARD_NR_GPIO_PINS)) - #error "M43 not supported for this board" +#include + +#ifndef NUM_DIGITAL_PINS + // Only in ST's Arduino core (STM32duino, STM32Core) + #error "Expected NUM_DIGITAL_PINS not found" #endif -// Strange - STM32F4 comes to HAL_STM32 rather than HAL_STM32F4 for these files -#ifdef STM32F4 - #ifdef NUM_DIGITAL_PINS // Only in ST's Arduino core (STM32duino, STM32Core) - #include "pinsDebug_STM32duino.h" - #elif defined(BOARD_NR_GPIO_PINS) // Only in STM32GENERIC (Maple) - #include "pinsDebug_STM32GENERIC.h" +/** + * 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 - #error "M43 not supported for this board" + #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 diff --git a/Marlin/src/HAL/STM32/pinsDebug_STM32GENERIC.h b/Marlin/src/HAL/STM32/pinsDebug_STM32GENERIC.h deleted file mode 100644 index 9069d9f7bd8a..000000000000 --- a/Marlin/src/HAL/STM32/pinsDebug_STM32GENERIC.h +++ /dev/null @@ -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 . - * - */ -#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 diff --git a/Marlin/src/HAL/STM32/pinsDebug_STM32duino.h b/Marlin/src/HAL/STM32/pinsDebug_STM32duino.h deleted file mode 100644 index 71480153a717..000000000000 --- a/Marlin/src/HAL/STM32/pinsDebug_STM32duino.h +++ /dev/null @@ -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 . - * - */ -#pragma once - -#include - -#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 diff --git a/Marlin/src/HAL/STM32F1/pinsDebug.h b/Marlin/src/HAL/STM32F1/pinsDebug.h index 2d63ebd770f0..8e7a3d8135fd 100644 --- a/Marlin/src/HAL/STM32F1/pinsDebug.h +++ b/Marlin/src/HAL/STM32F1/pinsDebug.h @@ -18,10 +18,102 @@ */ #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 not supported for this board" +/** + * Support routines for STM32GENERIC (Maple) + */ + +/** + * 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 + +#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); +} diff --git a/Marlin/src/HAL/STM32_F4_F7/HAL.cpp b/Marlin/src/HAL/STM32_F4_F7/HAL.cpp deleted file mode 100644 index b4629d2afd12..000000000000 --- a/Marlin/src/HAL/STM32_F4_F7/HAL.cpp +++ /dev/null @@ -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 . - * - */ -#if defined(STM32GENERIC) && (defined(STM32F4) || defined(STM32F7)) - -#include "HAL.h" - -//#include - -// ------------------------ -// 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 -//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(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) diff --git a/Marlin/src/HAL/STM32_F4_F7/HAL.h b/Marlin/src/HAL/STM32_F4_F7/HAL.h deleted file mode 100644 index 85fbf098ff85..000000000000 --- a/Marlin/src/HAL/STM32_F4_F7/HAL.h +++ /dev/null @@ -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 . - * - */ -#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 - -#if defined(STM32F4) && USBCON - #include -#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(_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(_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 diff --git a/Marlin/src/HAL/STM32_F4_F7/HAL_SPI.cpp b/Marlin/src/HAL/STM32_F4_F7/HAL_SPI.cpp deleted file mode 100644 index ebd0b4cee7d0..000000000000 --- a/Marlin/src/HAL/STM32_F4_F7/HAL_SPI.cpp +++ /dev/null @@ -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 . - * - */ -#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 -#include -#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(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(buf), 512); - #else - SPI.transfer((uint8_t*)buf, nullptr, 512); - #endif - SPI.endTransaction(); -} - -#endif // SOFTWARE_SPI -#endif // STM32GENERIC && (STM32F4 || STM32F7) diff --git a/Marlin/src/HAL/STM32_F4_F7/README.md b/Marlin/src/HAL/STM32_F4_F7/README.md deleted file mode 100644 index 3b5a9ab02e21..000000000000 --- a/Marlin/src/HAL/STM32_F4_F7/README.md +++ /dev/null @@ -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. diff --git a/Marlin/src/HAL/STM32_F4_F7/STM32F4/README.md b/Marlin/src/HAL/STM32_F4_F7/STM32F4/README.md deleted file mode 100644 index 10396e875b88..000000000000 --- a/Marlin/src/HAL/STM32_F4_F7/STM32F4/README.md +++ /dev/null @@ -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. - diff --git a/Marlin/src/HAL/STM32_F4_F7/STM32F4/timers.cpp b/Marlin/src/HAL/STM32_F4_F7/STM32F4/timers.cpp deleted file mode 100644 index 8b753f72902e..000000000000 --- a/Marlin/src/HAL/STM32_F4_F7/STM32F4/timers.cpp +++ /dev/null @@ -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 . - * - */ -#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 diff --git a/Marlin/src/HAL/STM32_F4_F7/STM32F4/timers.h b/Marlin/src/HAL/STM32_F4_F7/STM32F4/timers.h deleted file mode 100644 index a4a7ad82cca9..000000000000 --- a/Marlin/src/HAL/STM32_F4_F7/STM32F4/timers.h +++ /dev/null @@ -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 . - * - */ -#pragma once - -#include - -// ------------------------ -// 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) diff --git a/Marlin/src/HAL/STM32_F4_F7/STM32F7/README.md b/Marlin/src/HAL/STM32_F4_F7/STM32F7/README.md deleted file mode 100644 index 23155b425e31..000000000000 --- a/Marlin/src/HAL/STM32_F4_F7/STM32F7/README.md +++ /dev/null @@ -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. diff --git a/Marlin/src/HAL/STM32_F4_F7/STM32F7/TMC2660.cpp b/Marlin/src/HAL/STM32_F4_F7/STM32F7/TMC2660.cpp deleted file mode 100644 index e67808c3c458..000000000000 --- a/Marlin/src/HAL/STM32_F4_F7/STM32F7/TMC2660.cpp +++ /dev/null @@ -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 -#include -#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 diff --git a/Marlin/src/HAL/STM32_F4_F7/STM32F7/TMC2660.h b/Marlin/src/HAL/STM32_F4_F7/STM32F7/TMC2660.h deleted file mode 100644 index 208c3bc7e062..000000000000 --- a/Marlin/src/HAL/STM32_F4_F7/STM32F7/TMC2660.h +++ /dev/null @@ -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 - -//! 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, 1…15: 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,1…12: 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 0…255 - * - * 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); -}; diff --git a/Marlin/src/HAL/STM32_F4_F7/STM32F7/timers.cpp b/Marlin/src/HAL/STM32_F4_F7/STM32F7/timers.cpp deleted file mode 100644 index bc8f76af0987..000000000000 --- a/Marlin/src/HAL/STM32_F4_F7/STM32F7/timers.cpp +++ /dev/null @@ -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 . - * - */ -#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 diff --git a/Marlin/src/HAL/STM32_F4_F7/STM32F7/timers.h b/Marlin/src/HAL/STM32_F4_F7/STM32F7/timers.h deleted file mode 100644 index d2f78259d68d..000000000000 --- a/Marlin/src/HAL/STM32_F4_F7/STM32F7/timers.h +++ /dev/null @@ -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 . - * - */ -#pragma once - -#include - -// ------------------------ -// 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) diff --git a/Marlin/src/HAL/STM32_F4_F7/Servo.cpp b/Marlin/src/HAL/STM32_F4_F7/Servo.cpp deleted file mode 100644 index 7185468f50a8..000000000000 --- a/Marlin/src/HAL/STM32_F4_F7/Servo.cpp +++ /dev/null @@ -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 . - * - */ -#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) diff --git a/Marlin/src/HAL/STM32_F4_F7/Servo.h b/Marlin/src/HAL/STM32_F4_F7/Servo.h deleted file mode 100644 index e42cc6084091..000000000000 --- a/Marlin/src/HAL/STM32_F4_F7/Servo.h +++ /dev/null @@ -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 . - * - */ -#pragma once - -//#ifdef STM32F7 -// #include <../../libraries/Servo/src/Servo.h> -//#else - #include -//#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 -}; diff --git a/Marlin/src/HAL/STM32_F4_F7/eeprom_emul.cpp b/Marlin/src/HAL/STM32_F4_F7/eeprom_emul.cpp deleted file mode 100644 index e0726c7cd592..000000000000 --- a/Marlin/src/HAL/STM32_F4_F7/eeprom_emul.cpp +++ /dev/null @@ -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****/ diff --git a/Marlin/src/HAL/STM32_F4_F7/eeprom_emul.h b/Marlin/src/HAL/STM32_F4_F7/eeprom_emul.h deleted file mode 100644 index 84c4c6e3d253..000000000000 --- a/Marlin/src/HAL/STM32_F4_F7/eeprom_emul.h +++ /dev/null @@ -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. - * - * 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****/ diff --git a/Marlin/src/HAL/STM32_F4_F7/eeprom_flash.cpp b/Marlin/src/HAL/STM32_F4_F7/eeprom_flash.cpp deleted file mode 100644 index 8c5795b6853b..000000000000 --- a/Marlin/src/HAL/STM32_F4_F7/eeprom_flash.cpp +++ /dev/null @@ -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 . - * - */ -#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) diff --git a/Marlin/src/HAL/STM32_F4_F7/eeprom_wired.cpp b/Marlin/src/HAL/STM32_F4_F7/eeprom_wired.cpp deleted file mode 100644 index 2bf386bec505..000000000000 --- a/Marlin/src/HAL/STM32_F4_F7/eeprom_wired.cpp +++ /dev/null @@ -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 . - * - */ -#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) diff --git a/Marlin/src/HAL/STM32_F4_F7/endstop_interrupts.h b/Marlin/src/HAL/STM32_F4_F7/endstop_interrupts.h deleted file mode 100644 index fdff8cc644cd..000000000000 --- a/Marlin/src/HAL/STM32_F4_F7/endstop_interrupts.h +++ /dev/null @@ -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 . - * - */ -#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)); -} diff --git a/Marlin/src/HAL/STM32_F4_F7/fastio.h b/Marlin/src/HAL/STM32_F4_F7/fastio.h deleted file mode 100644 index f42be5835433..000000000000 --- a/Marlin/src/HAL/STM32_F4_F7/fastio.h +++ /dev/null @@ -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 . - * - */ -#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 diff --git a/Marlin/src/HAL/STM32_F4_F7/inc/Conditionals_LCD.h b/Marlin/src/HAL/STM32_F4_F7/inc/Conditionals_LCD.h deleted file mode 100644 index a9f1b5822215..000000000000 --- a/Marlin/src/HAL/STM32_F4_F7/inc/Conditionals_LCD.h +++ /dev/null @@ -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 . - * - */ -#pragma once - -#if HAS_SPI_TFT || HAS_FSMC_TFT - #error "Sorry! TFT displays are not available for HAL/STM32F4_F7." -#endif diff --git a/Marlin/src/HAL/STM32_F4_F7/inc/Conditionals_adv.h b/Marlin/src/HAL/STM32_F4_F7/inc/Conditionals_adv.h deleted file mode 100644 index 5f1c4b16019d..000000000000 --- a/Marlin/src/HAL/STM32_F4_F7/inc/Conditionals_adv.h +++ /dev/null @@ -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 . - * - */ -#pragma once diff --git a/Marlin/src/HAL/STM32_F4_F7/inc/Conditionals_post.h b/Marlin/src/HAL/STM32_F4_F7/inc/Conditionals_post.h deleted file mode 100644 index b5d808e21acc..000000000000 --- a/Marlin/src/HAL/STM32_F4_F7/inc/Conditionals_post.h +++ /dev/null @@ -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 . - * - */ -#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 diff --git a/Marlin/src/HAL/STM32_F4_F7/inc/SanityCheck.h b/Marlin/src/HAL/STM32_F4_F7/inc/SanityCheck.h deleted file mode 100644 index 9bb36f3bbbca..000000000000 --- a/Marlin/src/HAL/STM32_F4_F7/inc/SanityCheck.h +++ /dev/null @@ -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 . - * - */ -#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 diff --git a/Marlin/src/HAL/STM32_F4_F7/pinsDebug.h b/Marlin/src/HAL/STM32_F4_F7/pinsDebug.h deleted file mode 100644 index 973abb1b0185..000000000000 --- a/Marlin/src/HAL/STM32_F4_F7/pinsDebug.h +++ /dev/null @@ -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 . - * - */ -#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 diff --git a/Marlin/src/HAL/STM32_F4_F7/spi_pins.h b/Marlin/src/HAL/STM32_F4_F7/spi_pins.h deleted file mode 100644 index 75a6a2b250f6..000000000000 --- a/Marlin/src/HAL/STM32_F4_F7/spi_pins.h +++ /dev/null @@ -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 . - * - */ -#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 diff --git a/Marlin/src/HAL/STM32_F4_F7/timers.h b/Marlin/src/HAL/STM32_F4_F7/timers.h deleted file mode 100644 index 4e8c81783e59..000000000000 --- a/Marlin/src/HAL/STM32_F4_F7/timers.h +++ /dev/null @@ -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 . - * - */ -#pragma once - -#ifdef STM32F4 - #include "STM32F4/timers.h" -#else - #include "STM32F7/timers.h" -#endif diff --git a/Marlin/src/HAL/STM32_F4_F7/watchdog.cpp b/Marlin/src/HAL/STM32_F4_F7/watchdog.cpp deleted file mode 100644 index c0afd0cd58fb..000000000000 --- a/Marlin/src/HAL/STM32_F4_F7/watchdog.cpp +++ /dev/null @@ -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 . - * - */ -#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) diff --git a/Marlin/src/HAL/STM32_F4_F7/watchdog.h b/Marlin/src/HAL/STM32_F4_F7/watchdog.h deleted file mode 100644 index 3dbc2d08c139..000000000000 --- a/Marlin/src/HAL/STM32_F4_F7/watchdog.h +++ /dev/null @@ -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 . - * - */ -#pragma once - -extern IWDG_HandleTypeDef hiwdg; - -void watchdog_init(); -void HAL_watchdog_refresh(); diff --git a/Marlin/src/HAL/platforms.h b/Marlin/src/HAL/platforms.h index ef17d19170cc..e0617bdf7fa5 100644 --- a/Marlin/src/HAL/platforms.h +++ b/Marlin/src/HAL/platforms.h @@ -37,8 +37,6 @@ #define HAL_PATH(PATH, NAME) XSTR(PATH/LPC1768/NAME) #elif defined(__STM32F1__) || defined(TARGET_STM32F1) #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) #define HAL_PATH(PATH, NAME) XSTR(PATH/STM32/NAME) #elif defined(ARDUINO_ARCH_ESP32) diff --git a/Marlin/src/HAL/shared/backtrace/unwmemaccess.cpp b/Marlin/src/HAL/shared/backtrace/unwmemaccess.cpp index e74953064592..5ca46f98865b 100644 --- a/Marlin/src/HAL/shared/backtrace/unwmemaccess.cpp +++ b/Marlin/src/HAL/shared/backtrace/unwmemaccess.cpp @@ -74,17 +74,6 @@ #define START_FLASH_ADDR 0x08000000 #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) // For STM32F765VI in RemRam v1 diff --git a/Marlin/src/HAL/shared/servo.h b/Marlin/src/HAL/shared/servo.h index 6d850da851d2..c2560a853832 100644 --- a/Marlin/src/HAL/shared/servo.h +++ b/Marlin/src/HAL/shared/servo.h @@ -76,8 +76,6 @@ #include "../LPC1768/Servo.h" #elif defined(__STM32F1__) || defined(TARGET_STM32F1) #include "../STM32F1/Servo.h" -#elif defined(STM32GENERIC) && defined(STM32F4) - #include "../STM32_F4_F7/Servo.h" #elif defined(ARDUINO_ARCH_STM32) #include "../STM32/Servo.h" #elif defined(ARDUINO_ARCH_ESP32) diff --git a/Marlin/src/core/boards.h b/Marlin/src/core/boards.h index e68ba196ee81..1d1f3972d9d7 100644 --- a/Marlin/src/core/boards.h +++ b/Marlin/src/core/boards.h @@ -329,6 +329,7 @@ #define BOARD_TRIGORILLA_PRO 4037 // Trigorilla Pro (STM32F103ZET6) #define BOARD_FLY_MINI 4038 // FLY MINI (STM32F103RCT6) #define BOARD_FLSUN_HISPEED 4039 // FLSUN HiSpeedV1 (STM32F103VET6) +#define BOARD_BEAST 4040 // STM32F103RET6 Libmaple-based controller // // ARM Cortex-M4F @@ -341,37 +342,34 @@ // STM32 ARM Cortex-M4F // -#define BOARD_BEAST 4200 // STM32F4xxVxT6 Libmaple-based STM32F4 controller -#define BOARD_GENERIC_STM32F4 4201 // STM32 STM32GENERIC-based STM32F4 controller -#define BOARD_ARMED 4202 // Arm'ed STM32F4-based controller -#define BOARD_RUMBA32_V1_0 4203 // RUMBA32 STM32F446VET6 based controller from Aus3D -#define BOARD_RUMBA32_V1_1 4204 // RUMBA32 STM32F446VET6 based controller from Aus3D -#define BOARD_RUMBA32_MKS 4205 // RUMBA32 STM32F446VET6 based controller from Makerbase -#define BOARD_BLACK_STM32F407VE 4206 // BLACK_STM32F407VE -#define BOARD_BLACK_STM32F407ZE 4207 // BLACK_STM32F407ZE -#define BOARD_STEVAL_3DP001V1 4208 // STEVAL-3DP001V1 3D PRINTER BOARD -#define BOARD_BTT_SKR_PRO_V1_1 4209 // BigTreeTech SKR Pro v1.1 (STM32F407ZG) -#define BOARD_BTT_SKR_PRO_V1_2 4210 // BigTreeTech SKR Pro v1.2 (STM32F407ZG) -#define BOARD_BTT_BTT002_V1_0 4211 // BigTreeTech BTT002 v1.0 (STM32F407VG) -#define BOARD_BTT_GTR_V1_0 4212 // BigTreeTech GTR v1.0 (STM32F407IGT) -#define BOARD_LERDGE_K 4213 // Lerdge K (STM32F407ZG) -#define BOARD_LERDGE_S 4214 // Lerdge S (STM32F407VE) -#define BOARD_LERDGE_X 4215 // Lerdge X (STM32F407VE) -#define BOARD_VAKE403D 4216 // VAkE 403D (STM32F446VET6) -#define BOARD_FYSETC_S6 4217 // FYSETC S6 board -#define BOARD_FYSETC_S6_V2_0 4218 // FYSETC S6 v2.0 board -#define BOARD_FLYF407ZG 4219 // FLYF407ZG board (STM32F407ZG) -#define BOARD_MKS_ROBIN2 4220 // MKS_ROBIN2 (STM32F407ZE) +#define BOARD_ARMED 4200 // Arm'ed STM32F4-based controller +#define BOARD_RUMBA32_V1_0 4201 // RUMBA32 STM32F446VET6 based controller from Aus3D +#define BOARD_RUMBA32_V1_1 4202 // RUMBA32 STM32F446VET6 based controller from Aus3D +#define BOARD_RUMBA32_MKS 4203 // RUMBA32 STM32F446VET6 based controller from Makerbase +#define BOARD_BLACK_STM32F407VE 4204 // BLACK_STM32F407VE +#define BOARD_BLACK_STM32F407ZE 4205 // BLACK_STM32F407ZE +#define BOARD_STEVAL_3DP001V1 4206 // STEVAL-3DP001V1 3D PRINTER BOARD +#define BOARD_BTT_SKR_PRO_V1_1 4207 // BigTreeTech SKR Pro v1.1 (STM32F407ZG) +#define BOARD_BTT_SKR_PRO_V1_2 4208 // BigTreeTech SKR Pro v1.2 (STM32F407ZG) +#define BOARD_BTT_BTT002_V1_0 4209 // BigTreeTech BTT002 v1.0 (STM32F407VG) +#define BOARD_BTT_GTR_V1_0 4210 // BigTreeTech GTR v1.0 (STM32F407IGT) +#define BOARD_LERDGE_K 4211 // Lerdge K (STM32F407ZG) +#define BOARD_LERDGE_S 4212 // Lerdge S (STM32F407VE) +#define BOARD_LERDGE_X 4213 // Lerdge X (STM32F407VE) +#define BOARD_VAKE403D 4214 // VAkE 403D (STM32F446VET6) +#define BOARD_FYSETC_S6 4215 // FYSETC S6 board +#define BOARD_FYSETC_S6_V2_0 4216 // FYSETC S6 v2.0 board +#define BOARD_FLYF407ZG 4217 // FLYF407ZG board (STM32F407ZG) +#define BOARD_MKS_ROBIN2 4218 // MKS_ROBIN2 (STM32F407ZE) // // ARM Cortex M7 // -#define BOARD_THE_BORG 5000 // THE-BORG (Power outputs: Hotend0, Hotend1, Bed, Fan) -#define BOARD_REMRAM_V1 5001 // RemRam v1 -#define BOARD_TEENSY41 5002 // Teensy 4.1 -#define BOARD_T41U5XBB 5003 // T41U5XBB Teensy 4.1 breakout board -#define BOARD_NUCLEO_F767ZI 5004 // ST NUCLEO-F767ZI Dev Board +#define BOARD_REMRAM_V1 5000 // RemRam v1 +#define BOARD_TEENSY41 5001 // Teensy 4.1 +#define BOARD_T41U5XBB 5002 // T41U5XBB Teensy 4.1 breakout board +#define BOARD_NUCLEO_F767ZI 5003 // ST NUCLEO-F767ZI Dev Board // // Espressif ESP32 WiFi diff --git a/Marlin/src/core/macros.h b/Marlin/src/core/macros.h index 7985706173fe..2e38fad30ef6 100644 --- a/Marlin/src/core/macros.h +++ b/Marlin/src/core/macros.h @@ -61,11 +61,7 @@ #define _O3 __attribute__((optimize("O3"))) #ifndef UNUSED - #if defined(ARDUINO_ARCH_STM32) && !defined(STM32GENERIC) - #define UNUSED(X) (void)X - #else - #define UNUSED(x) ((void)(x)) - #endif + #define UNUSED(x) ((void)(x)) #endif // Clock speed factors diff --git a/Marlin/src/module/stepper/TMC26X.h b/Marlin/src/module/stepper/TMC26X.h index 8977266b47bf..547eb6521f19 100644 --- a/Marlin/src/module/stepper/TMC26X.h +++ b/Marlin/src/module/stepper/TMC26X.h @@ -31,11 +31,7 @@ // TMC26X drivers have STEP/DIR on normal pins, but ENABLE via SPI #include -#if defined(STM32GENERIC) && defined(STM32F7) - #include "../../HAL/STM32_F4_F7/STM32F7/TMC2660.h" -#else - #include -#endif +#include void tmc26x_init_to_defaults(); diff --git a/Marlin/src/pins/pins.h b/Marlin/src/pins/pins.h index af3b72475660..1660d16dd2da 100644 --- a/Marlin/src/pins/pins.h +++ b/Marlin/src/pins/pins.h @@ -594,6 +594,8 @@ #include "stm32f1/pins_FLY_MINI.h" // STM32F1 env:FLY_MINI #elif MB(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 @@ -608,10 +610,6 @@ // 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) #include "stm32f4/pins_ARMED.h" // STM32F4 env:ARMED #elif MB(RUMBA32_V1_0) @@ -633,13 +631,13 @@ #elif MB(BTT_BTT002_V1_0) #include "stm32f4/pins_BTT_BTT002_V1_0.h" // STM32F4 env:BIGTREE_BTT002 #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) - #include "stm32f4/pins_LERDGE_S.h" // STM32F4 env:LERDGE_S + #include "stm32f4/pins_LERDGE_S.h" // STM32F4 env:LERDGES #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) - #include "stm32f4/pins_VAKE403D.h" // STM32F4 env:STM32F4 + #include "stm32f4/pins_VAKE403D.h" // STM32F4 #elif MB(FYSETC_S6) #include "stm32f4/pins_FYSETC_S6.h" // STM32F4 env:FYSETC_S6 #elif MB(FLYF407ZG) @@ -653,10 +651,8 @@ // ARM Cortex M7 // -#elif MB(THE_BORG) - #include "stm32f7/pins_THE_BORG.h" // STM32F7 env:STM32F7 #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) #include "stm32f7/pins_NUCLEO_F767ZI.h" // STM32F7 env:NUCLEO_F767ZI #elif MB(TEENSY41) diff --git a/Marlin/src/pins/stm32f4/pins_BEAST.h b/Marlin/src/pins/stm32f1/pins_BEAST.h similarity index 98% rename from Marlin/src/pins/stm32f4/pins_BEAST.h rename to Marlin/src/pins/stm32f1/pins_BEAST.h index 279d0b9ec70d..ccb8a31ab727 100644 --- a/Marlin/src/pins/stm32f4/pins_BEAST.h +++ b/Marlin/src/pins/stm32f1/pins_BEAST.h @@ -21,8 +21,8 @@ */ #pragma once -#if NOT_TARGET(__STM32F1__, __STM32F4__) - #error "Oops! Select an STM32F1/4 board in 'Tools > Board.'" +#if NOT_TARGET(__STM32F1__) + #error "Oops! Select an STM32F1 board in 'Tools > Board.'" #endif /** diff --git a/Marlin/src/pins/stm32f4/pins_GENERIC_STM32F4.h b/Marlin/src/pins/stm32f4/pins_GENERIC_STM32F4.h deleted file mode 100644 index 4acfd743b756..000000000000 --- a/Marlin/src/pins/stm32f4/pins_GENERIC_STM32F4.h +++ /dev/null @@ -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 . - * - */ -#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 diff --git a/Marlin/src/pins/stm32f7/pins_THE_BORG.h b/Marlin/src/pins/stm32f7/pins_THE_BORG.h deleted file mode 100644 index c050824a83da..000000000000 --- a/Marlin/src/pins/stm32f7/pins_THE_BORG.h +++ /dev/null @@ -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 . - * - */ -#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 diff --git a/buildroot/tests/BIGTREE_SKR_PRO-tests b/buildroot/tests/BIGTREE_SKR_PRO-tests index 3d0000ccc4f7..ff4a8d734e73 100644 --- a/buildroot/tests/BIGTREE_SKR_PRO-tests +++ b/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 X_DRIVER_TYPE TMC2209 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" # clean up diff --git a/buildroot/tests/STM32F7-tests b/buildroot/tests/REMRAM_V1-tests similarity index 89% rename from buildroot/tests/STM32F7-tests rename to buildroot/tests/REMRAM_V1-tests index b23a16467edc..f5944ff5af84 100644 --- a/buildroot/tests/STM32F7-tests +++ b/buildroot/tests/REMRAM_V1-tests @@ -1,6 +1,6 @@ #!/usr/bin/env bash # -# Build tests for STM32F7 +# Build tests for REMRAM_V1 # # exit on first failure diff --git a/buildroot/tests/STM32F103RC_btt-tests b/buildroot/tests/STM32F103RC_btt-tests index 77044dcb364e..5d695c9296b1 100644 --- a/buildroot/tests/STM32F103RC_btt-tests +++ b/buildroot/tests/STM32F103RC_btt-tests @@ -21,6 +21,7 @@ opt_set X_SLAVE_ADDRESS 0 opt_set Y_SLAVE_ADDRESS 1 opt_set Z_SLAVE_ADDRESS 2 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" diff --git a/buildroot/tests/STM32F4-tests b/buildroot/tests/STM32F4-tests deleted file mode 100644 index 89281860f65f..000000000000 --- a/buildroot/tests/STM32F4-tests +++ /dev/null @@ -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 diff --git a/platformio.ini b/platformio.ini index 9fb49040209a..062514c882e5 100644 --- a/platformio.ini +++ b/platformio.ini @@ -863,22 +863,13 @@ lib_deps = ${common_stm32f1.lib_deps} USBComposite for STM32F1@0.91 # -# STM32F4 with STM32GENERIC +# REMRAM_V1 # -[env:STM32F4] -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} + - - -# -# STM32F7 with STM32GENERIC -# -[env:STM32F7] +[env:REMRAM_V1] platform = ${common_stm32.platform} +extends = common_stm32 board = remram_v1 -build_flags = ${common.build_flags} -DUSE_STM32GENERIC -DSTM32GENERIC -DSTM32F7 -DMENU_USB_SERIAL -DMENU_SERIAL=SerialUSB -DHAL_IWDG_MODULE_ENABLED -src_filter = ${common.default_src_filter} + - +build_flags = ${common_stm32.build_flags} # # ST NUCLEO-F767ZI Development Board From 4f4843a84578dfb27176fbea855faa407453e706 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Thu, 26 Nov 2020 01:08:12 -0600 Subject: [PATCH 21/47] Tweak some pin errors --- Marlin/src/pins/esp32/pins_E4D.h | 2 +- Marlin/src/pins/esp32/pins_FYSETC_E4.h | 2 +- Marlin/src/pins/esp32/pins_MRR_ESPA.h | 2 +- Marlin/src/pins/esp32/pins_MRR_ESPE.h | 2 +- Marlin/src/pins/stm32f1/pins_CREALITY_V4.h | 2 +- Marlin/src/pins/stm32f1/pins_MKS_ROBIN_E3.h | 2 +- Marlin/src/pins/stm32f1/pins_MKS_ROBIN_E3D.h | 2 +- Marlin/src/pins/stm32f1/pins_MKS_ROBIN_E3P.h | 6 +++--- Marlin/src/pins/stm32f4/pins_BTT_BTT002_V1_0.h | 2 +- Marlin/src/pins/stm32f4/pins_LERDGE_X.h | 2 +- Marlin/src/pins/stm32f7/pins_REMRAM_V1.h | 2 +- 11 files changed, 13 insertions(+), 13 deletions(-) diff --git a/Marlin/src/pins/esp32/pins_E4D.h b/Marlin/src/pins/esp32/pins_E4D.h index 2a1f070ddaaf..6009ea6cdb72 100644 --- a/Marlin/src/pins/esp32/pins_E4D.h +++ b/Marlin/src/pins/esp32/pins_E4D.h @@ -32,7 +32,7 @@ #elif EXTRUDERS > 1 || E_STEPPERS > 1 #error "E4d@box only supports one E Stepper. Comment out this line to continue." #elif HOTENDS > 1 - #error "E4d@box currently supports only one hotend. Comment out this line to continue." + #error "E4d@box only supports one hotend / E-stepper. Comment out this line to continue." #endif #define BOARD_INFO_NAME "E4D@BOX" diff --git a/Marlin/src/pins/esp32/pins_FYSETC_E4.h b/Marlin/src/pins/esp32/pins_FYSETC_E4.h index af179256e136..5b6251868954 100644 --- a/Marlin/src/pins/esp32/pins_FYSETC_E4.h +++ b/Marlin/src/pins/esp32/pins_FYSETC_E4.h @@ -32,7 +32,7 @@ #elif EXTRUDERS > 1 || E_STEPPERS > 1 #error "FYSETC E4 only supports one E Stepper. Comment out this line to continue." #elif HOTENDS > 1 - #error "FYSETC E4 currently supports only one hotend. Comment out this line to continue." + #error "FYSETC E4 only supports one hotend / E-stepper. Comment out this line to continue." #endif #define BOARD_INFO_NAME "FYSETC_E4" diff --git a/Marlin/src/pins/esp32/pins_MRR_ESPA.h b/Marlin/src/pins/esp32/pins_MRR_ESPA.h index 52837df741c2..02cdd0a0094e 100644 --- a/Marlin/src/pins/esp32/pins_MRR_ESPA.h +++ b/Marlin/src/pins/esp32/pins_MRR_ESPA.h @@ -32,7 +32,7 @@ #elif EXTRUDERS > 1 || E_STEPPERS > 1 #error "MRR ESPA only supports one E Stepper. Comment out this line to continue." #elif HOTENDS > 1 - #error "MRR ESPA currently supports only one hotend. Comment out this line to continue." + #error "MRR ESPA only supports one hotend / E-stepper. Comment out this line to continue." #endif #define BOARD_INFO_NAME "MRR ESPA" diff --git a/Marlin/src/pins/esp32/pins_MRR_ESPE.h b/Marlin/src/pins/esp32/pins_MRR_ESPE.h index 0c489dd7b473..0c9ab43fd3ac 100644 --- a/Marlin/src/pins/esp32/pins_MRR_ESPE.h +++ b/Marlin/src/pins/esp32/pins_MRR_ESPE.h @@ -33,7 +33,7 @@ #elif EXTRUDERS > 2 || E_STEPPERS > 2 #error "MRR ESPE only supports two E Steppers. Comment out this line to continue." #elif HOTENDS > 1 - #error "MRR ESPE currently supports only one hotend. Comment out this line to continue." + #error "MRR ESPE only supports one hotend / E-stepper. Comment out this line to continue." #endif #define BOARD_INFO_NAME "MRR ESPE" diff --git a/Marlin/src/pins/stm32f1/pins_CREALITY_V4.h b/Marlin/src/pins/stm32f1/pins_CREALITY_V4.h index c6f2dd8b8081..f0c1611cb861 100644 --- a/Marlin/src/pins/stm32f1/pins_CREALITY_V4.h +++ b/Marlin/src/pins/stm32f1/pins_CREALITY_V4.h @@ -27,7 +27,7 @@ #if NOT_TARGET(__STM32F1__) #error "Oops! Select an STM32F1 board in 'Tools > Board.'" #elif HOTENDS > 1 || E_STEPPERS > 1 - #error "CREALITY supports up to 1 hotends / E-steppers. Comment out this line to continue." + #error "Creality V4 only supports one hotend / E-stepper. Comment out this line to continue." #endif #ifndef BOARD_INFO_NAME diff --git a/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_E3.h b/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_E3.h index 2028cd9dd4d0..89ace3493fc2 100644 --- a/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_E3.h +++ b/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_E3.h @@ -26,7 +26,7 @@ */ #if HOTENDS > 1 || E_STEPPERS > 1 - #error "MKS Robin E3 supports up to 1 hotends / E-steppers. Comment out this line to continue." + #error "MKS Robin E3 only supports one hotend / E-stepper. Comment out this line to continue." #endif #ifndef BOARD_INFO_NAME diff --git a/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_E3D.h b/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_E3D.h index d1f6dece5c15..a629bce9f38d 100644 --- a/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_E3D.h +++ b/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_E3D.h @@ -26,7 +26,7 @@ */ #if HOTENDS > 1 || E_STEPPERS > 1 - #error "MKS Robin E3D supports up to 1 hotends / E-steppers. Comment out this line to continue." + #error "MKS Robin E3D only supports one hotend / E-stepper. Comment out this line to continue." #endif #ifndef BOARD_INFO_NAME diff --git a/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_E3P.h b/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_E3P.h index b9283a060f86..93890e9aa777 100644 --- a/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_E3P.h +++ b/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_E3P.h @@ -28,12 +28,12 @@ #if NOT_TARGET(__STM32F1__) #error "Oops! Select an STM32F1 board in 'Tools > Board.'" #elif HOTENDS > 1 || E_STEPPERS > 1 - #error "MKS Robin e3p supports up to 1 hotends / E-steppers. Comment out this line to continue." + #error "MKS Robin E3P only supports one hotend / E-stepper. Comment out this line to continue." #elif HAS_FSMC_TFT - #error "MKS Robin e3p doesn't support FSMC-based TFT displays." + #error "MKS Robin E3P doesn't support FSMC-based TFT displays." #endif -#define BOARD_INFO_NAME "MKS Robin e3p" +#define BOARD_INFO_NAME "MKS Robin E3P" #define BOARD_NO_NATIVE_USB diff --git a/Marlin/src/pins/stm32f4/pins_BTT_BTT002_V1_0.h b/Marlin/src/pins/stm32f4/pins_BTT_BTT002_V1_0.h index 19ff2a34e222..660ba29e97d1 100644 --- a/Marlin/src/pins/stm32f4/pins_BTT_BTT002_V1_0.h +++ b/Marlin/src/pins/stm32f4/pins_BTT_BTT002_V1_0.h @@ -24,7 +24,7 @@ #if NOT_TARGET(STM32F4) #error "Oops! Select an STM32F4 board in 'Tools > Board.'" #elif HOTENDS > 1 || E_STEPPERS > 1 - #error "BIGTREE BTT002 V1.0 supports up to 1 hotends / E-steppers." + #error "BIGTREE BTT002 V1.0 only supports one hotend / E-stepper." #endif #define BOARD_INFO_NAME "BTT BTT002 V1.0" diff --git a/Marlin/src/pins/stm32f4/pins_LERDGE_X.h b/Marlin/src/pins/stm32f4/pins_LERDGE_X.h index bed51ca660cf..075aec6e9bf8 100644 --- a/Marlin/src/pins/stm32f4/pins_LERDGE_X.h +++ b/Marlin/src/pins/stm32f4/pins_LERDGE_X.h @@ -21,7 +21,7 @@ #if NOT_TARGET(STM32F4, STM32F4xx) #error "Oops! Select an STM32F4 board in 'Tools > Board.'" #elif HOTENDS > 1 || E_STEPPERS > 1 - #error "LERDGE X supports only one hotend / E-steppers" + #error "LERDGE X only supports one hotend / E-steppers" #endif #define BOARD_INFO_NAME "Lerdge X" diff --git a/Marlin/src/pins/stm32f7/pins_REMRAM_V1.h b/Marlin/src/pins/stm32f7/pins_REMRAM_V1.h index c3dc004728d8..f07cf824d22c 100644 --- a/Marlin/src/pins/stm32f7/pins_REMRAM_V1.h +++ b/Marlin/src/pins/stm32f7/pins_REMRAM_V1.h @@ -33,7 +33,7 @@ #endif #if HOTENDS > 1 || E_STEPPERS > 1 - #error "RemRam supports only one hotend / E-stepper." + #error "RemRam only supports one hotend / E-stepper." #endif // From 8c59212ca46a3a9f721b2216bb538c0b42a3992f Mon Sep 17 00:00:00 2001 From: mks-viva <1224833100@qq.com> Date: Thu, 26 Nov 2020 16:36:29 +0800 Subject: [PATCH 22/47] MKS Robin E3 / E3D v1.1 (#20216) --- Marlin/src/core/boards.h | 54 ++++++++------- Marlin/src/pins/pins.h | 4 ++ .../pins/stm32f1/pins_MKS_ROBIN_E3D_V1_1.h | 67 +++++++++++++++++++ .../src/pins/stm32f1/pins_MKS_ROBIN_E3_V1_1.h | 36 ++++++++++ .../stm32f1/pins_MKS_ROBIN_E3_V1_1_common.h | 39 +++++++++++ .../pins/stm32f1/pins_MKS_ROBIN_E3_common.h | 10 ++- 6 files changed, 181 insertions(+), 29 deletions(-) create mode 100644 Marlin/src/pins/stm32f1/pins_MKS_ROBIN_E3D_V1_1.h create mode 100644 Marlin/src/pins/stm32f1/pins_MKS_ROBIN_E3_V1_1.h create mode 100644 Marlin/src/pins/stm32f1/pins_MKS_ROBIN_E3_V1_1_common.h diff --git a/Marlin/src/core/boards.h b/Marlin/src/core/boards.h index 1d1f3972d9d7..a6fc1b4dfdd0 100644 --- a/Marlin/src/core/boards.h +++ b/Marlin/src/core/boards.h @@ -289,11 +289,11 @@ // STM32 ARM Cortex-M3 // -#define BOARD_MALYAN_M200_V2 4000 // STM32F070CB STM32F0 controller +#define BOARD_MALYAN_M200_V2 4000 // STM32F070CB controller #define BOARD_MALYAN_M300 4001 // STM32F070-based delta #define BOARD_STM32F103RE 4002 // STM32F103RE Libmaple-based STM32F1 controller -#define BOARD_MALYAN_M200 4003 // STM32C8T6 Libmaple-based STM32F1 controller -#define BOARD_STM3R_MINI 4004 // STM32F103RE Libmaple-based STM32F1 controller +#define BOARD_MALYAN_M200 4003 // STM32C8T6 Libmaple-based STM32F1 controller +#define BOARD_STM3R_MINI 4004 // STM32F103RE Libmaple-based STM32F1 controller #define BOARD_GTM32_PRO_VB 4005 // STM32F103VET6 controller #define BOARD_GTM32_MINI 4006 // STM32F103VET6 controller #define BOARD_GTM32_MINI_A30 4007 // STM32F103VET6 controller @@ -307,29 +307,31 @@ #define BOARD_MKS_ROBIN_LITE 4015 // MKS Robin Lite/Lite2 (STM32F103RCT6) #define BOARD_MKS_ROBIN_LITE3 4016 // MKS Robin Lite3 (STM32F103RCT6) #define BOARD_MKS_ROBIN_PRO 4017 // MKS Robin Pro (STM32F103ZET6) -#define BOARD_MKS_ROBIN_E3 4018 // MKS Robin E3 (STM32F103RCT6) -#define BOARD_MKS_ROBIN_E3D 4019 // MKS Robin E3D (STM32F103RCT6) -#define BOARD_MKS_ROBIN_E3P 4020 // MKS Robin E3p (STM32F103VET6) -#define BOARD_BTT_SKR_MINI_V1_1 4021 // BigTreeTech SKR Mini v1.1 (STM32F103RC) -#define BOARD_BTT_SKR_MINI_E3_V1_0 4022 // BigTreeTech SKR Mini E3 (STM32F103RC) -#define BOARD_BTT_SKR_MINI_E3_V1_2 4023 // BigTreeTech SKR Mini E3 V1.2 (STM32F103RC) -#define BOARD_BTT_SKR_MINI_E3_V2_0 4024 // BigTreeTech SKR Mini E3 V2.0 (STM32F103RC) -#define BOARD_BTT_SKR_MINI_MZ_V1_0 4025 // BigTreeTech SKR Mini MZ V1.0 (STM32F103RC) -#define BOARD_BTT_SKR_E3_DIP 4026 // BigTreeTech SKR E3 DIP V1.0 (STM32F103RC / STM32F103RE) -#define BOARD_JGAURORA_A5S_A1 4027 // JGAurora A5S A1 (STM32F103ZET6) -#define BOARD_FYSETC_AIO_II 4028 // FYSETC AIO_II -#define BOARD_FYSETC_CHEETAH 4029 // FYSETC Cheetah -#define BOARD_FYSETC_CHEETAH_V12 4030 // FYSETC Cheetah V1.2 -#define BOARD_LONGER3D_LK 4031 // Alfawise U20/U20+/U30 (Longer3D LK1/2) / STM32F103VET6 -#define BOARD_CCROBOT_MEEB_3DP 4032 // ccrobot-online.com MEEB_3DP (STM32F103RC) -#define BOARD_CHITU3D_V5 4033 // Chitu3D TronXY X5SA V5 Board -#define BOARD_CHITU3D_V6 4034 // Chitu3D TronXY X5SA V5 Board -#define BOARD_CREALITY_V4 4035 // Creality v4.x (STM32F103RE) -#define BOARD_CREALITY_V427 4036 // Creality v4.2.7 (STM32F103RE) -#define BOARD_TRIGORILLA_PRO 4037 // Trigorilla Pro (STM32F103ZET6) -#define BOARD_FLY_MINI 4038 // FLY MINI (STM32F103RCT6) -#define BOARD_FLSUN_HISPEED 4039 // FLSUN HiSpeedV1 (STM32F103VET6) -#define BOARD_BEAST 4040 // STM32F103RET6 Libmaple-based controller +#define BOARD_MKS_ROBIN_E3 4018 // MKS Robin E3 (STM32F103RCT6) +#define BOARD_MKS_ROBIN_E3_V1_1 4019 // MKS Robin E3 V1.1 (STM32F103RCT6) +#define BOARD_MKS_ROBIN_E3D 4020 // MKS Robin E3D (STM32F103RCT6) +#define BOARD_MKS_ROBIN_E3D_V1_1 4021 // MKS Robin E3D V1.1 (STM32F103RCT6) +#define BOARD_MKS_ROBIN_E3P 4022 // MKS Robin E3p (STM32F103VET6) +#define BOARD_BTT_SKR_MINI_V1_1 4023 // BigTreeTech SKR Mini v1.1 (STM32F103RC) +#define BOARD_BTT_SKR_MINI_E3_V1_0 4024 // BigTreeTech SKR Mini E3 (STM32F103RC) +#define BOARD_BTT_SKR_MINI_E3_V1_2 4025 // BigTreeTech SKR Mini E3 V1.2 (STM32F103RC) +#define BOARD_BTT_SKR_MINI_E3_V2_0 4026 // BigTreeTech SKR Mini E3 V2.0 (STM32F103RC) +#define BOARD_BTT_SKR_MINI_MZ_V1_0 4027 // BigTreeTech SKR Mini MZ V1.0 (STM32F103RC) +#define BOARD_BTT_SKR_E3_DIP 4028 // BigTreeTech SKR E3 DIP V1.0 (STM32F103RC / STM32F103RE) +#define BOARD_JGAURORA_A5S_A1 4029 // JGAurora A5S A1 (STM32F103ZET6) +#define BOARD_FYSETC_AIO_II 4030 // FYSETC AIO_II +#define BOARD_FYSETC_CHEETAH 4031 // FYSETC Cheetah +#define BOARD_FYSETC_CHEETAH_V12 4032 // FYSETC Cheetah V1.2 +#define BOARD_LONGER3D_LK 4033 // Alfawise U20/U20+/U30 (Longer3D LK1/2) / STM32F103VET6 +#define BOARD_CCROBOT_MEEB_3DP 4034 // ccrobot-online.com MEEB_3DP (STM32F103RC) +#define BOARD_CHITU3D_V5 4035 // Chitu3D TronXY X5SA V5 Board +#define BOARD_CHITU3D_V6 4036 // Chitu3D TronXY X5SA V5 Board +#define BOARD_CREALITY_V4 4037 // Creality v4.x (STM32F103RE) +#define BOARD_CREALITY_V427 4038 // Creality v4.2.7 (STM32F103RE) +#define BOARD_TRIGORILLA_PRO 4039 // Trigorilla Pro (STM32F103ZET6) +#define BOARD_FLY_MINI 4040 // FLY MINI (STM32F103RCT6) +#define BOARD_FLSUN_HISPEED 4041 // FLSUN HiSpeedV1 (STM32F103VET6) +#define BOARD_BEAST 4042 // STM32F103RET6 Libmaple-based controller // // ARM Cortex-M4F diff --git a/Marlin/src/pins/pins.h b/Marlin/src/pins/pins.h index 1660d16dd2da..676e1133102a 100644 --- a/Marlin/src/pins/pins.h +++ b/Marlin/src/pins/pins.h @@ -552,8 +552,12 @@ #include "stm32f1/pins_MKS_ROBIN_PRO.h" // STM32F1 env:mks_robin_pro #elif MB(MKS_ROBIN_E3) #include "stm32f1/pins_MKS_ROBIN_E3.h" // STM32F1 env:mks_robin_e3 +#elif MB(MKS_ROBIN_E3_V1_1) + #include "stm32f1/pins_MKS_ROBIN_E3_V1_1.h" // STM32F1 env:mks_robin_e3 #elif MB(MKS_ROBIN_E3D) #include "stm32f1/pins_MKS_ROBIN_E3D.h" // STM32F1 env:mks_robin_e3 +#elif MB(MKS_ROBIN_E3D_V1_1) + #include "stm32f1/pins_MKS_ROBIN_E3D_V1_1.h" // STM32F1 env:mks_robin_e3 #elif MB(MKS_ROBIN_E3P) #include "stm32f1/pins_MKS_ROBIN_E3P.h" // STM32F1 env:mks_robin_e3p #elif MB(BTT_SKR_MINI_V1_1) diff --git a/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_E3D_V1_1.h b/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_E3D_V1_1.h new file mode 100644 index 000000000000..0d927cf7cb6a --- /dev/null +++ b/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_E3D_V1_1.h @@ -0,0 +1,67 @@ +/** + * 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 . + * + */ +#pragma once + +/** + * MKS Robin E3D v1.1 (STM32F103RCT6) board pin assignments + */ + +#if HOTENDS > 1 || E_STEPPERS > 1 + #error "MKS Robin E3D v1.1 only supports one hotend / E-stepper. Comment out this line to continue." +#endif + +#ifndef BOARD_INFO_NAME + #define BOARD_INFO_NAME "MKS Robin E3D V1.1" +#endif + +// +// Steppers +// +#ifndef X_CS_PIN + #define X_CS_PIN PC7 +#endif +#ifndef Y_CS_PIN + #define Y_CS_PIN PD2 +#endif +#ifndef Z_CS_PIN + #define Z_CS_PIN PC12 +#endif +#ifndef E0_CS_PIN + #define E0_CS_PIN PC11 +#endif + +// +// Software SPI pins for TMC2130 stepper drivers +// +#if ENABLED(TMC_USE_SW_SPI) + #ifndef TMC_SW_MOSI + #define TMC_SW_MOSI PB15 + #endif + #ifndef TMC_SW_MISO + #define TMC_SW_MISO PB14 + #endif + #ifndef TMC_SW_SCK + #define TMC_SW_SCK PB13 + #endif +#endif + +#include "pins_MKS_ROBIN_E3_V1_1_common.h" diff --git a/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_E3_V1_1.h b/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_E3_V1_1.h new file mode 100644 index 000000000000..002c35fe54c1 --- /dev/null +++ b/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_E3_V1_1.h @@ -0,0 +1,36 @@ +/** + * 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 . + * + */ +#pragma once + +/** + * MKS Robin E3 v1.1 (STM32F103RCT6) board pin assignments + */ + +#if HOTENDS > 1 || E_STEPPERS > 1 + #error "MKS Robin E3 v1.1 only supports one hotend / E-stepper. Comment out this line to continue." +#endif + +#ifndef BOARD_INFO_NAME + #define BOARD_INFO_NAME "MKS Robin E3 V1.1" +#endif + +#include "pins_MKS_ROBIN_E3_V1_1_common.h" diff --git a/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_E3_V1_1_common.h b/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_E3_V1_1_common.h new file mode 100644 index 000000000000..4eaf2e946939 --- /dev/null +++ b/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_E3_V1_1_common.h @@ -0,0 +1,39 @@ +/** + * 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 . + * + */ +#pragma once + +// +// EEPROM +// +// Onboard I2C EEPROM +#if NO_EEPROM_SELECTED + #define I2C_EEPROM + #define MARLIN_EEPROM_SIZE 0x1000// 4KB + #undef NO_EEPROM_SELECTED +#endif + +#define Z_STEP_PIN PC14 +#define Z_DIR_PIN PC15 + +#define BTN_ENC_EN -1 + +#include "pins_MKS_ROBIN_E3_common.h" diff --git a/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_E3_common.h b/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_E3_common.h index c2b7e52067c1..1362d2208619 100644 --- a/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_E3_common.h +++ b/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_E3_common.h @@ -70,8 +70,12 @@ #define Y_DIR_PIN PB9 #define Y_ENABLE_PIN PB12 -#define Z_STEP_PIN PB7 -#define Z_DIR_PIN PB6 +#ifndef Z_STEP_PIN + #define Z_STEP_PIN PB7 +#endif +#ifndef Z_DIR_PIN + #define Z_DIR_PIN PB6 +#endif #define Z_ENABLE_PIN PB8 #define E0_STEP_PIN PB4 @@ -161,7 +165,7 @@ #define LCD_PINS_D6 PC4 #define LCD_PINS_D7 PC5 - #if ENABLED(REPRAP_DISCOUNT_FULL_GRAPHIC_SMART_CONTROLLER) + #if !defined(BTN_ENC_EN) && ENABLED(REPRAP_DISCOUNT_FULL_GRAPHIC_SMART_CONTROLLER) #define BTN_ENC_EN LCD_PINS_D7 // Detect the presence of the encoder #endif From aa2ced96e05de394abf34cb5b75046f823aa4954 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Thu, 26 Nov 2020 03:47:07 -0600 Subject: [PATCH 23/47] Finish HAL/STM32 cpp wrappers --- Marlin/src/HAL/STM32/MarlinSPI.cpp | 1 - Marlin/src/HAL/STM32/MarlinSerial.cpp | 1 - Marlin/src/HAL/STM32/Sd2Card_sdio_stm32duino.cpp | 4 +++- Marlin/src/HAL/STM32/eeprom_sdcard.cpp | 5 ++--- Marlin/src/HAL/STM32/fast_pwm.cpp | 2 ++ Marlin/src/HAL/STM32/tft/tft_fsmc.cpp | 2 ++ Marlin/src/HAL/STM32/tft/tft_spi.cpp | 2 ++ Marlin/src/HAL/STM32/tft/xpt2046.cpp | 2 ++ Marlin/src/HAL/STM32/usb_serial.cpp | 3 +-- Marlin/src/HAL/STM32/watchdog.cpp | 1 - 10 files changed, 14 insertions(+), 9 deletions(-) diff --git a/Marlin/src/HAL/STM32/MarlinSPI.cpp b/Marlin/src/HAL/STM32/MarlinSPI.cpp index da11b88a60b1..399430f5eb94 100644 --- a/Marlin/src/HAL/STM32/MarlinSPI.cpp +++ b/Marlin/src/HAL/STM32/MarlinSPI.cpp @@ -19,7 +19,6 @@ * along with this program. If not, see . * */ - #if defined(ARDUINO_ARCH_STM32) && !defined(STM32GENERIC) #include "MarlinSPI.h" diff --git a/Marlin/src/HAL/STM32/MarlinSerial.cpp b/Marlin/src/HAL/STM32/MarlinSerial.cpp index a146664366df..50765ee9958e 100644 --- a/Marlin/src/HAL/STM32/MarlinSerial.cpp +++ b/Marlin/src/HAL/STM32/MarlinSerial.cpp @@ -16,7 +16,6 @@ * along with this program. If not, see . * */ - #if defined(ARDUINO_ARCH_STM32) && !defined(STM32GENERIC) #include "../../inc/MarlinConfig.h" diff --git a/Marlin/src/HAL/STM32/Sd2Card_sdio_stm32duino.cpp b/Marlin/src/HAL/STM32/Sd2Card_sdio_stm32duino.cpp index 9c2666ed26f4..a7b1e8006f2d 100644 --- a/Marlin/src/HAL/STM32/Sd2Card_sdio_stm32duino.cpp +++ b/Marlin/src/HAL/STM32/Sd2Card_sdio_stm32duino.cpp @@ -19,10 +19,11 @@ * along with this program. If not, see . * */ +#if defined(ARDUINO_ARCH_STM32) && !defined(STM32GENERIC) #include "../../inc/MarlinConfig.h" -#if ENABLED(SDIO_SUPPORT) && !defined(STM32GENERIC) +#if ENABLED(SDIO_SUPPORT) #include #include @@ -319,3 +320,4 @@ #endif // !USBD_USE_CDC_COMPOSITE #endif // SDIO_SUPPORT +#endif // ARDUINO_ARCH_STM32 && !STM32GENERIC diff --git a/Marlin/src/HAL/STM32/eeprom_sdcard.cpp b/Marlin/src/HAL/STM32/eeprom_sdcard.cpp index c9180bf09b22..f811468fb484 100644 --- a/Marlin/src/HAL/STM32/eeprom_sdcard.cpp +++ b/Marlin/src/HAL/STM32/eeprom_sdcard.cpp @@ -19,13 +19,12 @@ * along with this program. If not, see . * */ +#if defined(ARDUINO_ARCH_STM32) && !defined(STM32GENERIC) /** * Implementation of EEPROM settings in SD Card */ -#if defined(ARDUINO_ARCH_STM32) && !defined(STM32GENERIC) - #include "../../inc/MarlinConfig.h" #if ENABLED(SDCARD_EEPROM_EMULATION) @@ -89,4 +88,4 @@ bool PersistentStore::read_data(int &pos, uint8_t *value, const size_t size, uin } #endif // SDCARD_EEPROM_EMULATION -#endif // STM32 && !STM32GENERIC +#endif // ARDUINO_ARCH_STM32 && !STM32GENERIC diff --git a/Marlin/src/HAL/STM32/fast_pwm.cpp b/Marlin/src/HAL/STM32/fast_pwm.cpp index 99101c6e81fe..42eecb5e1a96 100644 --- a/Marlin/src/HAL/STM32/fast_pwm.cpp +++ b/Marlin/src/HAL/STM32/fast_pwm.cpp @@ -19,6 +19,7 @@ * along with this program. If not, see . * */ +#if defined(ARDUINO_ARCH_STM32) && !defined(STM32GENERIC) #include "../../inc/MarlinConfigPre.h" @@ -55,3 +56,4 @@ void set_pwm_duty(const pin_t pin, const uint16_t v, const uint16_t v_size/*=255 } #endif // NEEDS_HARDWARE_PWM +#endif // ARDUINO_ARCH_STM32 && !STM32GENERIC diff --git a/Marlin/src/HAL/STM32/tft/tft_fsmc.cpp b/Marlin/src/HAL/STM32/tft/tft_fsmc.cpp index 3a080d5e271e..b6bc7fcd8426 100644 --- a/Marlin/src/HAL/STM32/tft/tft_fsmc.cpp +++ b/Marlin/src/HAL/STM32/tft/tft_fsmc.cpp @@ -19,6 +19,7 @@ * along with this program. If not, see . * */ +#if defined(ARDUINO_ARCH_STM32) && !defined(STM32GENERIC) #include "../../../inc/MarlinConfig.h" @@ -178,3 +179,4 @@ void TFT_FSMC::TransmitDMA(uint32_t MemoryIncrease, uint16_t *Data, uint16_t Cou } #endif // HAS_FSMC_TFT +#endif // ARDUINO_ARCH_STM32 && !STM32GENERIC diff --git a/Marlin/src/HAL/STM32/tft/tft_spi.cpp b/Marlin/src/HAL/STM32/tft/tft_spi.cpp index d3eb4ba8db6a..aed15ad66df5 100644 --- a/Marlin/src/HAL/STM32/tft/tft_spi.cpp +++ b/Marlin/src/HAL/STM32/tft/tft_spi.cpp @@ -19,6 +19,7 @@ * along with this program. If not, see . * */ +#if defined(ARDUINO_ARCH_STM32) && !defined(STM32GENERIC) #include "../../../inc/MarlinConfig.h" @@ -210,3 +211,4 @@ void TFT_SPI::TransmitDMA(uint32_t MemoryIncrease, uint16_t *Data, uint16_t Coun } #endif // HAS_SPI_TFT +#endif // ARDUINO_ARCH_STM32 && !STM32GENERIC diff --git a/Marlin/src/HAL/STM32/tft/xpt2046.cpp b/Marlin/src/HAL/STM32/tft/xpt2046.cpp index f95bb8ca4da4..7e2dbfd15adb 100644 --- a/Marlin/src/HAL/STM32/tft/xpt2046.cpp +++ b/Marlin/src/HAL/STM32/tft/xpt2046.cpp @@ -19,6 +19,7 @@ * along with this program. If not, see . * */ +#if defined(ARDUINO_ARCH_STM32) && !defined(STM32GENERIC) #include "../../../inc/MarlinConfig.h" @@ -186,3 +187,4 @@ uint16_t XPT2046::SoftwareIO(uint16_t data) { } #endif // HAS_TFT_XPT2046 +#endif // ARDUINO_ARCH_STM32 && !STM32GENERIC diff --git a/Marlin/src/HAL/STM32/usb_serial.cpp b/Marlin/src/HAL/STM32/usb_serial.cpp index 25c47d694fbd..705d649ff58c 100644 --- a/Marlin/src/HAL/STM32/usb_serial.cpp +++ b/Marlin/src/HAL/STM32/usb_serial.cpp @@ -16,7 +16,6 @@ * along with this program. If not, see . * */ - #if defined(ARDUINO_ARCH_STM32) && !defined(STM32GENERIC) #include "../../inc/MarlinConfigPre.h" @@ -51,5 +50,5 @@ void USB_Hook_init() { USBD_CDC_fops.Receive = USBD_CDC_Receive_hook; } -#endif // EMERGENCY_PARSER +#endif // EMERGENCY_PARSER && USBD_USE_CDC #endif // ARDUINO_ARCH_STM32 && !STM32GENERIC diff --git a/Marlin/src/HAL/STM32/watchdog.cpp b/Marlin/src/HAL/STM32/watchdog.cpp index 3d8340831118..aad0a79a0cb2 100644 --- a/Marlin/src/HAL/STM32/watchdog.cpp +++ b/Marlin/src/HAL/STM32/watchdog.cpp @@ -46,5 +46,4 @@ void HAL_watchdog_refresh() { } #endif // USE_WATCHDOG - #endif // ARDUINO_ARCH_STM32 && !STM32GENERIC From 7ce675e60497f1f68ab1f3753e3d114c9418dd66 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Wed, 25 Nov 2020 23:36:22 -0600 Subject: [PATCH 24/47] No auto debug for EEPROM_CHITCHAT --- Marlin/src/module/settings.cpp | 8 +++----- 1 file changed, 3 insertions(+), 5 deletions(-) diff --git a/Marlin/src/module/settings.cpp b/Marlin/src/module/settings.cpp index 6614aec35b8a..c49c643b60e3 100644 --- a/Marlin/src/module/settings.cpp +++ b/Marlin/src/module/settings.cpp @@ -559,13 +559,11 @@ void MarlinSettings::postprocess() { #endif // SD_FIRMWARE_UPDATE #ifdef ARCHIM2_SPI_FLASH_EEPROM_BACKUP_SIZE - static_assert( - EEPROM_OFFSET + sizeof(SettingsData) < ARCHIM2_SPI_FLASH_EEPROM_BACKUP_SIZE, - "ARCHIM2_SPI_FLASH_EEPROM_BACKUP_SIZE is insufficient to capture all EEPROM data." - ); + static_assert(EEPROM_OFFSET + sizeof(SettingsData) < ARCHIM2_SPI_FLASH_EEPROM_BACKUP_SIZE, + "ARCHIM2_SPI_FLASH_EEPROM_BACKUP_SIZE is insufficient to capture all EEPROM data."); #endif -#define DEBUG_OUT ENABLED(EEPROM_CHITCHAT) +//#define DEBUG_OUT 1 #include "../core/debug_out.h" #if ENABLED(EEPROM_SETTINGS) From 3ba374a29eff40535e72267f4d5cf89ca07a3ce6 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Wed, 25 Nov 2020 22:28:42 -0600 Subject: [PATCH 25/47] Optimize emergency parser check --- Marlin/src/gcode/queue.cpp | 9 ++++----- 1 file changed, 4 insertions(+), 5 deletions(-) diff --git a/Marlin/src/gcode/queue.cpp b/Marlin/src/gcode/queue.cpp index 12dfce5111ff..ba2cdf35b11c 100644 --- a/Marlin/src/gcode/queue.cpp +++ b/Marlin/src/gcode/queue.cpp @@ -538,12 +538,11 @@ void GCodeQueue::get_serial_commands() { #if DISABLED(EMERGENCY_PARSER) // Process critical commands early - if (strcmp_P(command, PSTR("M108")) == 0) { - wait_for_heatup = false; - TERN_(HAS_LCD_MENU, wait_for_user = false); + if (command[0] == 'M') switch (command[3]) { + case '8': if (command[2] == '0' && command[1] == '1') { wait_for_heatup = false; TERN_(HAS_LCD_MENU, wait_for_user = false); } break; + case '2': if (command[2] == '1' && command[1] == '1') kill(M112_KILL_STR, nullptr, true); break; + case '0': if (command[1] == '4' && command[2] == '1') quickstop_stepper(); break; } - if (strcmp_P(command, PSTR("M112")) == 0) kill(M112_KILL_STR, nullptr, true); - if (strcmp_P(command, PSTR("M410")) == 0) quickstop_stepper(); #endif #if defined(NO_TIMEOUTS) && NO_TIMEOUTS > 0 From 58ac815822b4c04f29b66ddf076156e6b4994749 Mon Sep 17 00:00:00 2001 From: wmariz <11435639+wmariz@users.noreply.github.com> Date: Thu, 26 Nov 2020 10:58:19 -0300 Subject: [PATCH 26/47] Level Corners with Probe option (#20241) --- Marlin/Configuration.h | 6 + Marlin/src/feature/backlash.cpp | 10 +- Marlin/src/feature/bltouch.cpp | 11 +- Marlin/src/gcode/calibrate/G425.cpp | 8 +- Marlin/src/inc/SanityCheck.h | 4 +- Marlin/src/lcd/language/language_en.h | 3 + Marlin/src/lcd/menu/menu_bed_corners.cpp | 205 +++++++++++++++++++---- Marlin/src/module/endstops.cpp | 6 +- Marlin/src/module/probe.cpp | 20 +-- Marlin/src/module/probe.h | 6 + buildroot/tests/LPC1769-tests | 1 + 11 files changed, 211 insertions(+), 69 deletions(-) diff --git a/Marlin/Configuration.h b/Marlin/Configuration.h index c64569d2bf91..3320e18abc3d 100644 --- a/Marlin/Configuration.h +++ b/Marlin/Configuration.h @@ -1392,6 +1392,12 @@ #define LEVEL_CORNERS_HEIGHT 0.0 // (mm) Z height of nozzle at leveling points #define LEVEL_CORNERS_Z_HOP 4.0 // (mm) Z height of nozzle between leveling points //#define LEVEL_CENTER_TOO // Move to the center after the last corner + //#define LEVEL_CORNERS_USE_PROBE + #if ENABLED(LEVEL_CORNERS_USE_PROBE) + #define LEVEL_CORNERS_PROBE_TOLERANCE 0.1 + #define LEVEL_CORNERS_VERIFY_RAISED // After adjustment triggers the probe, re-probe to verify + //#define LEVEL_CORNERS_AUDIO_FEEDBACK + #endif #endif /** diff --git a/Marlin/src/feature/backlash.cpp b/Marlin/src/feature/backlash.cpp index 867e9cdd217c..b848214f0c46 100644 --- a/Marlin/src/feature/backlash.cpp +++ b/Marlin/src/feature/backlash.cpp @@ -123,24 +123,22 @@ void Backlash::add_correction_steps(const int32_t &da, const int32_t &db, const } #if ENABLED(MEASURE_BACKLASH_WHEN_PROBING) - #if HAS_CUSTOM_PROBE_PIN - #define TEST_PROBE_PIN (READ(Z_MIN_PROBE_PIN) != Z_MIN_PROBE_ENDSTOP_INVERTING) - #else - #define TEST_PROBE_PIN (READ(Z_MIN_PIN) != Z_MIN_ENDSTOP_INVERTING) - #endif + + #include "../module/probe.h" // Measure Z backlash by raising nozzle in increments until probe deactivates void Backlash::measure_with_probe() { if (measured_count.z == 255) return; const float start_height = current_position.z; - while (current_position.z < (start_height + BACKLASH_MEASUREMENT_LIMIT) && TEST_PROBE_PIN) + while (current_position.z < (start_height + BACKLASH_MEASUREMENT_LIMIT) && PROBE_TRIGGERED()) do_blocking_move_to_z(current_position.z + BACKLASH_MEASUREMENT_RESOLUTION, MMM_TO_MMS(BACKLASH_MEASUREMENT_FEEDRATE)); // The backlash from all probe points is averaged, so count the number of measurements measured_mm.z += current_position.z - start_height; measured_count.z++; } + #endif #endif // BACKLASH_COMPENSATION diff --git a/Marlin/src/feature/bltouch.cpp b/Marlin/src/feature/bltouch.cpp index d6b1f99c16b9..48eaf9efc400 100644 --- a/Marlin/src/feature/bltouch.cpp +++ b/Marlin/src/feature/bltouch.cpp @@ -31,6 +31,7 @@ BLTouch bltouch; bool BLTouch::last_written_mode; // Initialized by settings.load, 0 = Open Drain; 1 = 5V Drain #include "../module/servo.h" +#include "../module/probe.h" void stop(); @@ -90,15 +91,7 @@ void BLTouch::clear() { _stow(); // STOW to be ready for meaningful work. Could fail, don't care } -bool BLTouch::triggered() { - return ( - #if ENABLED(Z_MIN_PROBE_USES_Z_MIN_ENDSTOP_PIN) - READ(Z_MIN_PIN) != Z_MIN_ENDSTOP_INVERTING - #else - READ(Z_MIN_PROBE_PIN) != Z_MIN_PROBE_ENDSTOP_INVERTING - #endif - ); -} +bool BLTouch::triggered() { return PROBE_TRIGGERED(); } bool BLTouch::deploy_proc() { // Do a DEPLOY diff --git a/Marlin/src/gcode/calibrate/G425.cpp b/Marlin/src/gcode/calibrate/G425.cpp index 6517e6b4bdc4..9510da7740ef 100644 --- a/Marlin/src/gcode/calibrate/G425.cpp +++ b/Marlin/src/gcode/calibrate/G425.cpp @@ -143,14 +143,16 @@ inline void park_above_object(measurements_t &m, const float uncertainty) { #endif +#if !PIN_EXISTS(CALIBRATION) + #include "../../module/probe.h" +#endif + inline bool read_calibration_pin() { return ( #if PIN_EXISTS(CALIBRATION) READ(CALIBRATION_PIN) != CALIBRATION_PIN_INVERTING - #elif HAS_CUSTOM_PROBE_PIN - READ(Z_MIN_PROBE_PIN) != Z_MIN_PROBE_ENDSTOP_INVERTING #else - READ(Z_MIN_PIN) != Z_MIN_ENDSTOP_INVERTING + PROBE_TRIGGERED() #endif ); } diff --git a/Marlin/src/inc/SanityCheck.h b/Marlin/src/inc/SanityCheck.h index 9f4c10dd53e1..eec9ff084464 100644 --- a/Marlin/src/inc/SanityCheck.h +++ b/Marlin/src/inc/SanityCheck.h @@ -357,6 +357,8 @@ #error "LEVEL_CORNERS_INSET is now LEVEL_CORNERS_INSET_LFRB." #elif ENABLED(LEVEL_BED_CORNERS) && !defined(LEVEL_CORNERS_INSET_LFRB) #error "LEVEL_BED_CORNERS requires LEVEL_CORNERS_INSET_LFRB values." +#elif BOTH(LEVEL_CORNERS_USE_PROBE, SENSORLESS_PROBING) + #error "LEVEL_CORNERS_USE_PROBE is incompatible with SENSORLESS_PROBING." #elif defined(BEZIER_JERK_CONTROL) #error "BEZIER_JERK_CONTROL is now S_CURVE_ACCELERATION." #elif HAS_JUNCTION_DEVIATION && defined(JUNCTION_DEVIATION_FACTOR) @@ -1603,7 +1605,7 @@ static_assert(hbm[Z_AXIS] >= 0, "HOMING_BUMP_MM.Z must be greater than or equal * Allen Key * Deploying the Allen Key probe uses big moves in z direction. Too dangerous for an unhomed z-axis. */ -#if ENABLED(Z_PROBE_ALLEN_KEY) && (Z_HOME_DIR < 0) && ENABLED(Z_MIN_PROBE_USES_Z_MIN_ENDSTOP_PIN) +#if BOTH(Z_PROBE_ALLEN_KEY, Z_MIN_PROBE_USES_Z_MIN_ENDSTOP_PIN) && (Z_HOME_DIR < 0) #error "You can't home to a Z min endstop with a Z_PROBE_ALLEN_KEY." #endif diff --git a/Marlin/src/lcd/language/language_en.h b/Marlin/src/lcd/language/language_en.h index af0903b91612..2892f79df8ab 100644 --- a/Marlin/src/lcd/language/language_en.h +++ b/Marlin/src/lcd/language/language_en.h @@ -125,6 +125,8 @@ namespace Language_en { PROGMEM Language_Str MSG_BED_LEVELING = _UxGT("Bed Leveling"); PROGMEM Language_Str MSG_LEVEL_BED = _UxGT("Level Bed"); PROGMEM Language_Str MSG_LEVEL_CORNERS = _UxGT("Level Corners"); + PROGMEM Language_Str MSG_LEVEL_CORNERS_RAISE = _UxGT("Raise Bed Until Probe Triggered"); + PROGMEM Language_Str MSG_LEVEL_CORNERS_IN_RANGE = _UxGT("All Corners Within Tolerance. Level Bed"); PROGMEM Language_Str MSG_NEXT_CORNER = _UxGT("Next Corner"); PROGMEM Language_Str MSG_MESH_EDITOR = _UxGT("Mesh Editor"); PROGMEM Language_Str MSG_EDIT_MESH = _UxGT("Edit Mesh"); @@ -379,6 +381,7 @@ namespace Language_en { PROGMEM Language_Str MSG_BUTTON_DONE = _UxGT("Done"); PROGMEM Language_Str MSG_BUTTON_BACK = _UxGT("Back"); PROGMEM Language_Str MSG_BUTTON_PROCEED = _UxGT("Proceed"); + PROGMEM Language_Str MSG_BUTTON_SKIP = _UxGT("Skip"); PROGMEM Language_Str MSG_PAUSING = _UxGT("Pausing..."); PROGMEM Language_Str MSG_PAUSE_PRINT = _UxGT("Pause Print"); PROGMEM Language_Str MSG_RESUME_PRINT = _UxGT("Resume Print"); diff --git a/Marlin/src/lcd/menu/menu_bed_corners.cpp b/Marlin/src/lcd/menu/menu_bed_corners.cpp index 16f9992c1852..52d2d0ec3db6 100644 --- a/Marlin/src/lcd/menu/menu_bed_corners.cpp +++ b/Marlin/src/lcd/menu/menu_bed_corners.cpp @@ -44,53 +44,187 @@ #define LEVEL_CORNERS_HEIGHT 0.0 #endif +#if ENABLED(LEVEL_CORNERS_USE_PROBE) + #include "../../module/probe.h" + #include "../../module/endstops.h" + #if ENABLED(BLTOUCH) + #include "../../feature/bltouch.h" + #endif + #ifndef LEVEL_CORNERS_PROBE_TOLERANCE + #define LEVEL_CORNERS_PROBE_TOLERANCE 0.1 + #endif + #if ENABLED(LEVEL_CORNERS_AUDIO_FEEDBACK) + #include "../../libs/buzzer.h" + #define PROBE_BUZZ() BUZZ(200, 600) + #else + #define PROBE_BUZZ() NOOP + #endif + static float last_z; + static bool corner_probing_done; + static bool verify_corner; + static int good_points; +#endif + static_assert(LEVEL_CORNERS_Z_HOP >= 0, "LEVEL_CORNERS_Z_HOP must be >= 0. Please update your configuration."); +extern const char G28_STR[]; + #if HAS_LEVELING static bool leveling_was_active = false; #endif +static int8_t bed_corner; + /** * Level corners, starting in the front-left corner. */ -static int8_t bed_corner; -static inline void _lcd_goto_next_corner() { - constexpr float lfrb[4] = LEVEL_CORNERS_INSET_LFRB; - constexpr xy_pos_t lf { (X_MIN_BED) + lfrb[0], (Y_MIN_BED) + lfrb[1] }, - rb { (X_MAX_BED) - lfrb[2], (Y_MAX_BED) - lfrb[3] }; - line_to_z(LEVEL_CORNERS_Z_HOP); - switch (bed_corner) { - case 0: current_position = lf; break; // copy xy - case 1: current_position.x = rb.x; break; - case 2: current_position.y = rb.y; break; - case 3: current_position.x = lf.x; break; - #if ENABLED(LEVEL_CENTER_TOO) - case 4: current_position.set(X_CENTER, Y_CENTER); break; +#if ENABLED(LEVEL_CORNERS_USE_PROBE) + + static inline void _lcd_level_bed_corners_probing() { + ui.goto_screen([]{ MenuItem_static::draw((LCD_HEIGHT - 1) / 2, GET_TEXT(MSG_PROBING_MESH)); }); + + float lfrb[4] = LEVEL_CORNERS_INSET_LFRB; + xy_pos_t lf { (X_MIN_BED) + lfrb[0] - probe.offset_xy.x , (Y_MIN_BED) + lfrb[1] - probe.offset_xy.y }, + rb { (X_MAX_BED) - lfrb[2] - probe.offset_xy.x , (Y_MAX_BED) - lfrb[3] - probe.offset_xy.y }; + + do_blocking_move_to_z(LEVEL_CORNERS_Z_HOP - probe.offset.z); + + switch (bed_corner) { + case 0: current_position = lf; break; // copy xy + case 1: current_position.x = rb.x; break; + case 2: current_position.y = rb.y; break; + case 3: current_position.x = lf.x; break; + #if ENABLED(LEVEL_CENTER_TOO) + case 4: current_position.set(X_CENTER - probe.offset_xy.x, Y_CENTER - probe.offset_xy.y); good_points--; break; + #endif + } + + do_blocking_move_to_xy(current_position); + + #if ENABLED(BLTOUCH) && DISABLED(BLTOUCH_HS_MODE) + bltouch.deploy(); // DEPLOY in LOW SPEED MODE on every probe action #endif + TERN_(QUIET_PROBING, probe.set_probing_paused(true)); + + // Move down until the probe is triggered + do_blocking_move_to_z(last_z - (LEVEL_CORNERS_PROBE_TOLERANCE), manual_feedrate_mm_s.z); + + // Check to see if the probe was triggered + bool probe_triggered = TEST(endstops.trigger_state(), TERN(Z_MIN_PROBE_USES_Z_MIN_ENDSTOP_PIN, Z_MIN, Z_MIN_PROBE)); + if (!probe_triggered) { + + static bool wait_for_probe; + + ui.goto_screen([]{ + MenuItem_confirm::select_screen( + GET_TEXT(MSG_BUTTON_DONE), GET_TEXT(MSG_BUTTON_SKIP) + , []{ corner_probing_done = true; + wait_for_probe = false; + TERN_(HAS_LEVELING, set_bed_leveling_enabled(leveling_was_active)); + ui.goto_previous_screen_no_defer(); + } + , []{ wait_for_probe = false; } + , GET_TEXT(MSG_LEVEL_CORNERS_RAISE) + , (const char*)nullptr, PSTR("") + ); + }); + ui.set_selection(true); + + wait_for_probe = true; + while (wait_for_probe && !probe_triggered) { + probe_triggered = PROBE_TRIGGERED(); + if (probe_triggered) PROBE_BUZZ(); + idle(); + } + wait_for_probe = false; + + TERN_(LEVEL_CORNERS_VERIFY_RAISED, verify_corner = true); + } + + TERN_(QUIET_PROBING, probe.set_probing_paused(false)); + + #if ENABLED(BLTOUCH) && DISABLED(BLTOUCH_HS_MODE) + bltouch.stow(); + #endif + + if (probe_triggered) { + endstops.hit_on_purpose(); + if (!WITHIN(current_position.z, last_z - (LEVEL_CORNERS_PROBE_TOLERANCE), last_z + (LEVEL_CORNERS_PROBE_TOLERANCE))) { + last_z = current_position.z; + good_points = 0; + } + if (!verify_corner) good_points++; + } + + if (!corner_probing_done) { + if (!verify_corner) bed_corner++; + if (bed_corner > 3) bed_corner = 0; + verify_corner = false; + if (good_points < 4) + _lcd_level_bed_corners_probing(); + else { + ui.goto_screen([]{ + MenuItem_confirm::confirm_screen( + []{ ui.goto_previous_screen_no_defer(); + queue.inject_P(TERN(HAS_LEVELING, PSTR("G28\nG29"), G28_STR)); + } + , []{ ui.goto_previous_screen_no_defer(); } + , GET_TEXT(MSG_LEVEL_CORNERS_IN_RANGE) + , (const char*)nullptr, PSTR("?") + ); + }); + ui.set_selection(true); + } + } } - line_to_current_position(manual_feedrate_mm_s.x); - line_to_z(LEVEL_CORNERS_HEIGHT); - if (++bed_corner > 3 + ENABLED(LEVEL_CENTER_TOO)) bed_corner = 0; -} + +#else + + static inline void _lcd_goto_next_corner() { + constexpr float lfrb[4] = LEVEL_CORNERS_INSET_LFRB; + constexpr xy_pos_t lf { (X_MIN_BED) + lfrb[0], (Y_MIN_BED) + lfrb[1] }, + rb { (X_MAX_BED) - lfrb[2], (Y_MAX_BED) - lfrb[3] }; + line_to_z(LEVEL_CORNERS_Z_HOP); + switch (bed_corner) { + case 0: current_position = lf; break; // copy xy + case 1: current_position.x = rb.x; break; + case 2: current_position.y = rb.y; break; + case 3: current_position.x = lf.x; break; + #if ENABLED(LEVEL_CENTER_TOO) + case 4: current_position.set(X_CENTER, Y_CENTER); break; + #endif + } + line_to_current_position(manual_feedrate_mm_s.x); + line_to_z(LEVEL_CORNERS_HEIGHT); + if (++bed_corner > 3 + ENABLED(LEVEL_CENTER_TOO)) bed_corner = 0; + } + +#endif static inline void _lcd_level_bed_corners_homing() { _lcd_draw_homing(); if (all_axes_homed()) { - bed_corner = 0; - ui.goto_screen([]{ - MenuItem_confirm::select_screen( - GET_TEXT(MSG_BUTTON_NEXT), GET_TEXT(MSG_BUTTON_DONE) - , _lcd_goto_next_corner - , []{ - TERN_(HAS_LEVELING, set_bed_leveling_enabled(leveling_was_active)); - ui.goto_previous_screen_no_defer(); - } - , GET_TEXT(TERN(LEVEL_CENTER_TOO, MSG_LEVEL_BED_NEXT_POINT, MSG_NEXT_CORNER)) - , (const char*)nullptr, PSTR("?") - ); - }); - ui.set_selection(true); - _lcd_goto_next_corner(); + #if ENABLED(LEVEL_CORNERS_USE_PROBE) + TERN_(LEVEL_CENTER_TOO, bed_corner = 4); + endstops.enable_z_probe(true); + ui.goto_screen(_lcd_level_bed_corners_probing); + #else + bed_corner = 0; + ui.goto_screen([]{ + MenuItem_confirm::select_screen( + GET_TEXT(MSG_BUTTON_NEXT), GET_TEXT(MSG_BUTTON_DONE) + , _lcd_goto_next_corner + , []{ + TERN_(HAS_LEVELING, set_bed_leveling_enabled(leveling_was_active)); + ui.goto_previous_screen_no_defer(); + } + , GET_TEXT(TERN(LEVEL_CENTER_TOO, MSG_LEVEL_BED_NEXT_POINT, MSG_NEXT_CORNER)) + , (const char*)nullptr, PSTR("?") + ); + }); + ui.set_selection(true); + _lcd_goto_next_corner(); + #endif } } @@ -107,6 +241,13 @@ void _lcd_level_bed_corners() { set_bed_leveling_enabled(false); #endif + #if ENABLED(LEVEL_CORNERS_USE_PROBE) + last_z = LEVEL_CORNERS_HEIGHT; + corner_probing_done = false; + verify_corner = false; + good_points = 0; + #endif + ui.goto_screen(_lcd_level_bed_corners_homing); } diff --git a/Marlin/src/module/endstops.cpp b/Marlin/src/module/endstops.cpp index 697ced783379..ef0b92a7ee05 100644 --- a/Marlin/src/module/endstops.cpp +++ b/Marlin/src/module/endstops.cpp @@ -48,6 +48,10 @@ #include "../feature/joystick.h" #endif +#if HAS_BED_PROBE + #include "probe.h" +#endif + Endstops endstops; // private: @@ -455,7 +459,7 @@ void _O2 Endstops::report_states() { ES_REPORT(Z4_MAX); #endif #if HAS_CUSTOM_PROBE_PIN - print_es_state(READ(Z_MIN_PROBE_PIN) != Z_MIN_PROBE_ENDSTOP_INVERTING, PSTR(STR_Z_PROBE)); + print_es_state(PROBE_TRIGGERED(), PSTR(STR_Z_PROBE)); #endif #if HAS_FILAMENT_SENSOR #if NUM_RUNOUT_SENSORS == 1 diff --git a/Marlin/src/module/probe.cpp b/Marlin/src/module/probe.cpp index f02b90915063..47c6f569b7a9 100644 --- a/Marlin/src/module/probe.cpp +++ b/Marlin/src/module/probe.cpp @@ -270,13 +270,7 @@ FORCE_INLINE void probe_specific_action(const bool deploy) { #if ENABLED(PAUSE_BEFORE_DEPLOY_STOW) do { #if ENABLED(PAUSE_PROBE_DEPLOY_WHEN_TRIGGERED) - if (deploy == ( - #if HAS_CUSTOM_PROBE_PIN - READ(Z_MIN_PROBE_PIN) == Z_MIN_PROBE_ENDSTOP_INVERTING - #else - READ(Z_MIN_PIN) == Z_MIN_ENDSTOP_INVERTING - #endif - )) break; + if (deploy == PROBE_TRIGGERED()) break; #endif BUZZ(100, 659); @@ -375,23 +369,15 @@ bool Probe::set_deployed(const bool deploy) { const xy_pos_t old_xy = current_position; #if ENABLED(PROBE_TRIGGERED_WHEN_STOWED_TEST) - #if HAS_CUSTOM_PROBE_PIN - #define PROBE_STOWED() (READ(Z_MIN_PROBE_PIN) != Z_MIN_PROBE_ENDSTOP_INVERTING) - #else - #define PROBE_STOWED() (READ(Z_MIN_PIN) != Z_MIN_ENDSTOP_INVERTING) - #endif - #endif - - #ifdef PROBE_STOWED // Only deploy/stow if needed - if (PROBE_STOWED() == deploy) { + if (PROBE_TRIGGERED() == deploy) { if (!deploy) endstops.enable_z_probe(false); // Switch off triggered when stowed probes early // otherwise an Allen-Key probe can't be stowed. probe_specific_action(deploy); } - if (PROBE_STOWED() == deploy) { // Unchanged after deploy/stow action? + if (PROBE_TRIGGERED() == deploy) { // Unchanged after deploy/stow action? if (IsRunning()) { SERIAL_ERROR_MSG("Z-Probe failed"); LCD_ALERTMESSAGEPGM_P(PSTR("Err: ZPROBE")); diff --git a/Marlin/src/module/probe.h b/Marlin/src/module/probe.h index cac106fed681..e5ad892e379f 100644 --- a/Marlin/src/module/probe.h +++ b/Marlin/src/module/probe.h @@ -38,6 +38,12 @@ }; #endif +#if HAS_CUSTOM_PROBE_PIN + #define PROBE_TRIGGERED() (READ(Z_MIN_PROBE_PIN) != Z_MIN_PROBE_ENDSTOP_INVERTING) +#else + #define PROBE_TRIGGERED() (READ(Z_MIN_PIN) != Z_MIN_ENDSTOP_INVERTING) +#endif + class Probe { public: diff --git a/buildroot/tests/LPC1769-tests b/buildroot/tests/LPC1769-tests index 702f8035ecb3..f661babc40f0 100755 --- a/buildroot/tests/LPC1769-tests +++ b/buildroot/tests/LPC1769-tests @@ -19,6 +19,7 @@ opt_set TEMP_SENSOR_1 -1 opt_set TEMP_SENSOR_BED 5 opt_enable VIKI2 SDSUPPORT ADAPTIVE_FAN_SLOWING NO_FAN_SLOWING_IN_PID_TUNING \ FIX_MOUNTED_PROBE AUTO_BED_LEVELING_BILINEAR G29_RETRY_AND_RECOVER Z_MIN_PROBE_REPEATABILITY_TEST DEBUG_LEVELING_FEATURE \ + LEVEL_BED_CORNERS LEVEL_CORNERS_USE_PROBE LEVEL_CORNERS_VERIFY_RAISED \ BABYSTEPPING BABYSTEP_XY BABYSTEP_ZPROBE_OFFSET BABYSTEP_ZPROBE_GFX_OVERLAY \ PRINTCOUNTER NOZZLE_PARK_FEATURE NOZZLE_CLEAN_FEATURE SLOW_PWM_HEATERS PIDTEMPBED EEPROM_SETTINGS INCH_MODE_SUPPORT TEMPERATURE_UNITS_SUPPORT \ Z_SAFE_HOMING ADVANCED_PAUSE_FEATURE PARK_HEAD_ON_PAUSE \ From 5cae4e9f55a851d27efce52b7d67bc9b231a0654 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?=C5=A0t=C4=9Bp=C3=A1n=20Daleck=C3=BD?= <36531759+daleckystepan@users.noreply.github.com> Date: Thu, 26 Nov 2020 22:21:48 +0100 Subject: [PATCH 27/47] [WIP] Fix Probe::offset_xy (#20290) Co-authored-by: Jason Smith --- Marlin/src/module/probe.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/Marlin/src/module/probe.cpp b/Marlin/src/module/probe.cpp index 47c6f569b7a9..11447d71297e 100644 --- a/Marlin/src/module/probe.cpp +++ b/Marlin/src/module/probe.cpp @@ -89,7 +89,7 @@ Probe probe; xyz_pos_t Probe::offset; // Initialized by settings.load() #if HAS_PROBE_XY_OFFSET - const xy_pos_t &Probe::offset_xy = xy_pos_t(Probe::offset); + const xy_pos_t &Probe::offset_xy = Probe::offset; #endif #if ENABLED(Z_PROBE_SLED) From c61a311c0da25f2738e05c649cd8c2acb790cf8f Mon Sep 17 00:00:00 2001 From: thinkyhead Date: Fri, 27 Nov 2020 00:12:12 +0000 Subject: [PATCH 28/47] [cron] Bump distribution date (2020-11-27) --- Marlin/src/inc/Version.h | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/Marlin/src/inc/Version.h b/Marlin/src/inc/Version.h index 5fb065dc35d8..83345a9fd7f2 100644 --- a/Marlin/src/inc/Version.h +++ b/Marlin/src/inc/Version.h @@ -42,7 +42,7 @@ * version was tagged. */ #ifndef STRING_DISTRIBUTION_DATE - #define STRING_DISTRIBUTION_DATE "2020-11-26" + #define STRING_DISTRIBUTION_DATE "2020-11-27" #endif /** From b6a32500c401877e3ee1300fa613e81086bb31d3 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Thu, 26 Nov 2020 21:18:40 -0600 Subject: [PATCH 29/47] M808 Repeat Markers (#20084) --- Marlin/Configuration_adv.h | 2 + Marlin/src/MarlinCore.cpp | 5 ++ Marlin/src/feature/powerloss.cpp | 3 + Marlin/src/feature/powerloss.h | 6 ++ Marlin/src/feature/repeat.cpp | 81 +++++++++++++++++++++++++++ Marlin/src/feature/repeat.h | 49 ++++++++++++++++ Marlin/src/gcode/gcode.cpp | 4 ++ Marlin/src/gcode/gcode.h | 3 + Marlin/src/gcode/host/M115.cpp | 3 + Marlin/src/gcode/queue.cpp | 23 +++++--- Marlin/src/gcode/sd/M808.cpp | 51 +++++++++++++++++ Marlin/src/sd/cardreader.cpp | 3 +- Marlin/src/sd/cardreader.h | 7 ++- buildroot/test-gcode/M808-loops.gcode | 16 ++++++ buildroot/tests/mega2560-tests | 2 +- platformio.ini | 5 +- 16 files changed, 248 insertions(+), 15 deletions(-) create mode 100644 Marlin/src/feature/repeat.cpp create mode 100644 Marlin/src/feature/repeat.h create mode 100644 Marlin/src/gcode/sd/M808.cpp create mode 100644 buildroot/test-gcode/M808-loops.gcode diff --git a/Marlin/Configuration_adv.h b/Marlin/Configuration_adv.h index 7c8f2da948c6..e6b76a4133c1 100644 --- a/Marlin/Configuration_adv.h +++ b/Marlin/Configuration_adv.h @@ -1186,6 +1186,8 @@ //#define SD_IGNORE_AT_STARTUP // Don't mount the SD card when starting up //#define SDCARD_READONLY // Read-only SD card (to save over 2K of flash) + //#define GCODE_REPEAT_MARKERS // Enable G-code M808 to set repeat markers and do looping + #define SD_PROCEDURE_DEPTH 1 // Increase if you need more nested M32 calls #define SD_FINISHED_STEPPERRELEASE true // Disable steppers when SD Print is finished diff --git a/Marlin/src/MarlinCore.cpp b/Marlin/src/MarlinCore.cpp index 5769da05d0f2..b6282cb09835 100644 --- a/Marlin/src/MarlinCore.cpp +++ b/Marlin/src/MarlinCore.cpp @@ -173,6 +173,10 @@ #include "feature/pause.h" #endif +#if ENABLED(GCODE_REPEAT_MARKERS) + #include "feature/repeat.h" +#endif + #if ENABLED(POWER_LOSS_RECOVERY) #include "feature/powerloss.h" #endif @@ -435,6 +439,7 @@ bool printingIsPaused() { void startOrResumeJob() { if (!printingIsPaused()) { + TERN_(GCODE_REPEAT_MARKERS, repeat.reset()); TERN_(CANCEL_OBJECTS, cancelable.reset()); TERN_(LCD_SHOW_E_TOTAL, e_move_accumulator = 0); #if BOTH(LCD_SET_PROGRESS_MANUALLY, USE_M73_REMAINING_TIME) diff --git a/Marlin/src/feature/powerloss.cpp b/Marlin/src/feature/powerloss.cpp index c4e0ef694abe..c55b278a724a 100644 --- a/Marlin/src/feature/powerloss.cpp +++ b/Marlin/src/feature/powerloss.cpp @@ -182,6 +182,8 @@ void PrintJobRecovery::save(const bool force/*=false*/, const float zraise/*=0*/ info.current_position = current_position; info.feedrate = uint16_t(feedrate_mm_s * 60.0f); info.zraise = zraise; + + TERN_(GCODE_REPEAT_MARKERS, info.stored_repeat = repeat); TERN_(HAS_HOME_OFFSET, info.home_offset = home_offset); TERN_(HAS_POSITION_SHIFT, info.position_shift = position_shift); @@ -507,6 +509,7 @@ void PrintJobRecovery::resume() { sprintf_P(cmd, PSTR("G92.9 E%s"), dtostrf(info.current_position.e, 1, 3, str_1)); gcode.process_subcommands_now(cmd); + TERN_(GCODE_REPEAT_MARKERS, repeat = info.stored_repeat); TERN_(HAS_HOME_OFFSET, home_offset = info.home_offset); TERN_(HAS_POSITION_SHIFT, position_shift = info.position_shift); #if HAS_HOME_OFFSET || HAS_POSITION_SHIFT diff --git a/Marlin/src/feature/powerloss.h b/Marlin/src/feature/powerloss.h index 73cd0b70faf4..f964f122941f 100644 --- a/Marlin/src/feature/powerloss.h +++ b/Marlin/src/feature/powerloss.h @@ -30,6 +30,10 @@ #include "../inc/MarlinConfig.h" +#if ENABLED(GCODE_REPEAT_MARKERS) + #include "../feature/repeat.h" +#endif + #if ENABLED(MIXING_EXTRUDER) #include "../feature/mixing.h" #endif @@ -50,6 +54,8 @@ typedef struct { uint16_t feedrate; float zraise; + // Repeat information + TERN_(GCODE_REPEAT_MARKERS, Repeat stored_repeat); TERN_(HAS_HOME_OFFSET, xyz_pos_t home_offset); TERN_(HAS_POSITION_SHIFT, xyz_pos_t position_shift); diff --git a/Marlin/src/feature/repeat.cpp b/Marlin/src/feature/repeat.cpp new file mode 100644 index 000000000000..d48157a84d41 --- /dev/null +++ b/Marlin/src/feature/repeat.cpp @@ -0,0 +1,81 @@ +/** + * 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 . + * + */ +#include "../inc/MarlinConfig.h" + +#if ENABLED(GCODE_REPEAT_MARKERS) + +//#define DEBUG_GCODE_REPEAT_MARKERS + +#include "repeat.h" + +#include "../gcode/gcode.h" +#include "../sd/cardreader.h" + +#define DEBUG_OUT ENABLED(DEBUG_GCODE_REPEAT_MARKERS) +#include "../core/debug_out.h" + +repeat_marker_t Repeat::marker[MAX_REPEAT_NESTING]; +uint8_t Repeat::index; + +void Repeat::add_marker(const uint32_t sdpos, const uint16_t count) { + if (index >= MAX_REPEAT_NESTING) + SERIAL_ECHO_MSG("!Too many markers."); + else { + marker[index].sdpos = sdpos; + marker[index].counter = count ?: -1; + index++; + DEBUG_ECHOLNPAIR("Add Marker ", int(index), " at ", sdpos, " (", count, ")"); + } +} + +void Repeat::loop() { + if (!index) // No marker? + SERIAL_ECHO_MSG("!No marker set."); // Inform the user. + else { + const uint8_t ind = index - 1; // Active marker's index + if (!marker[ind].counter) { // Did its counter run out? + DEBUG_ECHOLNPAIR("Pass Marker ", int(index)); + index--; // Carry on. Previous marker on the next 'M808'. + } + else { + card.setIndex(marker[ind].sdpos); // Loop back to the marker. + if (marker[ind].counter > 0) // Ignore a negative (or zero) counter. + --marker[ind].counter; // Decrement the counter. If zero this 'M808' will be skipped next time. + DEBUG_ECHOLNPAIR("Goto Marker ", int(index), " at ", marker[ind].sdpos, " (", marker[ind].counter, ")"); + } + } +} + +void Repeat::cancel() { LOOP_L_N(i, index) marker[i].counter = 0; } + +void Repeat::early_parse_M808(char * const cmd) { + if (is_command_M808(cmd)) { + DEBUG_ECHOLNPAIR("Parsing \"", cmd, "\""); + parser.parse(cmd); + if (parser.seen('L')) + add_marker(card.getIndex(), parser.value_ushort()); + else + Repeat::loop(); + } +} + +#endif // GCODE_REPEAT_MARKERS diff --git a/Marlin/src/feature/repeat.h b/Marlin/src/feature/repeat.h new file mode 100644 index 000000000000..e293b2bbacb4 --- /dev/null +++ b/Marlin/src/feature/repeat.h @@ -0,0 +1,49 @@ +/** + * 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 . + * + */ +#pragma once + +#include "../inc/MarlinConfigPre.h" +#include "../gcode/parser.h" + +#include + +#define MAX_REPEAT_NESTING 10 + +typedef struct { + uint32_t sdpos; // The repeat file position + int16_t counter; // The counter for looping +} repeat_marker_t; + +class Repeat { +private: + static repeat_marker_t marker[MAX_REPEAT_NESTING]; + static uint8_t index; +public: + static inline void reset() { index = 0; } + static bool is_command_M808(char * const cmd) { return cmd[0] == 'M' && cmd[1] == '8' && cmd[2] == '0' && cmd[3] == '8' && !NUMERIC(cmd[4]); } + static void early_parse_M808(char * const cmd); + static void add_marker(const uint32_t sdpos, const uint16_t count); + static void loop(); + static void cancel(); +}; + +extern Repeat repeat; diff --git a/Marlin/src/gcode/gcode.cpp b/Marlin/src/gcode/gcode.cpp index 3bce34c1f323..8e2ef62204e8 100644 --- a/Marlin/src/gcode/gcode.cpp +++ b/Marlin/src/gcode/gcode.cpp @@ -882,6 +882,10 @@ void GcodeSuite::process_parsed_command(const bool no_ok/*=false*/) { case 800: parser.debug(); break; // M800: GCode Parser Test for M #endif + #if ENABLED(GCODE_REPEAT_MARKERS) + case 808: M808(); break; // M808: Set / Goto repeat markers + #endif + #if ENABLED(I2C_POSITION_ENCODERS) case 860: M860(); break; // M860: Report encoder module position case 861: M861(); break; // M861: Report encoder module status diff --git a/Marlin/src/gcode/gcode.h b/Marlin/src/gcode/gcode.h index 1d74ac371960..735456a533b3 100644 --- a/Marlin/src/gcode/gcode.h +++ b/Marlin/src/gcode/gcode.h @@ -242,6 +242,7 @@ * M672 - Set/Reset Duet Smart Effector's sensitivity. (Requires DUET_SMART_EFFECTOR and SMART_EFFECTOR_MOD_PIN) * M701 - Load filament (Requires FILAMENT_LOAD_UNLOAD_GCODES) * M702 - Unload filament (Requires FILAMENT_LOAD_UNLOAD_GCODES) + * M808 - Set or Goto a Repeat Marker (Requires GCODE_REPEAT_MARKERS) * M810-M819 - Define/execute a G-code macro (Requires GCODE_MACROS) * M851 - Set Z probe's XYZ offsets in current units. (Negative values: X=left, Y=front, Z=below) * M852 - Set skew factors: "M852 [I] [J] [K]". (Requires SKEW_CORRECTION_GCODE, and SKEW_CORRECTION_FOR_Z for IJ) @@ -807,6 +808,8 @@ class GcodeSuite { static void M702(); #endif + TERN_(GCODE_REPEAT_MARKERS, static void M808()); + TERN_(GCODE_MACROS, static void M810_819()); TERN_(HAS_BED_PROBE, static void M851()); diff --git a/Marlin/src/gcode/host/M115.cpp b/Marlin/src/gcode/host/M115.cpp index 529b1dd6d012..63511b606d16 100644 --- a/Marlin/src/gcode/host/M115.cpp +++ b/Marlin/src/gcode/host/M115.cpp @@ -117,6 +117,9 @@ void GcodeSuite::M115() { // SDCARD (M20, M23, M24, etc.) cap_line(PSTR("SDCARD"), ENABLED(SDSUPPORT)); + // REPEAT (M808) + cap_line(PSTR("REPEAT"), ENABLED(GCODE_REPEAT_MARKERS)); + // AUTOREPORT_SD_STATUS (M27 extension) cap_line(PSTR("AUTOREPORT_SD_STATUS"), ENABLED(AUTO_REPORT_SD_STATUS)); diff --git a/Marlin/src/gcode/queue.cpp b/Marlin/src/gcode/queue.cpp index ba2cdf35b11c..d23e9ee07fc3 100644 --- a/Marlin/src/gcode/queue.cpp +++ b/Marlin/src/gcode/queue.cpp @@ -51,6 +51,10 @@ GCodeQueue queue; #include "../feature/powerloss.h" #endif +#if ENABLED(GCODE_REPEAT_MARKERS) + #include "../feature/repeat.h" +#endif + /** * GCode line number handling. Hosts may opt to include line numbers when * sending commands to Marlin, and lines will be checked for sequentiality. @@ -577,10 +581,9 @@ void GCodeQueue::get_serial_commands() { if (!IS_SD_PRINTING()) return; int sd_count = 0; - bool card_eof = card.eof(); - while (length < BUFSIZE && !card_eof) { + while (length < BUFSIZE && !card.eof()) { const int16_t n = card.get(); - card_eof = card.eof(); + const bool card_eof = card.eof(); if (n < 0 && !card_eof) { SERIAL_ERROR_MSG(STR_SD_ERR_READ); continue; } const char sd_char = (char)n; @@ -590,17 +593,21 @@ void GCodeQueue::get_serial_commands() { // Reset stream state, terminate the buffer, and commit a non-empty command if (!is_eol && sd_count) ++sd_count; // End of file with no newline if (!process_line_done(sd_input_state, command_buffer[index_w], sd_count)) { + + // M808 S saves the sdpos of the next line. M808 loops to a new sdpos. + TERN_(GCODE_REPEAT_MARKERS, repeat.early_parse_M808(command_buffer[index_w])); + + // Put the new command into the buffer (no "ok" sent) _commit_command(false); - #if ENABLED(POWER_LOSS_RECOVERY) - recovery.cmd_sdpos = card.getIndex(); // Prime for the NEXT _commit_command - #endif + + // Prime Power-Loss Recovery for the NEXT _commit_command + TERN_(POWER_LOSS_RECOVERY, recovery.cmd_sdpos = card.getIndex()); } - if (card_eof) card.fileHasFinished(); // Handle end of file reached + if (card.eof()) card.fileHasFinished(); // Handle end of file reached } else process_stream_char(sd_char, sd_input_state, command_buffer[index_w], sd_count); - } } diff --git a/Marlin/src/gcode/sd/M808.cpp b/Marlin/src/gcode/sd/M808.cpp new file mode 100644 index 000000000000..0d11b16f8ae2 --- /dev/null +++ b/Marlin/src/gcode/sd/M808.cpp @@ -0,0 +1,51 @@ +/** + * 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 . + * + */ + +#include "../../inc/MarlinConfig.h" + +#if ENABLED(GCODE_REPEAT_MARKERS) + +#include "../gcode.h" +#include "../../feature/repeat.h" + +/** + * M808: Set / Goto a repeat marker + * + * L - Set a repeat marker with 'count' repetitions. If omitted, infinity. + * + * Examples: + * + * M808 L ; Set a loop marker with a count of infinity + * M808 L2 ; Set a loop marker with a count of 2 + * M808 ; Decrement and loop if not zero. + */ +void GcodeSuite::M808() { + + // Handled early and ignored here in the queue. + // Allowed to go into the queue for logging purposes. + + // M808 K sent from the host to cancel all loops + if (parser.seen('K')) repeat.cancel(); + +} + +#endif // GCODE_REPEAT_MARKERS diff --git a/Marlin/src/sd/cardreader.cpp b/Marlin/src/sd/cardreader.cpp index 4416f4e90792..bce84bbd3921 100644 --- a/Marlin/src/sd/cardreader.cpp +++ b/Marlin/src/sd/cardreader.cpp @@ -699,8 +699,7 @@ void CardReader::removeFile(const char * const name) { void CardReader::report_status() { if (isPrinting()) { - SERIAL_ECHOPGM(STR_SD_PRINTING_BYTE); - SERIAL_ECHO(sdpos); + SERIAL_ECHOPAIR(STR_SD_PRINTING_BYTE, sdpos); SERIAL_CHAR('/'); SERIAL_ECHOLN(filesize); } diff --git a/Marlin/src/sd/cardreader.h b/Marlin/src/sd/cardreader.h index c6fe37400c2d..dabbf719f92b 100644 --- a/Marlin/src/sd/cardreader.h +++ b/Marlin/src/sd/cardreader.h @@ -159,9 +159,9 @@ class CardReader { static inline uint32_t getIndex() { return sdpos; } static inline uint32_t getFileSize() { return filesize; } static inline bool eof() { return sdpos >= filesize; } - static inline void setIndex(const uint32_t index) { sdpos = index; file.seekSet(index); } + static inline void setIndex(const uint32_t index) { file.seekSet((sdpos = index)); } static inline char* getWorkDirName() { workDir.getDosName(filename); return filename; } - static inline int16_t get() { sdpos = file.curPosition(); return (int16_t)file.read(); } + static inline int16_t get() { int16_t out = (int16_t)file.read(); sdpos = file.curPosition(); return out; } static inline int16_t read(void* buf, uint16_t nbyte) { return file.isOpen() ? file.read(buf, nbyte) : -1; } static inline int16_t write(void* buf, uint16_t nbyte) { return file.isOpen() ? file.write(buf, nbyte) : -1; } @@ -244,7 +244,8 @@ class CardReader { static SdVolume volume; static SdFile file; - static uint32_t filesize, sdpos; + static uint32_t filesize, // Total size of the current file, in bytes + sdpos; // Index most recently read (one behind file.getPos) // // Procedure calls to other files diff --git a/buildroot/test-gcode/M808-loops.gcode b/buildroot/test-gcode/M808-loops.gcode new file mode 100644 index 000000000000..6248c9cc3146 --- /dev/null +++ b/buildroot/test-gcode/M808-loops.gcode @@ -0,0 +1,16 @@ +; +; M808 Repeat Marker Test +; + +M808 L3 ; Marker at 54 + +M118 Outer Loop +M300 S220 P100 + +M808 L5 ; Marker at 111 + +M118 Inner Loop +M300 S110 P100 + +M808 +M808 diff --git a/buildroot/tests/mega2560-tests b/buildroot/tests/mega2560-tests index a968a5d21316..da3a79f58cb4 100755 --- a/buildroot/tests/mega2560-tests +++ b/buildroot/tests/mega2560-tests @@ -107,7 +107,7 @@ restore_configs opt_set MOTHERBOARD BOARD_MEGACONTROLLER opt_set LCD_LANGUAGE de opt_enable EEPROM_SETTINGS EEPROM_CHITCHAT \ - MINIPANEL SDSUPPORT PCA9632 LCD_INFO_MENU SOUND_MENU_ITEM \ + MINIPANEL SDSUPPORT PCA9632 LCD_INFO_MENU SOUND_MENU_ITEM GCODE_REPEAT_MARKERS \ AUTO_BED_LEVELING_BILINEAR PROBE_MANUALLY LCD_BED_LEVELING G26_MESH_VALIDATION MESH_EDIT_MENU \ LIN_ADVANCE EXTRA_LIN_ADVANCE_K \ INCH_MODE_SUPPORT TEMPERATURE_UNITS_SUPPORT EXPERIMENTAL_I2CBUS M100_FREE_MEMORY_WATCHER \ diff --git a/platformio.ini b/platformio.ini index 062514c882e5..52310e6b8198 100644 --- a/platformio.ini +++ b/platformio.ini @@ -101,6 +101,7 @@ default_src_filter = + - - + - - - - - + - - - - - - - @@ -182,6 +183,7 @@ default_src_filter = + - - + - - - + - - - - @@ -374,6 +376,7 @@ G38_PROBE_TARGET = src_filter=+ MAGNETIC_PARKING_EXTRUDER = src_filter=+ SDSUPPORT = src_filter=+ HAS_MEDIA_SUBCALLS = src_filter=+ +GCODE_REPEAT_MARKERS = src_filter=+ + HAS_EXTRUDERS = src_filter=+ + AUTO_REPORT_TEMPERATURES = src_filter=+ INCH_MODE_SUPPORT = src_filter=+ @@ -402,7 +405,7 @@ framework = arduino extra_scripts = ${common.extra_scripts} build_flags = ${common.build_flags} lib_deps = ${common.lib_deps} -monitor_speed = 250000 +monitor_speed = 115200 monitor_flags = --quiet --echo From 819ec462b8440172c32f009adf44ad54c266c1e5 Mon Sep 17 00:00:00 2001 From: BsCmOD <64871957+BsCmOD@users.noreply.github.com> Date: Fri, 27 Nov 2020 04:25:18 +0100 Subject: [PATCH 30/47] FIX TMC menu message (#20294) --- Marlin/src/lcd/menu/menu_tmc.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/Marlin/src/lcd/menu/menu_tmc.cpp b/Marlin/src/lcd/menu/menu_tmc.cpp index 402ee41a1b45..69193701eb1f 100644 --- a/Marlin/src/lcd/menu/menu_tmc.cpp +++ b/Marlin/src/lcd/menu/menu_tmc.cpp @@ -247,7 +247,7 @@ void menu_tmc_current() { void menu_tmc() { START_MENU(); - BACK_ITEM(MSG_CONTROL); + BACK_ITEM(MSG_ADVANCED_SETTINGS); SUBMENU(MSG_TMC_CURRENT, menu_tmc_current); #if ENABLED(HYBRID_THRESHOLD) SUBMENU(MSG_TMC_HYBRID_THRS, menu_tmc_hybrid_thrs); From 109f68f7dff0b0539d6d522ac3b849b516394ae9 Mon Sep 17 00:00:00 2001 From: ellensp Date: Fri, 27 Nov 2020 17:50:21 +1300 Subject: [PATCH 31/47] Fix BTT GTR 1.0 endstop/DIAG pins (#20296) --- Marlin/src/pins/stm32f4/pins_BTT_GTR_V1_0.h | 51 ++++++++++++++++++--- 1 file changed, 45 insertions(+), 6 deletions(-) diff --git a/Marlin/src/pins/stm32f4/pins_BTT_GTR_V1_0.h b/Marlin/src/pins/stm32f4/pins_BTT_GTR_V1_0.h index 6c475faeb558..bfa4007658db 100644 --- a/Marlin/src/pins/stm32f4/pins_BTT_GTR_V1_0.h +++ b/Marlin/src/pins/stm32f4/pins_BTT_GTR_V1_0.h @@ -46,15 +46,54 @@ #define PS_ON_PIN PH6 +// +// Trinamic Stallguard pins +// +#define X_DIAG_PIN PF2 // X- +#define Y_DIAG_PIN PC13 // Y- +#define Z_DIAG_PIN PE0 // Z- +#define E0_DIAG_PIN PG14 // X+ +#define E1_DIAG_PIN PG9 // Y+ +#define E2_DIAG_PIN PD3 // Z+ + // // Limit Switches // -#define X_MIN_PIN PF2 -#define X_MAX_PIN PG14 -#define Y_MIN_PIN PC13 -#define Y_MAX_PIN PG9 -#define Z_MIN_PIN PE0 -#define Z_MAX_PIN PD3 +#ifdef X_STALL_SENSITIVITY + #define X_STOP_PIN X_DIAG_PIN + #if X_HOME_DIR < 0 + #define X_MAX_PIN E0_DIAG_PIN // X+ + #else + #define X_MIN_PIN E0_DIAG_PIN // X+ + #endif +#else + #define X_MIN_PIN X_DIAG_PIN // X- + #define X_MAX_PIN E0_DIAG_PIN // X+ +#endif + +#ifdef Y_STALL_SENSITIVITY + #define Y_STOP_PIN Y_DIAG_PIN + #if Y_HOME_DIR < 0 + #define Y_MAX_PIN E1_DIAG_PIN // Y+ + #else + #define Y_MIN_PIN E1_DIAG_PIN // Y+ + #endif +#else + #define Y_MIN_PIN Y_DIAG_PIN // Y- + #define Y_MAX_PIN E1_DIAG_PIN // Y+ +#endif + +#ifdef Z_STALL_SENSITIVITY + #define Z_STOP_PIN Z_DIAG_PIN + #if Z_HOME_DIR < 0 + #define Z_MAX_PIN E2_DIAG_PIN // Z+ + #else + #define Z_MIN_PIN E2_DIAG_PIN // Z+ + #endif +#else + #define Z_MIN_PIN Z_DIAG_PIN // Z- + #define Z_MAX_PIN E2_DIAG_PIN // Z+ +#endif // // Pins on the extender From bab660ca7d4f2f22586375e44d97678d9f7846c1 Mon Sep 17 00:00:00 2001 From: yysh12 Date: Thu, 26 Nov 2020 23:29:07 -0600 Subject: [PATCH 32/47] =?UTF-8?q?Fix=20G2/G3=20arcs=20>=20180=C2=B0=20(#20?= =?UTF-8?q?292)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Marlin/src/gcode/motion/G2_G3.cpp | 13 +++++++++---- 1 file changed, 9 insertions(+), 4 deletions(-) diff --git a/Marlin/src/gcode/motion/G2_G3.cpp b/Marlin/src/gcode/motion/G2_G3.cpp index c713877a0e6a..b920e2307336 100644 --- a/Marlin/src/gcode/motion/G2_G3.cpp +++ b/Marlin/src/gcode/motion/G2_G3.cpp @@ -77,16 +77,21 @@ void plan_arc( rt_Y = cart[q_axis] - center_Q, start_L = current_position[l_axis]; - // CCW angle of rotation between position and target from the circle center. Only one atan2() trig computation required. + // Angle of rotation between position and target from the circle center. float angular_travel = ATAN2(rvec.a * rt_Y - rvec.b * rt_X, rvec.a * rt_X + rvec.b * rt_Y); - if (angular_travel < 0) angular_travel += RADIANS(360); + + // Make sure angular travel over 180 degrees goes the other way around. + switch (((angular_travel < 0) << 1) + clockwise) { + case 1: angular_travel -= RADIANS(360); break; // Positive but CW? Reverse direction. + case 2: angular_travel += RADIANS(360); break; // Negative but CCW? Reverse direction. + } + #ifdef MIN_ARC_SEGMENTS - uint16_t min_segments = CEIL((MIN_ARC_SEGMENTS) * (angular_travel / RADIANS(360))); + uint16_t min_segments = CEIL((MIN_ARC_SEGMENTS) * ABS(angular_travel) / RADIANS(360)); NOLESS(min_segments, 1U); #else constexpr uint16_t min_segments = 1; #endif - if (clockwise) angular_travel -= RADIANS(360); // Make a circle if the angular rotation is 0 and the target is current position if (NEAR_ZERO(angular_travel) && NEAR(current_position[p_axis], cart[p_axis]) && NEAR(current_position[q_axis], cart[q_axis])) { From 0acd751e2d99e3ba53dae69651ad25282ba6a058 Mon Sep 17 00:00:00 2001 From: Sergey1560 <53866542+Sergey1560@users.noreply.github.com> Date: Fri, 27 Nov 2020 09:00:25 +0300 Subject: [PATCH 33/47] Group related homing options (#20283) Co-authored-by: Scott Lahteine --- Marlin/Configuration.h | 4 ++-- Marlin/Configuration_adv.h | 2 -- 2 files changed, 2 insertions(+), 4 deletions(-) diff --git a/Marlin/Configuration.h b/Marlin/Configuration.h index 3320e18abc3d..0e529b3462be 100644 --- a/Marlin/Configuration.h +++ b/Marlin/Configuration.h @@ -1099,8 +1099,8 @@ // @section homing -//#define NO_MOTION_BEFORE_HOMING // Inhibit movement until all axes have been homed - +//#define NO_MOTION_BEFORE_HOMING // Inhibit movement until all axes have been homed. Also enable HOME_AFTER_DEACTIVATE for extra safety. +//#define HOME_AFTER_DEACTIVATE // Require rehoming after steppers are deactivated. Also enable NO_MOTION_BEFORE_HOMING for extra safety. //#define UNKNOWN_Z_NO_RAISE // Don't raise Z (lower the bed) if Z is "unknown." For beds that fall when Z is powered off. //#define Z_HOMING_HEIGHT 4 // (mm) Minimal Z height before homing (G28) for Z clearance above the bed, clamps, ... diff --git a/Marlin/Configuration_adv.h b/Marlin/Configuration_adv.h index e6b76a4133c1..03c9ba55eb35 100644 --- a/Marlin/Configuration_adv.h +++ b/Marlin/Configuration_adv.h @@ -854,8 +854,6 @@ // If the Nozzle or Bed falls when the Z stepper is disabled, set its resting position here. //#define Z_AFTER_DEACTIVATE Z_HOME_POS -//#define HOME_AFTER_DEACTIVATE // Require rehoming after steppers are deactivated - // Default Minimum Feedrates for printing and travel moves #define DEFAULT_MINIMUMFEEDRATE 0.0 // (mm/s) Minimum feedrate. Set with M205 S. #define DEFAULT_MINTRAVELFEEDRATE 0.0 // (mm/s) Minimum travel feedrate. Set with M205 T. From 1c7f53bbb27aae47a2529f907e8bf26f7590de7f Mon Sep 17 00:00:00 2001 From: Thomas Niccolo Reyes Date: Sat, 28 Nov 2020 05:26:19 +0800 Subject: [PATCH 34/47] Fix M73 LCD code typo (#20300) --- Marlin/src/lcd/HD44780/marlinui_HD44780.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/Marlin/src/lcd/HD44780/marlinui_HD44780.cpp b/Marlin/src/lcd/HD44780/marlinui_HD44780.cpp index 00968f4ba0e9..fabd403c6b73 100644 --- a/Marlin/src/lcd/HD44780/marlinui_HD44780.cpp +++ b/Marlin/src/lcd/HD44780/marlinui_HD44780.cpp @@ -714,7 +714,7 @@ inline uint8_t draw_elapsed_or_remaining_time(uint8_t timepos, const bool blink) const bool show_remain = TERN1(ROTATE_PROGRESS_DISPLAY, blink) && (printingIsActive() || marlin_state == MF_SD_COMPLETE); if (show_remain) { #if ENABLED(USE_M73_REMAINING_TIME) - duration_t remaining = get_remaining_time(); + duration_t remaining = ui.get_remaining_time(); #else uint8_t progress = ui.get_progress_percent(); uint32_t elapsed = print_job_timer.duration(); From d466ac12ea1452525456b0ea3f2e257f954abce2 Mon Sep 17 00:00:00 2001 From: thinkyhead Date: Sat, 28 Nov 2020 00:12:13 +0000 Subject: [PATCH 35/47] [cron] Bump distribution date (2020-11-28) --- Marlin/src/inc/Version.h | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/Marlin/src/inc/Version.h b/Marlin/src/inc/Version.h index 83345a9fd7f2..9360f4112a0d 100644 --- a/Marlin/src/inc/Version.h +++ b/Marlin/src/inc/Version.h @@ -42,7 +42,7 @@ * version was tagged. */ #ifndef STRING_DISTRIBUTION_DATE - #define STRING_DISTRIBUTION_DATE "2020-11-27" + #define STRING_DISTRIBUTION_DATE "2020-11-28" #endif /** From e7e1dcf19049448328ad9fb25bbdba9e59ade3a9 Mon Sep 17 00:00:00 2001 From: thinkyhead Date: Sun, 29 Nov 2020 00:12:56 +0000 Subject: [PATCH 36/47] [cron] Bump distribution date (2020-11-29) --- Marlin/src/inc/Version.h | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/Marlin/src/inc/Version.h b/Marlin/src/inc/Version.h index 9360f4112a0d..2ca9145bcbde 100644 --- a/Marlin/src/inc/Version.h +++ b/Marlin/src/inc/Version.h @@ -42,7 +42,7 @@ * version was tagged. */ #ifndef STRING_DISTRIBUTION_DATE - #define STRING_DISTRIBUTION_DATE "2020-11-28" + #define STRING_DISTRIBUTION_DATE "2020-11-29" #endif /** From dcb101224f3c0e2ceb12f81a91c13ce16468445d Mon Sep 17 00:00:00 2001 From: yysh12 Date: Sun, 29 Nov 2020 14:50:54 -0600 Subject: [PATCH 37/47] Arc Direction followup for circles (#20314) --- Marlin/src/gcode/motion/G2_G3.cpp | 26 ++++++++++++++------------ 1 file changed, 14 insertions(+), 12 deletions(-) diff --git a/Marlin/src/gcode/motion/G2_G3.cpp b/Marlin/src/gcode/motion/G2_G3.cpp index b920e2307336..469d726df91b 100644 --- a/Marlin/src/gcode/motion/G2_G3.cpp +++ b/Marlin/src/gcode/motion/G2_G3.cpp @@ -80,24 +80,26 @@ void plan_arc( // Angle of rotation between position and target from the circle center. float angular_travel = ATAN2(rvec.a * rt_Y - rvec.b * rt_X, rvec.a * rt_X + rvec.b * rt_Y); - // Make sure angular travel over 180 degrees goes the other way around. - switch (((angular_travel < 0) << 1) + clockwise) { - case 1: angular_travel -= RADIANS(360); break; // Positive but CW? Reverse direction. - case 2: angular_travel += RADIANS(360); break; // Negative but CCW? Reverse direction. - } - #ifdef MIN_ARC_SEGMENTS - uint16_t min_segments = CEIL((MIN_ARC_SEGMENTS) * ABS(angular_travel) / RADIANS(360)); - NOLESS(min_segments, 1U); + uint16_t min_segments = MIN_ARC_SEGMENTS; #else constexpr uint16_t min_segments = 1; #endif - // Make a circle if the angular rotation is 0 and the target is current position - if (NEAR_ZERO(angular_travel) && NEAR(current_position[p_axis], cart[p_axis]) && NEAR(current_position[q_axis], cart[q_axis])) { - angular_travel = RADIANS(360); + // Do a full circle if angular rotation is near 0 and the target is current position + if ((!angular_travel || NEAR_ZERO(angular_travel)) && NEAR(current_position[p_axis], cart[p_axis]) && NEAR(current_position[q_axis], cart[q_axis])) { + // Preserve direction for circles + angular_travel = clockwise ? -RADIANS(360) : RADIANS(360); + } + else { + // Make sure angular travel over 180 degrees goes the other way around. + switch (((angular_travel < 0) << 1) | clockwise) { + case 1: angular_travel -= RADIANS(360); break; // Positive but CW? Reverse direction. + case 2: angular_travel += RADIANS(360); break; // Negative but CCW? Reverse direction. + } #ifdef MIN_ARC_SEGMENTS - min_segments = MIN_ARC_SEGMENTS; + min_segments = CEIL(min_segments * ABS(angular_travel) / RADIANS(360)); + NOLESS(min_segments, 1U); #endif } From 39abda874391695cfa227acb4521fe88e7ac00aa Mon Sep 17 00:00:00 2001 From: "Alexander D. Kanevskiy" Date: Sun, 29 Nov 2020 22:55:18 +0200 Subject: [PATCH 38/47] SKR E3 Turbo Controller Fan (#20320) --- Marlin/src/pins/lpc1769/pins_BTT_SKR_E3_TURBO.h | 4 ++++ 1 file changed, 4 insertions(+) diff --git a/Marlin/src/pins/lpc1769/pins_BTT_SKR_E3_TURBO.h b/Marlin/src/pins/lpc1769/pins_BTT_SKR_E3_TURBO.h index 6d6d7557f57d..097a41347c22 100644 --- a/Marlin/src/pins/lpc1769/pins_BTT_SKR_E3_TURBO.h +++ b/Marlin/src/pins/lpc1769/pins_BTT_SKR_E3_TURBO.h @@ -173,6 +173,10 @@ #define FAN_PIN P2_01 #define FAN1_PIN P2_02 +#ifndef CONTROLLER_FAN_PIN + #define CONTROLLER_FAN_PIN FAN1_PIN +#endif + /** * _____ * 5V | 1 2 | GND From f2b9be6e70e1709010977f2675308d21bffe6977 Mon Sep 17 00:00:00 2001 From: Jason Smith Date: Sun, 29 Nov 2020 12:57:05 -0800 Subject: [PATCH 39/47] Fix STM32F1 'freeMemory()' warnings (#20319) --- Marlin/src/HAL/STM32F1/HAL.h | 12 ++---------- 1 file changed, 2 insertions(+), 10 deletions(-) diff --git a/Marlin/src/HAL/STM32F1/HAL.h b/Marlin/src/HAL/STM32F1/HAL.h index 06f75662cffa..226c8ca9b266 100644 --- a/Marlin/src/HAL/STM32F1/HAL.h +++ b/Marlin/src/HAL/STM32F1/HAL.h @@ -202,17 +202,9 @@ extern "C" { extern "C" char* _sbrk(int incr); -/* -static int freeMemory() { - volatile int top; - top = (int)((char*)&top - reinterpret_cast(_sbrk(0))); - return top; -} -*/ - -static int freeMemory() { +static inline int freeMemory() { volatile char top; - return &top - reinterpret_cast(_sbrk(0)); + return &top - _sbrk(0); } #if GCC_VERSION <= 50000 From df0a0c9490346f57e1b8224cb0fe7a1ad46d76bb Mon Sep 17 00:00:00 2001 From: Jason Smith Date: Sun, 29 Nov 2020 13:00:08 -0800 Subject: [PATCH 40/47] Leveling Fade Height default setting (#20316) --- Marlin/Configuration.h | 3 +++ Marlin/src/inc/Conditionals_post.h | 4 ++++ Marlin/src/module/settings.cpp | 4 ++-- 3 files changed, 9 insertions(+), 2 deletions(-) diff --git a/Marlin/Configuration.h b/Marlin/Configuration.h index 0e529b3462be..ebc3311d9eda 100644 --- a/Marlin/Configuration.h +++ b/Marlin/Configuration.h @@ -1291,6 +1291,9 @@ // at which point movement will be level to the machine's XY plane. // The height can be set with M420 Z #define ENABLE_LEVELING_FADE_HEIGHT + #if ENABLED(ENABLE_LEVELING_FADE_HEIGHT) + #define DEFAULT_LEVELING_FADE_HEIGHT 10.0 // (mm) Default fade height. + #endif // For Cartesian machines, instead of dividing moves on mesh boundaries, // split up moves into short segments like a Delta. This follows the diff --git a/Marlin/src/inc/Conditionals_post.h b/Marlin/src/inc/Conditionals_post.h index 35fd92e10b76..dfecd57749b0 100644 --- a/Marlin/src/inc/Conditionals_post.h +++ b/Marlin/src/inc/Conditionals_post.h @@ -2448,6 +2448,10 @@ #endif #endif +#ifndef DEFAULT_LEVELING_FADE_HEIGHT + #define DEFAULT_LEVELING_FADE_HEIGHT 0.0 +#endif + #if ENABLED(SEGMENT_LEVELED_MOVES) && !defined(LEVELED_SEGMENT_LENGTH) #define LEVELED_SEGMENT_LENGTH 5 #endif diff --git a/Marlin/src/module/settings.cpp b/Marlin/src/module/settings.cpp index c49c643b60e3..c6eee271a08f 100644 --- a/Marlin/src/module/settings.cpp +++ b/Marlin/src/module/settings.cpp @@ -696,7 +696,7 @@ void MarlinSettings::postprocess() { // Global Leveling // { - const float zfh = TERN(ENABLE_LEVELING_FADE_HEIGHT, planner.z_fade_height, 10.0f); + const float zfh = TERN(ENABLE_LEVELING_FADE_HEIGHT, planner.z_fade_height, (DEFAULT_LEVELING_FADE_HEIGHT)); EEPROM_WRITE(zfh); } @@ -2588,7 +2588,7 @@ void MarlinSettings::reset() { // // Global Leveling // - TERN_(ENABLE_LEVELING_FADE_HEIGHT, new_z_fade_height = 0.0); + TERN_(ENABLE_LEVELING_FADE_HEIGHT, new_z_fade_height = (DEFAULT_LEVELING_FADE_HEIGHT)); TERN_(HAS_LEVELING, reset_bed_level()); #if HAS_BED_PROBE From 0f9ac3026de3a95bfa62aaba348efba803fbc1a7 Mon Sep 17 00:00:00 2001 From: thinkyhead Date: Mon, 30 Nov 2020 00:12:42 +0000 Subject: [PATCH 41/47] [cron] Bump distribution date (2020-11-30) --- Marlin/src/inc/Version.h | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/Marlin/src/inc/Version.h b/Marlin/src/inc/Version.h index 2ca9145bcbde..dc3638439599 100644 --- a/Marlin/src/inc/Version.h +++ b/Marlin/src/inc/Version.h @@ -42,7 +42,7 @@ * version was tagged. */ #ifndef STRING_DISTRIBUTION_DATE - #define STRING_DISTRIBUTION_DATE "2020-11-29" + #define STRING_DISTRIBUTION_DATE "2020-11-30" #endif /** From 8fd8772a6fffe63d99d0b88aec7a77d283df8584 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Sun, 29 Nov 2020 19:06:40 -0600 Subject: [PATCH 42/47] Adjust axis homed / trusted methods (#20323) --- Marlin/src/gcode/calibrate/G28.cpp | 9 ++--- Marlin/src/gcode/calibrate/G34.cpp | 2 +- Marlin/src/gcode/calibrate/G34_M422.cpp | 2 +- Marlin/src/gcode/feature/pause/M600.cpp | 2 +- Marlin/src/gcode/feature/pause/M701_M702.cpp | 12 ++---- Marlin/src/lcd/HD44780/marlinui_HD44780.cpp | 18 +++------ Marlin/src/lcd/TFTGLCD/marlinui_TFTGLCD.cpp | 18 +++------ Marlin/src/lcd/dogm/status_screen_DOGM.cpp | 18 +++------ .../lcd/dogm/status_screen_lite_ST7920.cpp | 11 +++-- Marlin/src/lcd/dwin/e3v2/dwin.cpp | 3 +- Marlin/src/lcd/extui/ui_api.cpp | 12 +++--- Marlin/src/lcd/menu/menu.cpp | 3 +- Marlin/src/lcd/menu/menu_bed_corners.cpp | 2 +- Marlin/src/lcd/menu/menu_bed_leveling.cpp | 2 +- Marlin/src/lcd/menu/menu_configuration.cpp | 2 +- Marlin/src/lcd/menu/menu_ubl.cpp | 2 +- Marlin/src/lcd/tft/ui_320x240.cpp | 31 ++++++-------- Marlin/src/lcd/tft/ui_480x320.cpp | 31 ++++++-------- Marlin/src/module/motion.cpp | 35 ++++++++-------- Marlin/src/module/motion.h | 40 +++++++++++-------- Marlin/src/module/probe.cpp | 4 +- Marlin/src/module/stepper/indirection.h | 8 ++-- 22 files changed, 118 insertions(+), 149 deletions(-) diff --git a/Marlin/src/gcode/calibrate/G28.cpp b/Marlin/src/gcode/calibrate/G28.cpp index c4effe7d58b8..c17d6dcc8b94 100644 --- a/Marlin/src/gcode/calibrate/G28.cpp +++ b/Marlin/src/gcode/calibrate/G28.cpp @@ -319,15 +319,14 @@ void GcodeSuite::G28() { #endif - const float z_homing_height = - ENABLED(UNKNOWN_Z_NO_RAISE) && !TEST(axis_known_position, Z_AXIS) - ? 0 - : (parser.seenval('R') ? parser.value_linear_units() : Z_HOMING_HEIGHT); + const float z_homing_height = TERN1(UNKNOWN_Z_NO_RAISE, axis_is_trusted(Z_AXIS)) + ? (parser.seenval('R') ? parser.value_linear_units() : Z_HOMING_HEIGHT) + : 0; if (z_homing_height && (doX || doY || TERN0(Z_SAFE_HOMING, doZ))) { // Raise Z before homing any other axes and z is not already high enough (never lower z) if (DEBUGGING(LEVELING)) DEBUG_ECHOLNPAIR("Raise Z (before homing) by ", z_homing_height); - do_z_clearance(z_homing_height, true, DISABLED(UNKNOWN_Z_NO_RAISE)); + do_z_clearance(z_homing_height, axis_is_trusted(Z_AXIS), DISABLED(UNKNOWN_Z_NO_RAISE)); } #if ENABLED(QUICK_HOME) diff --git a/Marlin/src/gcode/calibrate/G34.cpp b/Marlin/src/gcode/calibrate/G34.cpp index 315b2d7333dd..85e843c2c8f1 100644 --- a/Marlin/src/gcode/calibrate/G34.cpp +++ b/Marlin/src/gcode/calibrate/G34.cpp @@ -39,7 +39,7 @@ void GcodeSuite::G34() { // Home before the alignment procedure - if (!all_axes_known()) home_all_axes(); + if (!all_axes_trusted()) home_all_axes(); SET_SOFT_ENDSTOP_LOOSE(true); TEMPORARY_BED_LEVELING_STATE(false); diff --git a/Marlin/src/gcode/calibrate/G34_M422.cpp b/Marlin/src/gcode/calibrate/G34_M422.cpp index 8d3dd0d06b23..840d04f29e98 100644 --- a/Marlin/src/gcode/calibrate/G34_M422.cpp +++ b/Marlin/src/gcode/calibrate/G34_M422.cpp @@ -167,7 +167,7 @@ void GcodeSuite::G34() { ); // Home before the alignment procedure - if (!all_axes_known()) home_all_axes(); + if (!all_axes_trusted()) home_all_axes(); // Move the Z coordinate realm towards the positive - dirty trick current_position.z += z_probe * 0.5f; diff --git a/Marlin/src/gcode/feature/pause/M600.cpp b/Marlin/src/gcode/feature/pause/M600.cpp index e676ed38a4a0..bdaec7c7f9b5 100644 --- a/Marlin/src/gcode/feature/pause/M600.cpp +++ b/Marlin/src/gcode/feature/pause/M600.cpp @@ -102,7 +102,7 @@ void GcodeSuite::M600() { #if ENABLED(HOME_BEFORE_FILAMENT_CHANGE) // If needed, home before parking for filament change - if (!all_axes_known()) home_all_axes(); + if (!all_axes_trusted()) home_all_axes(); #endif #if HAS_MULTI_EXTRUDER diff --git a/Marlin/src/gcode/feature/pause/M701_M702.cpp b/Marlin/src/gcode/feature/pause/M701_M702.cpp index a100d462da7e..a889da8aeaa7 100644 --- a/Marlin/src/gcode/feature/pause/M701_M702.cpp +++ b/Marlin/src/gcode/feature/pause/M701_M702.cpp @@ -59,10 +59,8 @@ void GcodeSuite::M701() { xyz_pos_t park_point = NOZZLE_PARK_POINT; - #if ENABLED(NO_MOTION_BEFORE_HOMING) - // Don't raise Z if the machine isn't homed - if (axes_should_home()) park_point.z = 0; - #endif + // Don't raise Z if the machine isn't homed + if (TERN0(NO_MOTION_BEFORE_HOMING, axes_should_home())) park_point.z = 0; #if ENABLED(MIXING_EXTRUDER) const int8_t target_e_stepper = get_target_e_stepper_from_command(); @@ -147,10 +145,8 @@ void GcodeSuite::M701() { void GcodeSuite::M702() { xyz_pos_t park_point = NOZZLE_PARK_POINT; - #if ENABLED(NO_MOTION_BEFORE_HOMING) - // Don't raise Z if the machine isn't homed - if (axes_should_home()) park_point.z = 0; - #endif + // Don't raise Z if the machine isn't homed + if (TERN0(NO_MOTION_BEFORE_HOMING, axes_should_home())) park_point.z = 0; #if ENABLED(MIXING_EXTRUDER) const uint8_t old_mixing_tool = mixer.get_current_vtool(); diff --git a/Marlin/src/lcd/HD44780/marlinui_HD44780.cpp b/Marlin/src/lcd/HD44780/marlinui_HD44780.cpp index fabd403c6b73..84c477fbde5d 100644 --- a/Marlin/src/lcd/HD44780/marlinui_HD44780.cpp +++ b/Marlin/src/lcd/HD44780/marlinui_HD44780.cpp @@ -506,18 +506,12 @@ FORCE_INLINE void _draw_axis_value(const AxisEnum axis, const char *value, const lcd_put_wchar('X' + uint8_t(axis)); if (blink) lcd_put_u8str(value); - else { - if (!TEST(axis_homed, axis)) - while (const char c = *value++) lcd_put_wchar(c <= '.' ? c : '?'); - else { - #if NONE(HOME_AFTER_DEACTIVATE, DISABLE_REDUCED_ACCURACY_WARNING) - if (!TEST(axis_known_position, axis)) - lcd_put_u8str_P(axis == Z_AXIS ? PSTR(" ") : PSTR(" ")); - else - #endif - lcd_put_u8str(value); - } - } + else if (axis_should_home(axis)) + while (const char c = *value++) lcd_put_wchar(c <= '.' ? c : '?'); + else if (NONE(HOME_AFTER_DEACTIVATE, DISABLE_REDUCED_ACCURACY_WARNING) && !axis_is_trusted(axis)) + lcd_put_u8str_P(axis == Z_AXIS ? PSTR(" ") : PSTR(" ")); + else + lcd_put_u8str(value); } FORCE_INLINE void _draw_heater_status(const heater_id_t heater_id, const char prefix, const bool blink) { diff --git a/Marlin/src/lcd/TFTGLCD/marlinui_TFTGLCD.cpp b/Marlin/src/lcd/TFTGLCD/marlinui_TFTGLCD.cpp index 74be828c727e..cadd693f6f9e 100644 --- a/Marlin/src/lcd/TFTGLCD/marlinui_TFTGLCD.cpp +++ b/Marlin/src/lcd/TFTGLCD/marlinui_TFTGLCD.cpp @@ -422,18 +422,12 @@ FORCE_INLINE void _draw_axis_value(const AxisEnum axis, const char *value, const lcd.write('X' + uint8_t(axis)); if (blink) lcd.print(value); - else { - if (!TEST(axis_homed, axis)) - while (const char c = *value++) lcd.write(c <= '.' ? c : '?'); - else { - #if NONE(HOME_AFTER_DEACTIVATE, DISABLE_REDUCED_ACCURACY_WARNING) - if (!TEST(axis_known_position, axis)) - lcd_put_u8str_P(axis == Z_AXIS ? PSTR(" ") : PSTR(" ")); - else - #endif - lcd_put_u8str(value); - } - } + else if (axis_should_home(axis)) + while (const char c = *value++) lcd.write(c <= '.' ? c : '?'); + else if (NONE(HOME_AFTER_DEACTIVATE, DISABLE_REDUCED_ACCURACY_WARNING) && !axis_is_trusted(axis)) + lcd_put_u8str_P(axis == Z_AXIS ? PSTR(" ") : PSTR(" ")); + else + lcd_put_u8str(value); } FORCE_INLINE void _draw_heater_status(const heater_id_t heater_id, const char *prefix, const bool blink) { diff --git a/Marlin/src/lcd/dogm/status_screen_DOGM.cpp b/Marlin/src/lcd/dogm/status_screen_DOGM.cpp index 882b2fef506a..29acb869413f 100644 --- a/Marlin/src/lcd/dogm/status_screen_DOGM.cpp +++ b/Marlin/src/lcd/dogm/status_screen_DOGM.cpp @@ -384,18 +384,12 @@ FORCE_INLINE void _draw_axis_value(const AxisEnum axis, const char *value, const if (blink) lcd_put_u8str(value); - else { - if (!TEST(axis_homed, axis)) - while (const char c = *value++) lcd_put_wchar(c <= '.' ? c : '?'); - else { - #if NONE(HOME_AFTER_DEACTIVATE, DISABLE_REDUCED_ACCURACY_WARNING) - if (!TEST(axis_known_position, axis)) - lcd_put_u8str_P(axis == Z_AXIS ? PSTR(" ") : PSTR(" ")); - else - #endif - lcd_put_u8str(value); - } - } + else if (axis_should_home(axis)) + while (const char c = *value++) lcd_put_wchar(c <= '.' ? c : '?'); + else if (NONE(HOME_AFTER_DEACTIVATE, DISABLE_REDUCED_ACCURACY_WARNING) && !axis_is_trusted(axis)) + lcd_put_u8str_P(axis == Z_AXIS ? PSTR(" ") : PSTR(" ")); + else + lcd_put_u8str(value); } /** diff --git a/Marlin/src/lcd/dogm/status_screen_lite_ST7920.cpp b/Marlin/src/lcd/dogm/status_screen_lite_ST7920.cpp index c06080f601bb..a538121d2cf6 100644 --- a/Marlin/src/lcd/dogm/status_screen_lite_ST7920.cpp +++ b/Marlin/src/lcd/dogm/status_screen_lite_ST7920.cpp @@ -659,13 +659,13 @@ void ST7920_Lite_Status_Screen::draw_status_message() { #endif } -void ST7920_Lite_Status_Screen::draw_position(const xyze_pos_t &pos, const bool position_known) { +void ST7920_Lite_Status_Screen::draw_position(const xyze_pos_t &pos, const bool position_trusted) { char str[7]; set_ddram_address(DDRAM_LINE_4); begin_data(); // If position is unknown, flash the labels. - const unsigned char alt_label = position_known ? 0 : (ui.get_blink() ? ' ' : 0); + const unsigned char alt_label = position_trusted ? 0 : (ui.get_blink() ? ' ' : 0); if (TERN1(LCD_SHOW_E_TOTAL, !printingIsActive())) { write_byte(alt_label ? alt_label : 'X'); @@ -831,9 +831,8 @@ void ST7920_Lite_Status_Screen::update_status_or_position(bool forceUpdate) { } } - if (countdown == 0 && (forceUpdate || position_changed() - || TERN(DISABLE_REDUCED_ACCURACY_WARNING, 0, blink_changed()) - )) draw_position(current_position, TERN(DISABLE_REDUCED_ACCURACY_WARNING, 1, all_axes_known())); + if (countdown == 0 && (forceUpdate || position_changed() || TERN(DISABLE_REDUCED_ACCURACY_WARNING, 0, blink_changed()))) + draw_position(current_position, TERN(DISABLE_REDUCED_ACCURACY_WARNING, 1, all_axes_trusted())); #endif } @@ -855,7 +854,7 @@ void ST7920_Lite_Status_Screen::update_progress(const bool forceUpdate) { UNUSED(forceUpdate); - #endif // LCD_SET_PROGRESS_MANUALLY || SDSUPPORT + #endif } void ST7920_Lite_Status_Screen::update(const bool forceUpdate) { diff --git a/Marlin/src/lcd/dwin/e3v2/dwin.cpp b/Marlin/src/lcd/dwin/e3v2/dwin.cpp index fe2397fa6b42..e9e6ef69e510 100644 --- a/Marlin/src/lcd/dwin/e3v2/dwin.cpp +++ b/Marlin/src/lcd/dwin/e3v2/dwin.cpp @@ -1281,8 +1281,7 @@ void HMI_Move_Z() { last_zoffset = dwin_zoffset; dwin_zoffset = HMI_ValueStruct.offset_value / 100.0f; #if EITHER(BABYSTEP_ZPROBE_OFFSET, JUST_BABYSTEP) - if ( (ENABLED(BABYSTEP_WITHOUT_HOMING) || all_axes_known()) && (ENABLED(BABYSTEP_ALWAYS_AVAILABLE) || printer_busy()) ) - babystep.add_mm(Z_AXIS, dwin_zoffset - last_zoffset); + if (BABYSTEP_ALLOWED()) babystep.add_mm(Z_AXIS, dwin_zoffset - last_zoffset); #endif DWIN_Draw_Signed_Float(font8x16, Select_Color, 2, 2, 202, MBASE(zoff_line), HMI_ValueStruct.offset_value); DWIN_UpdateLCD(); diff --git a/Marlin/src/lcd/extui/ui_api.cpp b/Marlin/src/lcd/extui/ui_api.cpp index 1583db41e90b..1877914bfb5d 100644 --- a/Marlin/src/lcd/extui/ui_api.cpp +++ b/Marlin/src/lcd/extui/ui_api.cpp @@ -356,9 +356,9 @@ namespace ExtUI { bool canMove(const axis_t axis) { switch (axis) { #if IS_KINEMATIC || ENABLED(NO_MOTION_BEFORE_HOMING) - case X: return TEST(axis_homed, X_AXIS); - case Y: return TEST(axis_homed, Y_AXIS); - case Z: return TEST(axis_homed, Z_AXIS); + case X: return axis_should_home(X_AXIS); + case Y: return axis_should_home(Y_AXIS); + case Z: return axis_should_home(Z_AXIS); #else case X: case Y: case Z: return true; #endif @@ -889,9 +889,9 @@ namespace ExtUI { bool commandsInQueue() { return (planner.movesplanned() || queue.has_commands_queued()); } - bool isAxisPositionKnown(const axis_t axis) { return TEST(axis_known_position, axis); } - bool isAxisPositionKnown(const extruder_t) { return TEST(axis_known_position, E_AXIS); } - bool isPositionKnown() { return all_axes_known(); } + bool isAxisPositionKnown(const axis_t axis) { return axis_is_trusted((AxisEnum)axis); } + bool isAxisPositionKnown(const extruder_t) { return axis_is_trusted(E_AXIS); } + bool isPositionKnown() { return all_axes_trusted(); } bool isMachineHomed() { return all_axes_homed(); } PGM_P getFirmwareName_str() { diff --git a/Marlin/src/lcd/menu/menu.cpp b/Marlin/src/lcd/menu/menu.cpp index 1497940ffe55..add306b6e322 100644 --- a/Marlin/src/lcd/menu/menu.cpp +++ b/Marlin/src/lcd/menu/menu.cpp @@ -188,8 +188,7 @@ void MarlinUI::goto_screen(screenFunc_t screen, const uint16_t encoder/*=0*/, co doubleclick_expire_ms = millis() + DOUBLECLICK_MAX_INTERVAL; } else if (screen == status_screen && currentScreen == menu_main && PENDING(millis(), doubleclick_expire_ms)) { - if ( (ENABLED(BABYSTEP_WITHOUT_HOMING) || all_axes_known()) - && (ENABLED(BABYSTEP_ALWAYS_AVAILABLE) || printer_busy()) ) + if (BABYSTEP_ALLOWED()) screen = TERN(BABYSTEP_ZPROBE_OFFSET, lcd_babystep_zoffset, lcd_babystep_z); else { #if ENABLED(MOVE_Z_WHEN_IDLE) diff --git a/Marlin/src/lcd/menu/menu_bed_corners.cpp b/Marlin/src/lcd/menu/menu_bed_corners.cpp index 52d2d0ec3db6..ad91c404aa7a 100644 --- a/Marlin/src/lcd/menu/menu_bed_corners.cpp +++ b/Marlin/src/lcd/menu/menu_bed_corners.cpp @@ -230,7 +230,7 @@ static inline void _lcd_level_bed_corners_homing() { void _lcd_level_bed_corners() { ui.defer_status_screen(); - if (!all_axes_known()) { + if (!all_axes_trusted()) { set_all_unhomed(); queue.inject_P(G28_STR); } diff --git a/Marlin/src/lcd/menu/menu_bed_leveling.cpp b/Marlin/src/lcd/menu/menu_bed_leveling.cpp index d089b2125ac7..64dca3b04fd2 100644 --- a/Marlin/src/lcd/menu/menu_bed_leveling.cpp +++ b/Marlin/src/lcd/menu/menu_bed_leveling.cpp @@ -237,7 +237,7 @@ * Save Settings (Req: EEPROM_SETTINGS) */ void menu_bed_leveling() { - const bool is_homed = all_axes_known(), + const bool is_homed = all_axes_trusted(), is_valid = leveling_is_valid(); START_MENU(); diff --git a/Marlin/src/lcd/menu/menu_configuration.cpp b/Marlin/src/lcd/menu/menu_configuration.cpp index 2c3af1e5ee2d..7b95f435baa0 100644 --- a/Marlin/src/lcd/menu/menu_configuration.cpp +++ b/Marlin/src/lcd/menu/menu_configuration.cpp @@ -164,7 +164,7 @@ void menu_advanced_settings(); void menu_tool_offsets() { auto _recalc_offsets = []{ - if (active_extruder && all_axes_known()) { // For the 2nd extruder re-home so the next tool-change gets the new offsets. + if (active_extruder && all_axes_trusted()) { // For the 2nd extruder re-home so the next tool-change gets the new offsets. queue.inject_P(G28_STR); // In future, we can babystep the 2nd extruder (if active), making homing unnecessary. active_extruder = 0; } diff --git a/Marlin/src/lcd/menu/menu_ubl.cpp b/Marlin/src/lcd/menu/menu_ubl.cpp index 5dce47eec294..eb19e96626c0 100644 --- a/Marlin/src/lcd/menu/menu_ubl.cpp +++ b/Marlin/src/lcd/menu/menu_ubl.cpp @@ -524,7 +524,7 @@ void _ubl_map_screen_homing() { */ void _ubl_goto_map_screen() { if (planner.movesplanned()) return; // The ACTION_ITEM will do nothing - if (!all_axes_known()) { + if (!all_axes_trusted()) { set_all_unhomed(); queue.inject_P(G28_STR); } diff --git a/Marlin/src/lcd/tft/ui_320x240.cpp b/Marlin/src/lcd/tft/ui_320x240.cpp index 45a91cd5e5c2..51f65c59b563 100644 --- a/Marlin/src/lcd/tft/ui_320x240.cpp +++ b/Marlin/src/lcd/tft/ui_320x240.cpp @@ -257,42 +257,37 @@ void MarlinUI::draw_status_screen() { tft.set_background(COLOR_BACKGROUND); tft.add_rectangle(0, 0, 312, 24, COLOR_AXIS_HOMED); - uint16_t color; - uint16_t offset; - bool is_homed; - tft.add_text( 10, 3, COLOR_AXIS_HOMED , "X"); tft.add_text(127, 3, COLOR_AXIS_HOMED , "Y"); tft.add_text(219, 3, COLOR_AXIS_HOMED , "Z"); - is_homed = TEST(axis_homed, X_AXIS); - tft_string.set(blink & !is_homed ? "?" : ftostr4sign(LOGICAL_X_POSITION(current_position.x))); - tft.add_text( 68 - tft_string.width(), 3, is_homed ? COLOR_AXIS_HOMED : COLOR_AXIS_NOT_HOMED, tft_string); + bool not_homed = axis_should_home(X_AXIS); + tft_string.set(blink && not_homed ? "?" : ftostr4sign(LOGICAL_X_POSITION(current_position.x))); + tft.add_text( 68 - tft_string.width(), 3, not_homed ? COLOR_AXIS_NOT_HOMED : COLOR_AXIS_HOMED, tft_string); - is_homed = TEST(axis_homed, Y_AXIS); - tft_string.set(blink & !is_homed ? "?" : ftostr4sign(LOGICAL_Y_POSITION(current_position.y))); - tft.add_text(185 - tft_string.width(), 3, is_homed ? COLOR_AXIS_HOMED : COLOR_AXIS_NOT_HOMED, tft_string); + not_homed = axis_should_home(Y_AXIS); + tft_string.set(blink && not_homed ? "?" : ftostr4sign(LOGICAL_Y_POSITION(current_position.y))); + tft.add_text(185 - tft_string.width(), 3, not_homed ? COLOR_AXIS_NOT_HOMED : COLOR_AXIS_HOMED, tft_string); - is_homed = TEST(axis_homed, Z_AXIS); - if (blink & !is_homed) { + not_homed = axis_should_home(Z_AXIS); + uint16_t offset = 25; + if (blink && not_homed) tft_string.set("?"); - offset = 25; // ".00" - } else { const float z = LOGICAL_Z_POSITION(current_position.z); tft_string.set(ftostr52sp((int16_t)z)); tft_string.rtrim(); - offset = tft_string.width(); + offset += tft_string.width(); tft_string.set(ftostr52sp(z)); - offset += 25 - tft_string.width(); + offset -= tft_string.width(); } - tft.add_text(301 - tft_string.width() - offset, 3, is_homed ? COLOR_AXIS_HOMED : COLOR_AXIS_NOT_HOMED, tft_string); + tft.add_text(301 - tft_string.width() - offset, 3, not_homed ? COLOR_AXIS_NOT_HOMED : COLOR_AXIS_HOMED, tft_string); // feed rate tft.canvas(70, 136, 80, 32); tft.set_background(COLOR_BACKGROUND); - color = feedrate_percentage == 100 ? COLOR_RATE_100 : COLOR_RATE_ALTERED; + uint16_t color = feedrate_percentage == 100 ? COLOR_RATE_100 : COLOR_RATE_ALTERED; tft.add_image(0, 0, imgFeedRate, color); tft_string.set(i16tostr3rj(feedrate_percentage)); tft_string.add('%'); diff --git a/Marlin/src/lcd/tft/ui_480x320.cpp b/Marlin/src/lcd/tft/ui_480x320.cpp index d152acdf7726..343d187d26ba 100644 --- a/Marlin/src/lcd/tft/ui_480x320.cpp +++ b/Marlin/src/lcd/tft/ui_480x320.cpp @@ -262,43 +262,38 @@ void MarlinUI::draw_status_screen() { tft.set_background(COLOR_BACKGROUND); tft.add_rectangle(0, 0, TFT_WIDTH - 8, 34, COLOR_AXIS_HOMED); - uint16_t color; - uint16_t offset; - bool is_homed; - tft.add_text( 16, 3, COLOR_AXIS_HOMED , "X"); tft.add_text(192, 3, COLOR_AXIS_HOMED , "Y"); tft.add_text(330, 3, COLOR_AXIS_HOMED , "Z"); - is_homed = TEST(axis_homed, X_AXIS); - tft_string.set(blink & !is_homed ? "?" : ftostr4sign(LOGICAL_X_POSITION(current_position.x))); - tft.add_text(102 - tft_string.width(), 3, is_homed ? COLOR_AXIS_HOMED : COLOR_AXIS_NOT_HOMED, tft_string); + bool not_homed = axis_should_home(X_AXIS); + tft_string.set(blink && not_homed ? "?" : ftostr4sign(LOGICAL_X_POSITION(current_position.x))); + tft.add_text(102 - tft_string.width(), 3, not_homed ? COLOR_AXIS_NOT_HOMED : COLOR_AXIS_HOMED, tft_string); - is_homed = TEST(axis_homed, Y_AXIS); - tft_string.set(blink & !is_homed ? "?" : ftostr4sign(LOGICAL_Y_POSITION(current_position.y))); - tft.add_text(280 - tft_string.width(), 3, is_homed ? COLOR_AXIS_HOMED : COLOR_AXIS_NOT_HOMED, tft_string); + not_homed = axis_should_home(Y_AXIS); + tft_string.set(blink && not_homed ? "?" : ftostr4sign(LOGICAL_Y_POSITION(current_position.y))); + tft.add_text(280 - tft_string.width(), 3, not_homed ? COLOR_AXIS_NOT_HOMED : COLOR_AXIS_HOMED, tft_string); - is_homed = TEST(axis_homed, Z_AXIS); - if (blink & !is_homed) { + uint16_t offset = 32; + not_homed = axis_should_home(Z_AXIS); + if (blink && not_homed) tft_string.set("?"); - offset = 32; // ".00" - } else { const float z = LOGICAL_Z_POSITION(current_position.z); tft_string.set(ftostr52sp((int16_t)z)); tft_string.rtrim(); - offset = tft_string.width(); + offset += tft_string.width(); tft_string.set(ftostr52sp(z)); - offset += 32 - tft_string.width(); + offset -= tft_string.width(); } - tft.add_text(455 - tft_string.width() - offset, 3, is_homed ? COLOR_AXIS_HOMED : COLOR_AXIS_NOT_HOMED, tft_string); + tft.add_text(455 - tft_string.width() - offset, 3, not_homed ? COLOR_AXIS_NOT_HOMED : COLOR_AXIS_HOMED, tft_string); TERN_(TOUCH_SCREEN, touch.add_control(MOVE_AXIS, 4, 132, TFT_WIDTH - 8, 34)); // feed rate tft.canvas(96, 180, 100, 32); tft.set_background(COLOR_BACKGROUND); - color = feedrate_percentage == 100 ? COLOR_RATE_100 : COLOR_RATE_ALTERED; + uint16_t color = feedrate_percentage == 100 ? COLOR_RATE_100 : COLOR_RATE_ALTERED; tft.add_image(0, 0, imgFeedRate, color); tft_string.set(i16tostr3rj(feedrate_percentage)); tft_string.add('%'); diff --git a/Marlin/src/module/motion.cpp b/Marlin/src/module/motion.cpp index 03c8ddc46296..3a01cda5c120 100644 --- a/Marlin/src/module/motion.cpp +++ b/Marlin/src/module/motion.cpp @@ -79,11 +79,11 @@ * Flags that each linear axis was homed. * XYZ on cartesian, ABC on delta, ABZ on SCARA. * - * axis_known_position - * Flags that the position is known in each linear axis. Set when homed. + * axis_trusted + * Flags that the position is trusted in each linear axis. Set when homed. * Cleared whenever a stepper powers off, potentially losing its position. */ -uint8_t axis_homed, axis_known_position; // = 0 +uint8_t axis_homed, axis_trusted; // = 0 // Relative Mode. Enable with G91, disable with G90. bool relative_mode; // = false; @@ -506,8 +506,8 @@ void do_blocking_move_to_xy_z(const xy_pos_t &raw, const float &z, const feedRat do_blocking_move_to(raw.x, raw.y, z, fr_mm_s); } -void do_z_clearance(const float &zclear, const bool z_known/*=true*/, const bool raise_on_unknown/*=true*/, const bool lower_allowed/*=false*/) { - const bool rel = raise_on_unknown && !z_known; +void do_z_clearance(const float &zclear, const bool z_trusted/*=true*/, const bool raise_on_untrusted/*=true*/, const bool lower_allowed/*=false*/) { + const bool rel = raise_on_untrusted && !z_trusted; float zdest = zclear + (rel ? current_position.z : 0.0f); if (!lower_allowed) NOLESS(zdest, current_position.z); do_blocking_move_to_z(_MIN(zdest, Z_MAX_POS), MMM_TO_MMS(TERN(HAS_BED_PROBE, Z_PROBE_SPEED_FAST, HOMING_FEEDRATE_Z))); @@ -649,7 +649,7 @@ void restore_feedrate_and_scaling() { constexpr xy_pos_t offs{0}; #endif - if (TERN1(IS_SCARA, TEST(axis_homed, X_AXIS) && TEST(axis_homed, Y_AXIS))) { + if (TERN1(IS_SCARA, axis_was_homed(X_AXIS) && axis_was_homed(Y_AXIS))) { const float dist_2 = HYPOT2(target.x - offs.x, target.y - offs.y); if (dist_2 > delta_max_radius_2) target *= float(delta_max_radius / SQRT(dist_2)); // 200 / 300 = 0.66 @@ -657,7 +657,7 @@ void restore_feedrate_and_scaling() { #else - if (TEST(axis_homed, X_AXIS)) { + if (axis_was_homed(X_AXIS)) { #if !HAS_SOFTWARE_ENDSTOPS || ENABLED(MIN_SOFTWARE_ENDSTOP_X) NOLESS(target.x, soft_endstop.min.x); #endif @@ -666,7 +666,7 @@ void restore_feedrate_and_scaling() { #endif } - if (TEST(axis_homed, Y_AXIS)) { + if (axis_was_homed(Y_AXIS)) { #if !HAS_SOFTWARE_ENDSTOPS || ENABLED(MIN_SOFTWARE_ENDSTOP_Y) NOLESS(target.y, soft_endstop.min.y); #endif @@ -677,7 +677,7 @@ void restore_feedrate_and_scaling() { #endif - if (TEST(axis_homed, Z_AXIS)) { + if (axis_was_homed(Z_AXIS)) { #if !HAS_SOFTWARE_ENDSTOPS || ENABLED(MIN_SOFTWARE_ENDSTOP_Z) NOLESS(target.z, soft_endstop.min.z); #endif @@ -1124,10 +1124,11 @@ void prepare_line_to_destination() { } uint8_t axes_should_home(uint8_t axis_bits/*=0x07*/) { + #define SHOULD_HOME(A) TERN(HOME_AFTER_DEACTIVATE, axis_is_trusted, axis_was_homed)(A) // Clear test bits that are trusted - if (TEST(axis_bits, X_AXIS) && TEST(axis_homed, X_AXIS)) CBI(axis_bits, X_AXIS); - if (TEST(axis_bits, Y_AXIS) && TEST(axis_homed, Y_AXIS)) CBI(axis_bits, Y_AXIS); - if (TEST(axis_bits, Z_AXIS) && TEST(axis_homed, Z_AXIS)) CBI(axis_bits, Z_AXIS); + if (TEST(axis_bits, X_AXIS) && SHOULD_HOME(X_AXIS)) CBI(axis_bits, X_AXIS); + if (TEST(axis_bits, Y_AXIS) && SHOULD_HOME(Y_AXIS)) CBI(axis_bits, Y_AXIS); + if (TEST(axis_bits, Z_AXIS) && SHOULD_HOME(Z_AXIS)) CBI(axis_bits, Z_AXIS); return axis_bits; } @@ -1388,7 +1389,7 @@ void do_homing_move(const AxisEnum axis, const float distance, const feedRate_t * * DELTA should wait until all homing is done before setting the XYZ * current_position to home, because homing is a single operation. - * In the case where the axis positions are already known and previously + * In the case where the axis positions are trusted and previously * homed, DELTA could home to X or Y individually by moving either one * to the center. However, homing Z always homes XY and Z. * @@ -1401,8 +1402,8 @@ void do_homing_move(const AxisEnum axis, const float distance, const feedRate_t void set_axis_is_at_home(const AxisEnum axis) { if (DEBUGGING(LEVELING)) DEBUG_ECHOLNPAIR(">>> set_axis_is_at_home(", axis_codes[axis], ")"); - SBI(axis_known_position, axis); - SBI(axis_homed, axis); + set_axis_trusted(axis); + set_axis_homed(axis); #if ENABLED(DUAL_X_CARRIAGE) if (axis == X_AXIS && (active_extruder == 1 || dual_x_carriage_mode == DXC_DUPLICATION_MODE)) { @@ -1462,8 +1463,8 @@ void set_axis_is_at_home(const AxisEnum axis) { void set_axis_never_homed(const AxisEnum axis) { if (DEBUGGING(LEVELING)) DEBUG_ECHOLNPAIR(">>> set_axis_never_homed(", axis_codes[axis], ")"); - CBI(axis_known_position, axis); - CBI(axis_homed, axis); + set_axis_untrusted(axis); + set_axis_unhomed(axis); if (DEBUGGING(LEVELING)) DEBUG_ECHOLNPAIR("<<< set_axis_never_homed(", axis_codes[axis], ")"); diff --git a/Marlin/src/module/motion.h b/Marlin/src/module/motion.h index abc59f92b886..efbfd7de4dda 100644 --- a/Marlin/src/module/motion.h +++ b/Marlin/src/module/motion.h @@ -34,19 +34,6 @@ #include "scara.h" #endif -// Axis homed and known-position states -extern uint8_t axis_homed, axis_known_position; -constexpr uint8_t xyz_bits = _BV(X_AXIS) | _BV(Y_AXIS) | _BV(Z_AXIS); -FORCE_INLINE bool no_axes_homed() { return !axis_homed; } -FORCE_INLINE bool all_axes_homed() { return (axis_homed & xyz_bits) == xyz_bits; } -FORCE_INLINE bool all_axes_known() { return (axis_known_position & xyz_bits) == xyz_bits; } -FORCE_INLINE void set_all_homed() { axis_homed = axis_known_position = xyz_bits; } -FORCE_INLINE void set_all_unhomed() { axis_homed = axis_known_position = 0; } - -FORCE_INLINE bool homing_needed() { - return !TERN(HOME_AFTER_DEACTIVATE, all_axes_known, all_axes_homed)(); -} - // Error margin to work around float imprecision constexpr float fslop = 0.0001; @@ -269,23 +256,42 @@ void remember_feedrate_and_scaling(); void remember_feedrate_scaling_off(); void restore_feedrate_and_scaling(); -void do_z_clearance(const float &zclear, const bool z_known=true, const bool raise_on_unknown=true, const bool lower_allowed=false); +void do_z_clearance(const float &zclear, const bool z_trusted=true, const bool raise_on_untrusted=true, const bool lower_allowed=false); + +/** + * Homing and Trusted Axes + */ +constexpr uint8_t xyz_bits = _BV(X_AXIS) | _BV(Y_AXIS) | _BV(Z_AXIS); +extern uint8_t axis_homed, axis_trusted; -// -// Homing -// void homeaxis(const AxisEnum axis); void set_axis_is_at_home(const AxisEnum axis); void set_axis_never_homed(const AxisEnum axis); uint8_t axes_should_home(uint8_t axis_bits=0x07); bool homing_needed_error(uint8_t axis_bits=0x07); +FORCE_INLINE bool axis_was_homed(const AxisEnum axis) { return TEST(axis_homed, axis); } +FORCE_INLINE bool axis_is_trusted(const AxisEnum axis) { return TEST(axis_trusted, axis); } +FORCE_INLINE bool axis_should_home(const AxisEnum axis) { return (axes_should_home() & _BV(axis)) != 0; } +FORCE_INLINE bool no_axes_homed() { return !axis_homed; } +FORCE_INLINE bool all_axes_homed() { return xyz_bits == (axis_homed & xyz_bits); } +FORCE_INLINE bool homing_needed() { return !all_axes_homed(); } +FORCE_INLINE bool all_axes_trusted() { return xyz_bits == (axis_trusted & xyz_bits); } +FORCE_INLINE void set_axis_homed(const AxisEnum axis) { SBI(axis_homed, axis); } +FORCE_INLINE void set_axis_unhomed(const AxisEnum axis) { CBI(axis_homed, axis); } +FORCE_INLINE void set_axis_trusted(const AxisEnum axis) { SBI(axis_trusted, axis); } +FORCE_INLINE void set_axis_untrusted(const AxisEnum axis) { CBI(axis_trusted, axis); } +FORCE_INLINE void set_all_homed() { axis_homed = axis_trusted = xyz_bits; } +FORCE_INLINE void set_all_unhomed() { axis_homed = axis_trusted = 0; } + #if ENABLED(NO_MOTION_BEFORE_HOMING) #define MOTION_CONDITIONS (IsRunning() && !homing_needed_error()) #else #define MOTION_CONDITIONS IsRunning() #endif +#define BABYSTEP_ALLOWED() ((ENABLED(BABYSTEP_WITHOUT_HOMING) || all_axes_trusted()) && (ENABLED(BABYSTEP_ALWAYS_AVAILABLE) || printer_busy())) + /** * Workspace offsets */ diff --git a/Marlin/src/module/probe.cpp b/Marlin/src/module/probe.cpp index 11447d71297e..400206f83ae1 100644 --- a/Marlin/src/module/probe.cpp +++ b/Marlin/src/module/probe.cpp @@ -350,7 +350,7 @@ bool Probe::set_deployed(const bool deploy) { // For beds that fall when Z is powered off only raise for trusted Z #if ENABLED(UNKNOWN_Z_NO_RAISE) - const bool unknown_condition = TEST(axis_known_position, Z_AXIS); + const bool unknown_condition = axis_is_trusted(Z_AXIS); #else constexpr float unknown_condition = true; #endif @@ -510,7 +510,7 @@ float Probe::run_z_probe(const bool sanity_check/*=true*/) { // Stop the probe before it goes too low to prevent damage. // If Z isn't known then probe to -10mm. - const float z_probe_low_point = TEST(axis_known_position, Z_AXIS) ? -offset.z + Z_PROBE_LOW_POINT : -10.0; + const float z_probe_low_point = axis_is_trusted(Z_AXIS) ? -offset.z + Z_PROBE_LOW_POINT : -10.0; // Double-probing does a fast probe followed by a slow probe #if TOTAL_PROBING == 2 diff --git a/Marlin/src/module/stepper/indirection.h b/Marlin/src/module/stepper/indirection.h index d14bfc7329c8..4346e9d6cccf 100644 --- a/Marlin/src/module/stepper/indirection.h +++ b/Marlin/src/module/stepper/indirection.h @@ -856,13 +856,11 @@ void reset_stepper_drivers(); // Called by settings.load / settings.reset #endif #define ENABLE_AXIS_X() if (SHOULD_ENABLE(x)) { ENABLE_STEPPER_X(); ENABLE_STEPPER_X2(); AFTER_CHANGE(x, true); } -#define DISABLE_AXIS_X() if (SHOULD_DISABLE(x)) { DISABLE_STEPPER_X(); DISABLE_STEPPER_X2(); AFTER_CHANGE(x, false); FORGET_AXIS(X_AXIS); } +#define DISABLE_AXIS_X() if (SHOULD_DISABLE(x)) { DISABLE_STEPPER_X(); DISABLE_STEPPER_X2(); AFTER_CHANGE(x, false); set_axis_untrusted(X_AXIS); } #define ENABLE_AXIS_Y() if (SHOULD_ENABLE(y)) { ENABLE_STEPPER_Y(); ENABLE_STEPPER_Y2(); AFTER_CHANGE(y, true); } -#define DISABLE_AXIS_Y() if (SHOULD_DISABLE(y)) { DISABLE_STEPPER_Y(); DISABLE_STEPPER_Y2(); AFTER_CHANGE(y, false); FORGET_AXIS(Y_AXIS); } +#define DISABLE_AXIS_Y() if (SHOULD_DISABLE(y)) { DISABLE_STEPPER_Y(); DISABLE_STEPPER_Y2(); AFTER_CHANGE(y, false); set_axis_untrusted(Y_AXIS); } #define ENABLE_AXIS_Z() if (SHOULD_ENABLE(z)) { ENABLE_STEPPER_Z(); ENABLE_STEPPER_Z2(); ENABLE_STEPPER_Z3(); ENABLE_STEPPER_Z4(); AFTER_CHANGE(z, true); } -#define DISABLE_AXIS_Z() if (SHOULD_DISABLE(z)) { DISABLE_STEPPER_Z(); DISABLE_STEPPER_Z2(); DISABLE_STEPPER_Z3(); DISABLE_STEPPER_Z4(); AFTER_CHANGE(z, false); FORGET_AXIS(Z_AXIS); Z_RESET(); } - -#define FORGET_AXIS(A) TERN(HOME_AFTER_DEACTIVATE, set_axis_never_homed(A), CBI(axis_known_position, A)) +#define DISABLE_AXIS_Z() if (SHOULD_DISABLE(z)) { DISABLE_STEPPER_Z(); DISABLE_STEPPER_Z2(); DISABLE_STEPPER_Z3(); DISABLE_STEPPER_Z4(); AFTER_CHANGE(z, false); set_axis_untrusted(Z_AXIS); Z_RESET(); } #ifdef Z_AFTER_DEACTIVATE #define Z_RESET() do{ current_position.z = Z_AFTER_DEACTIVATE; sync_plan_position(); }while(0) From fd35d1b8a6e08a72255a0b2cf9ddc1cf577fe12b Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Sun, 29 Nov 2020 20:49:42 -0600 Subject: [PATCH 43/47] General cleanup --- Marlin/src/feature/bedlevel/abl/abl.cpp | 2 +- Marlin/src/feature/power_monitor.cpp | 4 ++-- Marlin/src/feature/power_monitor.h | 4 ++-- Marlin/src/gcode/feature/controllerfan/M710.cpp | 4 ++-- Marlin/src/gcode/feature/power_monitor/M430.cpp | 4 ++-- Marlin/src/lcd/menu/menu_power_monitor.cpp | 4 ++-- Marlin/src/pins/ramps/pins_RAMPS_S_12.h | 2 +- Marlin/src/pins/stm32f1/pins_FLSUN_HISPEED.h | 4 ++-- 8 files changed, 14 insertions(+), 14 deletions(-) diff --git a/Marlin/src/feature/bedlevel/abl/abl.cpp b/Marlin/src/feature/bedlevel/abl/abl.cpp index 44e4fc38a1bd..3fb0cfc3583e 100644 --- a/Marlin/src/feature/bedlevel/abl/abl.cpp +++ b/Marlin/src/feature/bedlevel/abl/abl.cpp @@ -168,7 +168,7 @@ void print_bilinear_leveling_grid() { // cancelled out in bed_level_virt_cmr and does not impact the result. Return 0.0 rather than // making this function more complex by extrapolating two points. return 0.0; - } + } if (!x || x == ABL_TEMP_POINTS_X - 1) { if (x) { ep = GRID_MAX_POINTS_X - 1; diff --git a/Marlin/src/feature/power_monitor.cpp b/Marlin/src/feature/power_monitor.cpp index e1e7324fb6c6..97c4a933637e 100644 --- a/Marlin/src/feature/power_monitor.cpp +++ b/Marlin/src/feature/power_monitor.cpp @@ -1,9 +1,9 @@ /** * Marlin 3D Printer Firmware - * Copyright (C) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] + * 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) 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 diff --git a/Marlin/src/feature/power_monitor.h b/Marlin/src/feature/power_monitor.h index a0eaf353f4c7..f378ee2a107c 100644 --- a/Marlin/src/feature/power_monitor.h +++ b/Marlin/src/feature/power_monitor.h @@ -1,9 +1,9 @@ /** * Marlin 3D Printer Firmware - * Copyright (C) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] + * 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) 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 diff --git a/Marlin/src/gcode/feature/controllerfan/M710.cpp b/Marlin/src/gcode/feature/controllerfan/M710.cpp index 67d4ad8abf54..cc450732baed 100644 --- a/Marlin/src/gcode/feature/controllerfan/M710.cpp +++ b/Marlin/src/gcode/feature/controllerfan/M710.cpp @@ -1,9 +1,9 @@ /** * Marlin 3D Printer Firmware - * Copyright (C) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] + * 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) 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 diff --git a/Marlin/src/gcode/feature/power_monitor/M430.cpp b/Marlin/src/gcode/feature/power_monitor/M430.cpp index 7639ea962d9b..9559404456f5 100644 --- a/Marlin/src/gcode/feature/power_monitor/M430.cpp +++ b/Marlin/src/gcode/feature/power_monitor/M430.cpp @@ -1,9 +1,9 @@ /** * Marlin 3D Printer Firmware - * Copyright (C) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] + * 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) 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 diff --git a/Marlin/src/lcd/menu/menu_power_monitor.cpp b/Marlin/src/lcd/menu/menu_power_monitor.cpp index e88bdb28d8c8..d31ebd36b27f 100644 --- a/Marlin/src/lcd/menu/menu_power_monitor.cpp +++ b/Marlin/src/lcd/menu/menu_power_monitor.cpp @@ -1,9 +1,9 @@ /** * Marlin 3D Printer Firmware - * Copyright (C) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] + * 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) 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 diff --git a/Marlin/src/pins/ramps/pins_RAMPS_S_12.h b/Marlin/src/pins/ramps/pins_RAMPS_S_12.h index 42b665ce8659..1bcf310bc17c 100644 --- a/Marlin/src/pins/ramps/pins_RAMPS_S_12.h +++ b/Marlin/src/pins/ramps/pins_RAMPS_S_12.h @@ -263,7 +263,7 @@ #ifndef SD_DETECT_PIN #define SD_DETECT_PIN 38 #endif - + #if ENABLED(REPRAP_DISCOUNT_FULL_GRAPHIC_SMART_CONTROLLER) #define BTN_ENC_EN LCD_PINS_D7 // Detect the presence of the encoder #endif diff --git a/Marlin/src/pins/stm32f1/pins_FLSUN_HISPEED.h b/Marlin/src/pins/stm32f1/pins_FLSUN_HISPEED.h index 05b8b19a8a54..7541f8272941 100644 --- a/Marlin/src/pins/stm32f1/pins_FLSUN_HISPEED.h +++ b/Marlin/src/pins/stm32f1/pins_FLSUN_HISPEED.h @@ -243,7 +243,7 @@ #endif // Use the on-board card socket labeled SD_Extender -#if SD_CONNECTION_IS(CUSTOM_CABLE) +#if SD_CONNECTION_IS(CUSTOM_CABLE) #define SCK_PIN PC12 #define MISO_PIN PC8 #define MOSI_PIN PD2 @@ -300,7 +300,7 @@ #define FSMC_DMA_CHANNEL DMA_CH5 #define TFT_BUFFER_SIZE 14400 - #if ENABLED(TFT_CLASSIC_UI) + #if ENABLED(TFT_CLASSIC_UI) #define TFT_MARLINBG_COLOR 0x3186 // White #define TFT_MARLINUI_COLOR 0xC7B6 // green #define TFT_BTARROWS_COLOR 0xDEE6 // Yellow From 87ede6fa1b2ffb81d921264958b665f17b7326ab Mon Sep 17 00:00:00 2001 From: Jason Smith Date: Mon, 30 Nov 2020 04:44:34 -0800 Subject: [PATCH 44/47] Increase E3V2 DWIN steps/mm range to 999.9 (#20324) --- Marlin/src/lcd/dwin/e3v2/dwin.cpp | 3 +-- 1 file changed, 1 insertion(+), 2 deletions(-) diff --git a/Marlin/src/lcd/dwin/e3v2/dwin.cpp b/Marlin/src/lcd/dwin/e3v2/dwin.cpp index e9e6ef69e510..7e2259e17fd5 100644 --- a/Marlin/src/lcd/dwin/e3v2/dwin.cpp +++ b/Marlin/src/lcd/dwin/e3v2/dwin.cpp @@ -186,7 +186,6 @@ bool dwin_abort_flag = false; // Flag to reset feedrate, return to Home constexpr float default_max_feedrate[] = DEFAULT_MAX_FEEDRATE; constexpr float default_max_acceleration[] = DEFAULT_MAX_ACCELERATION; constexpr float default_max_jerk[] = { DEFAULT_XJERK, DEFAULT_YJERK, DEFAULT_ZJERK, DEFAULT_EJERK }; -constexpr float default_axis_steps_per_unit[] = DEFAULT_AXIS_STEPS_PER_UNIT; uint8_t Percentrecord = 0; uint16_t remain_time = 0; @@ -1522,7 +1521,7 @@ void HMI_StepXYZE() { } // Step limit if (WITHIN(HMI_flag.step_axis, X_AXIS, E_AXIS)) - NOMORE(HMI_ValueStruct.Max_Step, default_axis_steps_per_unit[HMI_flag.step_axis] * 2 * MINUNITMULT); + NOMORE(HMI_ValueStruct.Max_Step, 999.9 * MINUNITMULT); NOLESS(HMI_ValueStruct.Max_Step, MIN_STEP); // Step value DWIN_Draw_FloatValue(true, true, 0, font8x16, Color_White, Select_Color, 3, 1, 210, MBASE(select_step.now), HMI_ValueStruct.Max_Step); From db8fb9a03a1a8e13e55f82b537468883065a251a Mon Sep 17 00:00:00 2001 From: thinkyhead Date: Tue, 1 Dec 2020 00:13:08 +0000 Subject: [PATCH 45/47] [cron] Bump distribution date (2020-12-01) --- Marlin/src/inc/Version.h | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/Marlin/src/inc/Version.h b/Marlin/src/inc/Version.h index dc3638439599..e20e4525bd4a 100644 --- a/Marlin/src/inc/Version.h +++ b/Marlin/src/inc/Version.h @@ -42,7 +42,7 @@ * version was tagged. */ #ifndef STRING_DISTRIBUTION_DATE - #define STRING_DISTRIBUTION_DATE "2020-11-30" + #define STRING_DISTRIBUTION_DATE "2020-12-01" #endif /** From 6f4381df53235b4f97815d07ce560d704ad550ab Mon Sep 17 00:00:00 2001 From: Jason Smith Date: Mon, 30 Nov 2020 22:25:44 -0800 Subject: [PATCH 46/47] Prevent Watchdog reset writing Creality 4.x EEPROM (#20328) --- Marlin/src/HAL/STM32F1/eeprom_bl24cxx.cpp | 7 ++++++- 1 file changed, 6 insertions(+), 1 deletion(-) diff --git a/Marlin/src/HAL/STM32F1/eeprom_bl24cxx.cpp b/Marlin/src/HAL/STM32F1/eeprom_bl24cxx.cpp index 94b5e099bd58..09fe8f910370 100644 --- a/Marlin/src/HAL/STM32F1/eeprom_bl24cxx.cpp +++ b/Marlin/src/HAL/STM32F1/eeprom_bl24cxx.cpp @@ -48,6 +48,8 @@ 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) { + size_t written = 0; + while (size--) { uint8_t v = *value; uint8_t * const p = (uint8_t * const)pos; @@ -55,7 +57,10 @@ bool PersistentStore::write_data(int &pos, const uint8_t *value, size_t size, ui // so only write bytes that have changed! if (v != eeprom_read_byte(p)) { eeprom_write_byte(p, v); - delay(2); + if (++written % 128 == 0) + safe_delay(2); // Avoid triggering watchdog during long EEPROM writes + else + delay(2); if (eeprom_read_byte(p) != v) { SERIAL_ECHO_MSG(STR_ERR_EEPROM_WRITE); return true; From 0d080cea83b2666c105613678de212d7c828cbb1 Mon Sep 17 00:00:00 2001 From: Jason Smith Date: Tue, 1 Dec 2020 00:29:21 -0800 Subject: [PATCH 47/47] Fix E3V2 Control Menu when returning from Info (#20338) --- Marlin/src/lcd/dwin/e3v2/dwin.cpp | 12 ++++++------ 1 file changed, 6 insertions(+), 6 deletions(-) diff --git a/Marlin/src/lcd/dwin/e3v2/dwin.cpp b/Marlin/src/lcd/dwin/e3v2/dwin.cpp index 7e2259e17fd5..a96b1dcb73f4 100644 --- a/Marlin/src/lcd/dwin/e3v2/dwin.cpp +++ b/Marlin/src/lcd/dwin/e3v2/dwin.cpp @@ -726,14 +726,14 @@ inline void Draw_Control_Menu() { else { #ifdef USE_STRING_HEADINGS Draw_Title(GET_TEXT_F(MSG_CONTROL)); - DWIN_Draw_String(false, true, font8x16, Color_White, Color_Bg_Black, LBLX, MBASE(CONTROL_CASE_TEMP), GET_TEXT_F(MSG_TEMPERATURE)); - DWIN_Draw_String(false, true, font8x16, Color_White, Color_Bg_Black, LBLX, MBASE(CONTROL_CASE_MOVE), GET_TEXT_F(MSG_MOTION)); + DWIN_Draw_String(false, true, font8x16, Color_White, Color_Bg_Black, LBLX, CLINE(CONTROL_CASE_TEMP), GET_TEXT_F(MSG_TEMPERATURE)); + DWIN_Draw_String(false, true, font8x16, Color_White, Color_Bg_Black, LBLX, CLINE(CONTROL_CASE_MOVE), GET_TEXT_F(MSG_MOTION)); #if ENABLED(EEPROM_SETTINGS) - DWIN_Draw_String(false, true, font8x16, Color_White, Color_Bg_Black, LBLX, MBASE(CONTROL_CASE_SAVE), GET_TEXT_F(MSG_STORE_EEPROM)); - DWIN_Draw_String(false, true, font8x16, Color_White, Color_Bg_Black, LBLX, MBASE(CONTROL_CASE_LOAD), GET_TEXT_F(MSG_LOAD_EEPROM)); - DWIN_Draw_String(false, true, font8x16, Color_White, Color_Bg_Black, LBLX, MBASE(CONTROL_CASE_RESET), GET_TEXT_F(MSG_RESTORE_DEFAULTS)); + DWIN_Draw_String(false, true, font8x16, Color_White, Color_Bg_Black, LBLX, CLINE(CONTROL_CASE_SAVE), GET_TEXT_F(MSG_STORE_EEPROM)); + DWIN_Draw_String(false, true, font8x16, Color_White, Color_Bg_Black, LBLX, CLINE(CONTROL_CASE_LOAD), GET_TEXT_F(MSG_LOAD_EEPROM)); + DWIN_Draw_String(false, true, font8x16, Color_White, Color_Bg_Black, LBLX, CLINE(CONTROL_CASE_RESET), GET_TEXT_F(MSG_RESTORE_DEFAULTS)); #endif - if (CVISI(CONTROL_CASE_INFO)) DWIN_Draw_String(false, true, font8x16, Color_White, Color_Bg_Black, LBLX, MBASE(CONTROL_CASE_INFO), F("Info")); + if (CVISI(CONTROL_CASE_INFO)) DWIN_Draw_String(false, true, font8x16, Color_White, Color_Bg_Black, LBLX, CLINE(CONTROL_CASE_INFO), F("Info")); #else DWIN_Frame_TitleCopy(1, 128, 2, 176, 12); // "Control" DWIN_Frame_AreaCopy(1, 1, 89, 83, 101, LBLX, CLINE(CONTROL_CASE_TEMP)); // Temperature >