Browse Source

Move some MarlinCore and MarlinUI code (#20832)

vanilla_fb_2.0.x
Scott Lahteine 4 years ago
committed by GitHub
parent
commit
c0870d417a
No known key found for this signature in database GPG Key ID: 4AEE18F83AFDEB23
  1. 118
      Marlin/src/MarlinCore.cpp
  2. 13
      Marlin/src/MarlinCore.h
  3. 1
      Marlin/src/feature/e_parser.h
  4. 2
      Marlin/src/feature/encoder_i2c.cpp
  5. 47
      Marlin/src/feature/pause.cpp
  6. 6
      Marlin/src/feature/pause.h
  7. 3
      Marlin/src/feature/runout.cpp
  8. 8
      Marlin/src/feature/runout.h
  9. 10
      Marlin/src/feature/twibus.cpp
  10. 13
      Marlin/src/feature/twibus.h
  11. 3
      Marlin/src/gcode/control/M108_M112_M410.cpp
  12. 2
      Marlin/src/gcode/control/M226.cpp
  13. 4
      Marlin/src/gcode/control/M42.cpp
  14. 2
      Marlin/src/gcode/feature/i2c/M260_M261.cpp
  15. 9
      Marlin/src/gcode/feature/pause/M125.cpp
  16. 9
      Marlin/src/gcode/feature/pause/M600.cpp
  17. 13
      Marlin/src/gcode/feature/pause/M701_M702.cpp
  18. 32
      Marlin/src/gcode/gcode.cpp
  19. 2
      Marlin/src/gcode/gcode.h
  20. 1
      Marlin/src/gcode/queue.cpp
  21. 2
      Marlin/src/gcode/sd/M1001.cpp
  22. 2
      Marlin/src/lcd/dogm/marlinui_DOGM.cpp
  23. 1
      Marlin/src/lcd/dwin/e3v2/rotary_encoder.h
  24. 4
      Marlin/src/lcd/extui/lib/anycubic_i3mega/anycubic_i3mega_lcd.cpp
  25. 5
      Marlin/src/lcd/extui/lib/dgus/DGUSDisplay.h
  26. 2
      Marlin/src/lcd/extui/lib/mks_ui/tft_multi_language.cpp
  27. 4
      Marlin/src/lcd/extui/lib/mks_ui/wifi_module.cpp
  28. 2
      Marlin/src/lcd/marlinui.cpp
  29. 25
      Marlin/src/lcd/marlinui.h
  30. 2
      Marlin/src/lcd/menu/menu_configuration.cpp
  31. 2
      Marlin/src/lcd/menu/menu_delta_calibrate.cpp
  32. 4
      Marlin/src/lcd/menu/menu_filament.cpp
  33. 2
      Marlin/src/lcd/menu/menu_motion.cpp
  34. 1
      Marlin/src/module/endstops.cpp
  35. 13
      Marlin/src/module/motion.cpp
  36. 2
      Marlin/src/module/motion.h
  37. 2
      Marlin/src/module/probe.cpp
  38. 11
      Marlin/src/module/temperature.cpp

118
Marlin/src/MarlinCore.cpp

@ -43,6 +43,7 @@
#include <math.h> #include <math.h>
#include "core/utility.h" #include "core/utility.h"
#include "module/motion.h" #include "module/motion.h"
#include "module/planner.h" #include "module/planner.h"
#include "module/endstops.h" #include "module/endstops.h"
@ -57,6 +58,7 @@
#include "gcode/parser.h" #include "gcode/parser.h"
#include "gcode/queue.h" #include "gcode/queue.h"
#include "feature/pause.h"
#include "sd/cardreader.h" #include "sd/cardreader.h"
#include "lcd/marlinui.h" #include "lcd/marlinui.h"
@ -139,7 +141,6 @@
#if ENABLED(EXPERIMENTAL_I2CBUS) #if ENABLED(EXPERIMENTAL_I2CBUS)
#include "feature/twibus.h" #include "feature/twibus.h"
TWIBus i2c;
#endif #endif
#if ENABLED(I2C_POSITION_ENCODERS) #if ENABLED(I2C_POSITION_ENCODERS)
@ -173,10 +174,6 @@
#include "feature/bedlevel/bedlevel.h" #include "feature/bedlevel/bedlevel.h"
#endif #endif
#if BOTH(ADVANCED_PAUSE_FEATURE, PAUSE_PARK_NO_STEPPER_TIMEOUT)
#include "feature/pause.h"
#endif
#if ENABLED(GCODE_REPEAT_MARKERS) #if ENABLED(GCODE_REPEAT_MARKERS)
#include "feature/repeat.h" #include "feature/repeat.h"
#endif #endif
@ -267,40 +264,12 @@ bool wait_for_heatup = true;
#endif #endif
#if PIN_EXISTS(CHDK)
extern millis_t chdk_timeout;
#endif
#if ENABLED(I2C_POSITION_ENCODERS)
I2CPositionEncodersMgr I2CPEM;
#endif
/** /**
* *************************************************************************** * ***************************************************************************
* ******************************** FUNCTIONS ******************************** * ******************************** FUNCTIONS ********************************
* *************************************************************************** * ***************************************************************************
*/ */
void setup_killpin() {
#if HAS_KILL
#if KILL_PIN_STATE
SET_INPUT_PULLDOWN(KILL_PIN);
#else
SET_INPUT_PULLUP(KILL_PIN);
#endif
#endif
}
void setup_powerhold() {
#if HAS_SUICIDE
OUT_WRITE(SUICIDE_PIN, !SUICIDE_PIN_INVERTING);
#endif
#if ENABLED(PSU_CONTROL)
powersupply_on = ENABLED(PSU_DEFAULT_OFF);
if (ENABLED(PSU_DEFAULT_OFF)) PSU_OFF(); else PSU_ON();
#endif
}
/** /**
* Stepper Reset (RigidBoard, et.al.) * Stepper Reset (RigidBoard, et.al.)
*/ */
@ -309,18 +278,6 @@ void setup_powerhold() {
void enableStepperDrivers() { SET_INPUT(STEPPER_RESET_PIN); } // Set to input, allowing pullups to pull the pin high void enableStepperDrivers() { SET_INPUT(STEPPER_RESET_PIN); } // Set to input, allowing pullups to pull the pin high
#endif #endif
#if ENABLED(EXPERIMENTAL_I2CBUS) && I2C_SLAVE_ADDRESS > 0
void i2c_on_receive(int bytes) { // just echo all bytes received to serial
i2c.receive(bytes);
}
void i2c_on_request() { // just send dummy data for now
i2c.reply("Hello World!\n");
}
#endif
/** /**
* Sensitive pin test for M42, M226 * Sensitive pin test for M42, M226
*/ */
@ -342,17 +299,6 @@ bool pin_is_protected(const pin_t pin) {
#pragma GCC diagnostic pop #pragma GCC diagnostic pop
void protected_pin_err() {
SERIAL_ERROR_MSG(STR_ERR_PROTECTED_PIN);
}
void quickstop_stepper() {
planner.quick_stop();
planner.synchronize();
set_current_from_steppers_for_axis(ALL_AXES);
sync_plan_position();
}
void enable_e_steppers() { void enable_e_steppers() {
#define _ENA_E(N) ENABLE_AXIS_E##N(); #define _ENA_E(N) ENABLE_AXIS_E##N();
REPEAT(E_STEPPERS, _ENA_E) REPEAT(E_STEPPERS, _ENA_E)
@ -389,41 +335,6 @@ void disable_all_steppers() {
TERN_(EXTENSIBLE_UI, ExtUI::onSteppersDisabled()); TERN_(EXTENSIBLE_UI, ExtUI::onSteppersDisabled());
} }
#if ENABLED(G29_RETRY_AND_RECOVER)
void event_probe_failure() {
#ifdef ACTION_ON_G29_FAILURE
host_action(PSTR(ACTION_ON_G29_FAILURE));
#endif
#ifdef G29_FAILURE_COMMANDS
gcode.process_subcommands_now_P(PSTR(G29_FAILURE_COMMANDS));
#endif
#if ENABLED(G29_HALT_ON_FAILURE)
#ifdef ACTION_ON_CANCEL
host_action_cancel();
#endif
kill(GET_TEXT(MSG_LCD_PROBING_FAILED));
#endif
}
void event_probe_recover() {
TERN_(HOST_PROMPT_SUPPORT, host_prompt_do(PROMPT_INFO, PSTR("G29 Retrying"), DISMISS_STR));
#ifdef ACTION_ON_G29_RECOVER
host_action(PSTR(ACTION_ON_G29_RECOVER));
#endif
#ifdef G29_RECOVER_COMMANDS
gcode.process_subcommands_now_P(PSTR(G29_RECOVER_COMMANDS));
#endif
}
#endif
#if ENABLED(ADVANCED_PAUSE_FEATURE)
#include "feature/pause.h"
#else
constexpr bool did_pause_print = false;
#endif
/** /**
* A Print Job exists when the timer is running or SD printing * A Print Job exists when the timer is running or SD printing
*/ */
@ -511,8 +422,8 @@ inline void manage_inactivity(const bool ignore_stepper_queue=false) {
// Prevent steppers timing-out in the middle of M600 // Prevent steppers timing-out in the middle of M600
// unless PAUSE_PARK_NO_STEPPER_TIMEOUT is disabled // unless PAUSE_PARK_NO_STEPPER_TIMEOUT is disabled
const bool parked_or_ignoring = ignore_stepper_queue || const bool parked_or_ignoring = ignore_stepper_queue
(BOTH(ADVANCED_PAUSE_FEATURE, PAUSE_PARK_NO_STEPPER_TIMEOUT) && did_pause_print); || TERN0(PAUSE_PARK_NO_STEPPER_TIMEOUT, did_pause_print);
// Reset both the M18/M84 activity timeout and the M85 max 'kill' timeout // Reset both the M18/M84 activity timeout and the M85 max 'kill' timeout
if (parked_or_ignoring) gcode.reset_stepper_timeout(ms); if (parked_or_ignoring) gcode.reset_stepper_timeout(ms);
@ -550,6 +461,7 @@ inline void manage_inactivity(const bool ignore_stepper_queue=false) {
} }
#if PIN_EXISTS(CHDK) // Check if pin should be set to LOW (after M240 set it HIGH) #if PIN_EXISTS(CHDK) // Check if pin should be set to LOW (after M240 set it HIGH)
extern millis_t chdk_timeout;
if (chdk_timeout && ELAPSED(ms, chdk_timeout)) { if (chdk_timeout && ELAPSED(ms, chdk_timeout)) {
chdk_timeout = 0; chdk_timeout = 0;
WRITE(CHDK_PIN, LOW); WRITE(CHDK_PIN, LOW);
@ -1038,13 +950,29 @@ void setup() {
SETUP_RUN(recovery.setup()); SETUP_RUN(recovery.setup());
#endif #endif
SETUP_RUN(setup_killpin()); #if HAS_KILL
SETUP_LOG("KILL_PIN");
#if KILL_PIN_STATE
SET_INPUT_PULLDOWN(KILL_PIN);
#else
SET_INPUT_PULLUP(KILL_PIN);
#endif
#endif
#if HAS_TMC220x #if HAS_TMC220x
SETUP_RUN(tmc_serial_begin()); SETUP_RUN(tmc_serial_begin());
#endif #endif
SETUP_RUN(setup_powerhold()); #if HAS_SUICIDE
SETUP_LOG("SUICIDE_PIN")
OUT_WRITE(SUICIDE_PIN, !SUICIDE_PIN_INVERTING);
#endif
#if ENABLED(PSU_CONTROL)
SETUP_LOG("PSU_CONTROL");
powersupply_on = ENABLED(PSU_DEFAULT_OFF);
if (ENABLED(PSU_DEFAULT_OFF)) PSU_OFF(); else PSU_ON();
#endif
#if HAS_STEPPER_RESET #if HAS_STEPPER_RESET
SETUP_RUN(disableStepperDrivers()); SETUP_RUN(disableStepperDrivers());

13
Marlin/src/MarlinCore.h

@ -37,11 +37,6 @@ void stop();
void idle(TERN_(ADVANCED_PAUSE_FEATURE, bool no_stepper_sleep=false)); void idle(TERN_(ADVANCED_PAUSE_FEATURE, bool no_stepper_sleep=false));
inline void idle_no_sleep() { idle(TERN_(ADVANCED_PAUSE_FEATURE, true)); } inline void idle_no_sleep() { idle(TERN_(ADVANCED_PAUSE_FEATURE, true)); }
#if ENABLED(EXPERIMENTAL_I2CBUS)
#include "feature/twibus.h"
extern TWIBus i2c;
#endif
#if ENABLED(G38_PROBE_TARGET) #if ENABLED(G38_PROBE_TARGET)
extern uint8_t G38_move; // Flag to tell the ISR that G38 is in progress, and the type extern uint8_t G38_move; // Flag to tell the ISR that G38 is in progress, and the type
extern bool G38_did_trigger; // Flag from the ISR to indicate the endstop changed extern bool G38_did_trigger; // Flag from the ISR to indicate the endstop changed
@ -59,8 +54,6 @@ void disable_all_steppers();
void kill(PGM_P const lcd_error=nullptr, PGM_P const lcd_component=nullptr, const bool steppers_off=false); void kill(PGM_P const lcd_error=nullptr, PGM_P const lcd_component=nullptr, const bool steppers_off=false);
void minkill(const bool steppers_off=false); void minkill(const bool steppers_off=false);
void quickstop_stepper();
// Global State of the firmware // Global State of the firmware
enum MarlinState : uint8_t { enum MarlinState : uint8_t {
MF_INITIALIZING = 0, MF_INITIALIZING = 0,
@ -103,7 +96,6 @@ extern bool wait_for_heatup;
#endif #endif
bool pin_is_protected(const pin_t pin); bool pin_is_protected(const pin_t pin);
void protected_pin_err();
#if HAS_SUICIDE #if HAS_SUICIDE
inline void suicide() { OUT_WRITE(SUICIDE_PIN, SUICIDE_PIN_INVERTING); } inline void suicide() { OUT_WRITE(SUICIDE_PIN, SUICIDE_PIN_INVERTING); }
@ -116,11 +108,6 @@ void protected_pin_err();
inline bool kill_state() { return READ(KILL_PIN) == KILL_PIN_STATE; } inline bool kill_state() { return READ(KILL_PIN) == KILL_PIN_STATE; }
#endif #endif
#if ENABLED(G29_RETRY_AND_RECOVER)
void event_probe_recover();
void event_probe_failure();
#endif
extern const char NUL_STR[], M112_KILL_STR[], G28_STR[], M21_STR[], M23_STR[], M24_STR[], extern const char NUL_STR[], M112_KILL_STR[], G28_STR[], M21_STR[], M23_STR[], M24_STR[],
SP_A_STR[], SP_B_STR[], SP_C_STR[], SP_A_STR[], SP_B_STR[], SP_C_STR[],
SP_P_STR[], SP_T_STR[], SP_X_STR[], SP_Y_STR[], SP_Z_STR[], SP_E_STR[], SP_P_STR[], SP_T_STR[], SP_X_STR[], SP_Y_STR[], SP_Z_STR[], SP_E_STR[],

1
Marlin/src/feature/e_parser.h

@ -33,7 +33,6 @@
// External references // External references
extern bool wait_for_user, wait_for_heatup; extern bool wait_for_user, wait_for_heatup;
void quickstop_stepper();
class EmergencyParser { class EmergencyParser {

2
Marlin/src/feature/encoder_i2c.cpp

@ -41,6 +41,8 @@
#include <Wire.h> #include <Wire.h>
I2CPositionEncodersMgr I2CPEM;
void I2CPositionEncoder::init(const uint8_t address, const AxisEnum axis) { void I2CPositionEncoder::init(const uint8_t address, const AxisEnum axis) {
encoderAxis = axis; encoderAxis = axis;
i2cAddress = address; i2cAddress = address;

47
Marlin/src/feature/pause.cpp

@ -137,10 +137,7 @@ static bool ensure_safe_temperature(const bool wait=true, const PauseMode mode=P
thermalManager.setTargetHotend(thermalManager.extrude_min_temp, active_extruder); thermalManager.setTargetHotend(thermalManager.extrude_min_temp, active_extruder);
#endif #endif
#if HAS_LCD_MENU ui.pause_show_message(PAUSE_MESSAGE_HEATING, mode); UNUSED(mode);
lcd_pause_show_message(PAUSE_MESSAGE_HEATING, mode);
#endif
UNUSED(mode);
if (wait) return thermalManager.wait_for_hotend(active_extruder); if (wait) return thermalManager.wait_for_hotend(active_extruder);
@ -181,19 +178,13 @@ bool load_filament(const float &slow_load_length/*=0*/, const float &fast_load_l
DEBUG_SECTION(lf, "load_filament", true); DEBUG_SECTION(lf, "load_filament", true);
DEBUG_ECHOLNPAIR("... slowlen:", slow_load_length, " fastlen:", fast_load_length, " purgelen:", purge_length, " maxbeep:", int(max_beep_count), " showlcd:", int(show_lcd), " pauseforuser:", int(pause_for_user), " pausemode:", int(mode) DXC_SAY); DEBUG_ECHOLNPAIR("... slowlen:", slow_load_length, " fastlen:", fast_load_length, " purgelen:", purge_length, " maxbeep:", int(max_beep_count), " showlcd:", int(show_lcd), " pauseforuser:", int(pause_for_user), " pausemode:", int(mode) DXC_SAY);
UNUSED(show_lcd);
if (!ensure_safe_temperature(false, mode)) { if (!ensure_safe_temperature(false, mode)) {
#if HAS_LCD_MENU if (show_lcd) ui.pause_show_message(PAUSE_MESSAGE_STATUS, mode);
if (show_lcd) lcd_pause_show_message(PAUSE_MESSAGE_STATUS, mode);
#endif
return false; return false;
} }
if (pause_for_user) { if (pause_for_user) {
#if HAS_LCD_MENU if (show_lcd) ui.pause_show_message(PAUSE_MESSAGE_INSERT, mode);
if (show_lcd) lcd_pause_show_message(PAUSE_MESSAGE_INSERT, mode);
#endif
SERIAL_ECHO_MSG(_PMSG(STR_FILAMENT_CHANGE_INSERT)); SERIAL_ECHO_MSG(_PMSG(STR_FILAMENT_CHANGE_INSERT));
first_impatient_beep(max_beep_count); first_impatient_beep(max_beep_count);
@ -217,9 +208,7 @@ bool load_filament(const float &slow_load_length/*=0*/, const float &fast_load_l
} }
} }
#if HAS_LCD_MENU if (show_lcd) ui.pause_show_message(PAUSE_MESSAGE_LOAD, mode);
if (show_lcd) lcd_pause_show_message(PAUSE_MESSAGE_LOAD, mode);
#endif
#if ENABLED(DUAL_X_CARRIAGE) #if ENABLED(DUAL_X_CARRIAGE)
const int8_t saved_ext = active_extruder; const int8_t saved_ext = active_extruder;
@ -250,9 +239,7 @@ bool load_filament(const float &slow_load_length/*=0*/, const float &fast_load_l
#if ENABLED(ADVANCED_PAUSE_CONTINUOUS_PURGE) #if ENABLED(ADVANCED_PAUSE_CONTINUOUS_PURGE)
#if HAS_LCD_MENU if (show_lcd) ui.pause_show_message(PAUSE_MESSAGE_PURGE);
if (show_lcd) lcd_pause_show_message(PAUSE_MESSAGE_PURGE);
#endif
TERN_(HOST_PROMPT_SUPPORT, host_prompt_do(PROMPT_USER_CONTINUE, PSTR("Filament Purging..."), CONTINUE_STR)); TERN_(HOST_PROMPT_SUPPORT, host_prompt_do(PROMPT_USER_CONTINUE, PSTR("Filament Purging..."), CONTINUE_STR));
TERN_(EXTENSIBLE_UI, ExtUI::onUserConfirmRequired_P(PSTR("Filament Purging..."))); TERN_(EXTENSIBLE_UI, ExtUI::onUserConfirmRequired_P(PSTR("Filament Purging...")));
@ -266,9 +253,7 @@ bool load_filament(const float &slow_load_length/*=0*/, const float &fast_load_l
do { do {
if (purge_length > 0) { if (purge_length > 0) {
// "Wait for filament purge" // "Wait for filament purge"
#if HAS_LCD_MENU if (show_lcd) ui.pause_show_message(PAUSE_MESSAGE_PURGE);
if (show_lcd) lcd_pause_show_message(PAUSE_MESSAGE_PURGE);
#endif
// Extrude filament to get into hotend // Extrude filament to get into hotend
unscaled_e_move(purge_length, ADVANCED_PAUSE_PURGE_FEEDRATE); unscaled_e_move(purge_length, ADVANCED_PAUSE_PURGE_FEEDRATE);
@ -281,7 +266,7 @@ bool load_filament(const float &slow_load_length/*=0*/, const float &fast_load_l
// Show "Purge More" / "Resume" menu and wait for reply // Show "Purge More" / "Resume" menu and wait for reply
KEEPALIVE_STATE(PAUSED_FOR_USER); KEEPALIVE_STATE(PAUSED_FOR_USER);
wait_for_user = false; wait_for_user = false;
lcd_pause_show_message(PAUSE_MESSAGE_OPTION); ui.pause_show_message(PAUSE_MESSAGE_OPTION);
while (pause_menu_response == PAUSE_RESPONSE_WAIT_FOR) idle_no_sleep(); while (pause_menu_response == PAUSE_RESPONSE_WAIT_FOR) idle_no_sleep();
} }
#endif #endif
@ -330,22 +315,16 @@ bool unload_filament(const float &unload_length, const bool show_lcd/*=false*/,
#endif #endif
); );
UNUSED(show_lcd);
#if !BOTH(FILAMENT_UNLOAD_ALL_EXTRUDERS, MIXING_EXTRUDER) #if !BOTH(FILAMENT_UNLOAD_ALL_EXTRUDERS, MIXING_EXTRUDER)
constexpr float mix_multiplier = 1.0; constexpr float mix_multiplier = 1.0;
#endif #endif
if (!ensure_safe_temperature(false, mode)) { if (!ensure_safe_temperature(false, mode)) {
#if HAS_LCD_MENU if (show_lcd) ui.pause_show_message(PAUSE_MESSAGE_STATUS);
if (show_lcd) lcd_pause_show_message(PAUSE_MESSAGE_STATUS);
#endif
return false; return false;
} }
#if HAS_LCD_MENU if (show_lcd) ui.pause_show_message(PAUSE_MESSAGE_UNLOAD, mode);
if (show_lcd) lcd_pause_show_message(PAUSE_MESSAGE_UNLOAD, mode);
#endif
// Retract filament // Retract filament
unscaled_e_move(-(FILAMENT_UNLOAD_PURGE_RETRACT) * mix_multiplier, (PAUSE_PARK_RETRACT_FEEDRATE) * mix_multiplier); unscaled_e_move(-(FILAMENT_UNLOAD_PURGE_RETRACT) * mix_multiplier, (PAUSE_PARK_RETRACT_FEEDRATE) * mix_multiplier);
@ -479,7 +458,7 @@ void show_continue_prompt(const bool is_reload) {
DEBUG_SECTION(scp, "pause_print", true); DEBUG_SECTION(scp, "pause_print", true);
DEBUG_ECHOLNPAIR("... is_reload:", int(is_reload)); DEBUG_ECHOLNPAIR("... is_reload:", int(is_reload));
TERN_(HAS_LCD_MENU, lcd_pause_show_message(is_reload ? PAUSE_MESSAGE_INSERT : PAUSE_MESSAGE_WAITING)); ui.pause_show_message(is_reload ? PAUSE_MESSAGE_INSERT : PAUSE_MESSAGE_WAITING);
SERIAL_ECHO_START(); SERIAL_ECHO_START();
serialprintPGM(is_reload ? PSTR(_PMSG(STR_FILAMENT_CHANGE_INSERT) "\n") : PSTR(_PMSG(STR_FILAMENT_CHANGE_WAIT) "\n")); serialprintPGM(is_reload ? PSTR(_PMSG(STR_FILAMENT_CHANGE_INSERT) "\n") : PSTR(_PMSG(STR_FILAMENT_CHANGE_WAIT) "\n"));
} }
@ -520,7 +499,7 @@ void wait_for_confirmation(const bool is_reload/*=false*/, const int8_t max_beep
// Wait for the user to press the button to re-heat the nozzle, then // Wait for the user to press the button to re-heat the nozzle, then
// re-heat the nozzle, re-show the continue prompt, restart idle timers, start over // re-heat the nozzle, re-show the continue prompt, restart idle timers, start over
if (nozzle_timed_out) { if (nozzle_timed_out) {
TERN_(HAS_LCD_MENU, lcd_pause_show_message(PAUSE_MESSAGE_HEAT)); ui.pause_show_message(PAUSE_MESSAGE_HEAT);
SERIAL_ECHO_MSG(_PMSG(STR_FILAMENT_CHANGE_HEAT)); SERIAL_ECHO_MSG(_PMSG(STR_FILAMENT_CHANGE_HEAT));
TERN_(HOST_PROMPT_SUPPORT, host_prompt_do(PROMPT_USER_CONTINUE, GET_TEXT(MSG_HEATER_TIMEOUT), GET_TEXT(MSG_REHEAT))); TERN_(HOST_PROMPT_SUPPORT, host_prompt_do(PROMPT_USER_CONTINUE, GET_TEXT(MSG_HEATER_TIMEOUT), GET_TEXT(MSG_REHEAT)));
@ -614,7 +593,7 @@ void resume_print(const float &slow_load_length/*=0*/, const float &fast_load_le
thermalManager.wait_for_hotend(active_extruder, false); thermalManager.wait_for_hotend(active_extruder, false);
} }
TERN_(HAS_LCD_MENU, lcd_pause_show_message(PAUSE_MESSAGE_RESUME)); ui.pause_show_message(PAUSE_MESSAGE_RESUME);
// Check Temperature before moving hotend // Check Temperature before moving hotend
ensure_safe_temperature(); ensure_safe_temperature();
@ -653,7 +632,7 @@ void resume_print(const float &slow_load_length/*=0*/, const float &fast_load_le
// Write PLR now to update the z axis value // Write PLR now to update the z axis value
TERN_(POWER_LOSS_RECOVERY, if (recovery.enabled) recovery.save(true)); TERN_(POWER_LOSS_RECOVERY, if (recovery.enabled) recovery.save(true));
TERN_(HAS_LCD_MENU, lcd_pause_show_message(PAUSE_MESSAGE_STATUS)); ui.pause_show_message(PAUSE_MESSAGE_STATUS);
#ifdef ACTION_ON_RESUMED #ifdef ACTION_ON_RESUMED
host_action_resumed(); host_action_resumed();

6
Marlin/src/feature/pause.h

@ -101,4 +101,8 @@ bool unload_filament(const float &unload_length, const bool show_lcd=false, cons
#endif #endif
); );
#endif // ADVANCED_PAUSE_FEATURE #else // !ADVANCED_PAUSE_FEATURE
constexpr uint8_t did_pause_print = 0;
#endif // !ADVANCED_PAUSE_FEATURE

3
Marlin/src/feature/runout.cpp

@ -59,6 +59,7 @@ bool FilamentMonitorBase::enabled = true,
// Filament Runout event handler // Filament Runout event handler
// //
#include "../MarlinCore.h" #include "../MarlinCore.h"
#include "../feature/pause.h"
#include "../gcode/queue.h" #include "../gcode/queue.h"
#if ENABLED(HOST_ACTION_COMMANDS) #if ENABLED(HOST_ACTION_COMMANDS)
@ -71,7 +72,7 @@ bool FilamentMonitorBase::enabled = true,
void event_filament_runout() { void event_filament_runout() {
if (TERN0(ADVANCED_PAUSE_FEATURE, did_pause_print)) return; // Action already in progress. Purge triggered repeated runout. if (did_pause_print) return; // Action already in progress. Purge triggered repeated runout.
#if ENABLED(TOOLCHANGE_MIGRATION_FEATURE) #if ENABLED(TOOLCHANGE_MIGRATION_FEATURE)
if (migration.in_progress) { if (migration.in_progress) {

8
Marlin/src/feature/runout.h

@ -118,9 +118,7 @@ class TFilamentMonitor : public FilamentMonitorBase {
// Give the response a chance to update its counter. // Give the response a chance to update its counter.
static inline void run() { static inline void run() {
if ( enabled && !filament_ran_out if (enabled && !filament_ran_out && (printingIsActive() || did_pause_print)) {
&& (printingIsActive() || TERN0(ADVANCED_PAUSE_FEATURE, did_pause_print))
) {
TERN_(HAS_FILAMENT_RUNOUT_DISTANCE, cli()); // Prevent RunoutResponseDelayed::block_completed from accumulating here TERN_(HAS_FILAMENT_RUNOUT_DISTANCE, cli()); // Prevent RunoutResponseDelayed::block_completed from accumulating here
response.run(); response.run();
sensor.run(); sensor.run();
@ -343,9 +341,7 @@ class FilamentSensorBase {
} }
static inline void block_completed(const block_t* const b) { static inline void block_completed(const block_t* const b) {
if (b->steps.x || b->steps.y || b->steps.z if (b->steps.x || b->steps.y || b->steps.z || did_pause_print) { // Allow pause purge move to re-trigger runout state
|| TERN0(ADVANCED_PAUSE_FEATURE, did_pause_print) // Allow pause purge move to re-trigger runout state
) {
// Only trigger on extrusion with XYZ movement to allow filament change and retract/recover. // Only trigger on extrusion with XYZ movement to allow filament change and retract/recover.
const uint8_t e = b->extruder; const uint8_t e = b->extruder;
const int32_t steps = b->steps.e; const int32_t steps = b->steps.e;

10
Marlin/src/feature/twibus.cpp

@ -28,6 +28,8 @@
#include <Wire.h> #include <Wire.h>
TWIBus i2c;
TWIBus::TWIBus() { TWIBus::TWIBus() {
#if I2C_SLAVE_ADDRESS == 0 #if I2C_SLAVE_ADDRESS == 0
Wire.begin(); // No address joins the BUS as the master Wire.begin(); // No address joins the BUS as the master
@ -155,6 +157,14 @@ void TWIBus::flush() {
reset(); reset();
} }
void i2c_on_receive(int bytes) { // just echo all bytes received to serial
i2c.receive(bytes);
}
void i2c_on_request() { // just send dummy data for now
i2c.reply("Hello World!\n");
}
#endif #endif
#if ENABLED(DEBUG_TWIBUS) #if ENABLED(DEBUG_TWIBUS)

13
Marlin/src/feature/twibus.h

@ -31,6 +31,17 @@
typedef void (*twiReceiveFunc_t)(int bytes); typedef void (*twiReceiveFunc_t)(int bytes);
typedef void (*twiRequestFunc_t)(); typedef void (*twiRequestFunc_t)();
/**
* For a light i2c protocol that runs on two boards running Marlin see:
* See https://github.com/MarlinFirmware/Marlin/issues/4776#issuecomment-246262879
*/
#if I2C_SLAVE_ADDRESS > 0
void i2c_on_receive(int bytes); // Demo i2c onReceive handler
void i2c_on_request(); // Demo i2c onRequest handler
#endif
#define TWIBUS_BUFFER_SIZE 32 #define TWIBUS_BUFFER_SIZE 32
/** /**
@ -238,3 +249,5 @@ class TWIBus {
static inline void debug(const char[], uint8_t) {} static inline void debug(const char[], uint8_t) {}
#endif #endif
}; };
extern TWIBus i2c;

3
Marlin/src/gcode/control/M108_M112_M410.cpp

@ -25,7 +25,8 @@
#if DISABLED(EMERGENCY_PARSER) #if DISABLED(EMERGENCY_PARSER)
#include "../gcode.h" #include "../gcode.h"
#include "../../MarlinCore.h" // for wait_for_heatup, kill, quickstop_stepper #include "../../MarlinCore.h" // for wait_for_heatup, kill
#include "../../module/motion.h" // for quickstop_stepper
/** /**
* M108: Stop the waiting for heaters in M109, M190, M303. Does not affect the target temperature. * M108: Stop the waiting for heaters in M109, M190, M303. Does not affect the target temperature.

2
Marlin/src/gcode/control/M226.cpp

@ -28,6 +28,8 @@
#include "../../MarlinCore.h" // for pin_is_protected and idle() #include "../../MarlinCore.h" // for pin_is_protected and idle()
#include "../../module/stepper.h" #include "../../module/stepper.h"
void protected_pin_err();
/** /**
* M226: Wait until the specified pin reaches the state required (M226 P<pin> S<state>) * M226: Wait until the specified pin reaches the state required (M226 P<pin> S<state>)
*/ */

4
Marlin/src/gcode/control/M42.cpp

@ -31,6 +31,10 @@
#include "../../module/temperature.h" #include "../../module/temperature.h"
#endif #endif
void protected_pin_err() {
SERIAL_ERROR_MSG(STR_ERR_PROTECTED_PIN);
}
/** /**
* M42: Change pin status via GCode * M42: Change pin status via GCode
* *

2
Marlin/src/gcode/feature/i2c/M260_M261.cpp

@ -26,7 +26,7 @@
#include "../../gcode.h" #include "../../gcode.h"
#include "../../../MarlinCore.h" // for i2c #include "../../../feature/twibus.h"
/** /**
* M260: Send data to a I2C slave device * M260: Send data to a I2C slave device

9
Marlin/src/gcode/feature/pause/M125.cpp

@ -27,13 +27,10 @@
#include "../../gcode.h" #include "../../gcode.h"
#include "../../parser.h" #include "../../parser.h"
#include "../../../feature/pause.h" #include "../../../feature/pause.h"
#include "../../../lcd/marlinui.h"
#include "../../../module/motion.h" #include "../../../module/motion.h"
#include "../../../sd/cardreader.h"
#include "../../../module/printcounter.h" #include "../../../module/printcounter.h"
#include "../../../sd/cardreader.h"
#if HAS_LCD_MENU
#include "../../../lcd/marlinui.h"
#endif
#if ENABLED(POWER_LOSS_RECOVERY) #if ENABLED(POWER_LOSS_RECOVERY)
#include "../../../feature/powerloss.h" #include "../../../feature/powerloss.h"
@ -76,7 +73,7 @@ void GcodeSuite::M125() {
const bool sd_printing = TERN0(SDSUPPORT, IS_SD_PRINTING()); const bool sd_printing = TERN0(SDSUPPORT, IS_SD_PRINTING());
TERN_(HAS_LCD_MENU, lcd_pause_show_message(PAUSE_MESSAGE_PARKING, PAUSE_MODE_PAUSE_PRINT)); ui.pause_show_message(PAUSE_MESSAGE_PARKING, PAUSE_MODE_PAUSE_PRINT);
// If possible, show an LCD prompt with the 'P' flag // If possible, show an LCD prompt with the 'P' flag
const bool show_lcd = TERN0(HAS_LCD_MENU, parser.boolval('P')); const bool show_lcd = TERN0(HAS_LCD_MENU, parser.boolval('P'));

9
Marlin/src/gcode/feature/pause/M600.cpp

@ -28,15 +28,12 @@
#include "../../../feature/pause.h" #include "../../../feature/pause.h"
#include "../../../module/motion.h" #include "../../../module/motion.h"
#include "../../../module/printcounter.h" #include "../../../module/printcounter.h"
#include "../../../lcd/marlinui.h"
#if HAS_MULTI_EXTRUDER #if HAS_MULTI_EXTRUDER
#include "../../../module/tool_change.h" #include "../../../module/tool_change.h"
#endif #endif
#if HAS_LCD_MENU
#include "../../../lcd/marlinui.h"
#endif
#if ENABLED(MMU2_MENUS) #if ENABLED(MMU2_MENUS)
#include "../../../lcd/menu/menu_mmu2.h" #include "../../../lcd/menu/menu_mmu2.h"
#endif #endif
@ -96,8 +93,8 @@ void GcodeSuite::M600() {
#endif #endif
// Show initial "wait for start" message // Show initial "wait for start" message
#if HAS_LCD_MENU && DISABLED(MMU2_MENUS) #if DISABLED(MMU2_MENUS)
lcd_pause_show_message(PAUSE_MESSAGE_CHANGING, PAUSE_MODE_PAUSE_PRINT, target_extruder); ui.pause_show_message(PAUSE_MESSAGE_CHANGING, PAUSE_MODE_PAUSE_PRINT, target_extruder);
#endif #endif
#if ENABLED(HOME_BEFORE_FILAMENT_CHANGE) #if ENABLED(HOME_BEFORE_FILAMENT_CHANGE)

13
Marlin/src/gcode/feature/pause/M701_M702.cpp

@ -29,15 +29,12 @@
#include "../../../module/motion.h" #include "../../../module/motion.h"
#include "../../../module/temperature.h" #include "../../../module/temperature.h"
#include "../../../feature/pause.h" #include "../../../feature/pause.h"
#include "../../../lcd/marlinui.h"
#if HAS_MULTI_EXTRUDER #if HAS_MULTI_EXTRUDER
#include "../../../module/tool_change.h" #include "../../../module/tool_change.h"
#endif #endif
#if HAS_LCD_MENU
#include "../../../lcd/marlinui.h"
#endif
#if HAS_PRUSA_MMU2 #if HAS_PRUSA_MMU2
#include "../../../feature/mmu/mmu2.h" #include "../../../feature/mmu/mmu2.h"
#endif #endif
@ -82,7 +79,7 @@ void GcodeSuite::M701() {
if (parser.seenval('Z')) park_point.z = parser.linearval('Z'); if (parser.seenval('Z')) park_point.z = parser.linearval('Z');
// Show initial "wait for load" message // Show initial "wait for load" message
TERN_(HAS_LCD_MENU, lcd_pause_show_message(PAUSE_MESSAGE_LOAD, PAUSE_MODE_LOAD_FILAMENT, target_extruder)); ui.pause_show_message(PAUSE_MESSAGE_LOAD, PAUSE_MODE_LOAD_FILAMENT, target_extruder);
#if HAS_MULTI_EXTRUDER && (HAS_PRUSA_MMU1 || !HAS_MMU) #if HAS_MULTI_EXTRUDER && (HAS_PRUSA_MMU1 || !HAS_MMU)
// Change toolhead if specified // Change toolhead if specified
@ -128,7 +125,7 @@ void GcodeSuite::M701() {
TERN_(MIXING_EXTRUDER, mixer.T(old_mixing_tool)); // Restore original mixing tool TERN_(MIXING_EXTRUDER, mixer.T(old_mixing_tool)); // Restore original mixing tool
// Show status screen // Show status screen
TERN_(HAS_LCD_MENU, lcd_pause_show_message(PAUSE_MESSAGE_STATUS)); ui.pause_show_message(PAUSE_MESSAGE_STATUS);
} }
/** /**
@ -180,7 +177,7 @@ void GcodeSuite::M702() {
if (parser.seenval('Z')) park_point.z = parser.linearval('Z'); if (parser.seenval('Z')) park_point.z = parser.linearval('Z');
// Show initial "wait for unload" message // Show initial "wait for unload" message
TERN_(HAS_LCD_MENU, lcd_pause_show_message(PAUSE_MESSAGE_UNLOAD, PAUSE_MODE_UNLOAD_FILAMENT, target_extruder)); ui.pause_show_message(PAUSE_MESSAGE_UNLOAD, PAUSE_MODE_UNLOAD_FILAMENT, target_extruder);
#if HAS_MULTI_EXTRUDER && (HAS_PRUSA_MMU1 || !HAS_MMU) #if HAS_MULTI_EXTRUDER && (HAS_PRUSA_MMU1 || !HAS_MMU)
// Change toolhead if specified // Change toolhead if specified
@ -232,7 +229,7 @@ void GcodeSuite::M702() {
TERN_(MIXING_EXTRUDER, mixer.T(old_mixing_tool)); // Restore original mixing tool TERN_(MIXING_EXTRUDER, mixer.T(old_mixing_tool)); // Restore original mixing tool
// Show status screen // Show status screen
TERN_(HAS_LCD_MENU, lcd_pause_show_message(PAUSE_MESSAGE_STATUS)); ui.pause_show_message(PAUSE_MESSAGE_STATUS);
} }
#endif // ADVANCED_PAUSE_FEATURE #endif // ADVANCED_PAUSE_FEATURE

32
Marlin/src/gcode/gcode.cpp

@ -61,7 +61,7 @@ GcodeSuite gcode;
#include "../feature/password/password.h" #include "../feature/password/password.h"
#endif #endif
#include "../MarlinCore.h" // for idle() #include "../MarlinCore.h" // for idle, kill
// Inactivity shutdown // Inactivity shutdown
millis_t GcodeSuite::previous_move_ms = 0, millis_t GcodeSuite::previous_move_ms = 0,
@ -209,6 +209,31 @@ void GcodeSuite::dwell(millis_t time) {
*/ */
#if BOTH(HAS_LEVELING, G29_RETRY_AND_RECOVER) #if BOTH(HAS_LEVELING, G29_RETRY_AND_RECOVER)
void GcodeSuite::event_probe_recover() {
TERN_(HOST_PROMPT_SUPPORT, host_prompt_do(PROMPT_INFO, PSTR("G29 Retrying"), DISMISS_STR));
#ifdef ACTION_ON_G29_RECOVER
host_action(PSTR(ACTION_ON_G29_RECOVER));
#endif
#ifdef G29_RECOVER_COMMANDS
process_subcommands_now_P(PSTR(G29_RECOVER_COMMANDS));
#endif
}
void GcodeSuite::event_probe_failure() {
#ifdef ACTION_ON_G29_FAILURE
host_action(PSTR(ACTION_ON_G29_FAILURE));
#endif
#ifdef G29_FAILURE_COMMANDS
process_subcommands_now_P(PSTR(G29_FAILURE_COMMANDS));
#endif
#if ENABLED(G29_HALT_ON_FAILURE)
#ifdef ACTION_ON_CANCEL
host_action_cancel();
#endif
kill(GET_TEXT(MSG_LCD_PROBING_FAILED));
#endif
}
#ifndef G29_MAX_RETRIES #ifndef G29_MAX_RETRIES
#define G29_MAX_RETRIES 0 #define G29_MAX_RETRIES 0
#endif #endif
@ -216,7 +241,10 @@ void GcodeSuite::dwell(millis_t time) {
void GcodeSuite::G29_with_retry() { void GcodeSuite::G29_with_retry() {
uint8_t retries = G29_MAX_RETRIES; uint8_t retries = G29_MAX_RETRIES;
while (G29()) { // G29 should return true for failed probes ONLY while (G29()) { // G29 should return true for failed probes ONLY
if (retries--) event_probe_recover(); if (retries) {
event_probe_recover();
--retries;
}
else { else {
event_probe_failure(); event_probe_failure();
return; return;

2
Marlin/src/gcode/gcode.h

@ -452,6 +452,8 @@ private:
#if HAS_LEVELING #if HAS_LEVELING
#if ENABLED(G29_RETRY_AND_RECOVER) #if ENABLED(G29_RETRY_AND_RECOVER)
static void event_probe_failure();
static void event_probe_recover();
static void G29_with_retry(); static void G29_with_retry();
#define G29_TYPE bool #define G29_TYPE bool
#else #else

1
Marlin/src/gcode/queue.cpp

@ -31,6 +31,7 @@ GCodeQueue queue;
#include "../lcd/marlinui.h" #include "../lcd/marlinui.h"
#include "../sd/cardreader.h" #include "../sd/cardreader.h"
#include "../module/motion.h"
#include "../module/planner.h" #include "../module/planner.h"
#include "../module/temperature.h" #include "../module/temperature.h"
#include "../MarlinCore.h" #include "../MarlinCore.h"

2
Marlin/src/gcode/sd/M1001.cpp

@ -44,7 +44,7 @@
#endif #endif
#if HAS_LEDS_OFF_FLAG #if HAS_LEDS_OFF_FLAG
#include "../../MarlinCore.h" // for wait_for_user_response #include "../../MarlinCore.h" // for wait_for_user_response()
#include "../../feature/leds/printer_event_leds.h" #include "../../feature/leds/printer_event_leds.h"
#endif #endif

2
Marlin/src/lcd/dogm/marlinui_DOGM.cpp

@ -544,6 +544,8 @@ void MarlinUI::clear_lcd() { } // Automatically cleared by Picture Loop
// Put Relevant Text on Display // Put Relevant Text on Display
extern const char X_LBL[], Y_LBL[], Z_LBL[];
// Show X and Y positions at top of screen // Show X and Y positions at top of screen
u8g.setColorIndex(1); u8g.setColorIndex(1);
if (PAGE_UNDER(7)) { if (PAGE_UNDER(7)) {

1
Marlin/src/lcd/dwin/e3v2/rotary_encoder.h

@ -30,7 +30,6 @@
****************************************************************************/ ****************************************************************************/
#include "../../../inc/MarlinConfig.h" #include "../../../inc/MarlinConfig.h"
#include "../../../MarlinCore.h"
/*********************** Encoder Set ***********************/ /*********************** Encoder Set ***********************/

4
Marlin/src/lcd/extui/lib/anycubic_i3mega/anycubic_i3mega_lcd.cpp

@ -27,8 +27,8 @@
#include "../../ui_api.h" #include "../../ui_api.h"
#include "../../../../libs/numtostr.h" #include "../../../../libs/numtostr.h"
#include "../../../../module/motion.h" // for A20 read printing speed feedrate_percentage #include "../../../../module/motion.h" // for quickstop_stepper, A20 read printing speed, feedrate_percentage
#include "../../../../MarlinCore.h" // for quickstop_stepper, disable_steppers, G28_STR #include "../../../../MarlinCore.h" // for disable_steppers, G28_STR
#include "../../../../inc/MarlinConfig.h" #include "../../../../inc/MarlinConfig.h"
// command sending macro's with debugging capability // command sending macro's with debugging capability

5
Marlin/src/lcd/extui/lib/dgus/DGUSDisplay.h

@ -25,7 +25,8 @@
#include "../../../../inc/MarlinConfigPre.h" #include "../../../../inc/MarlinConfigPre.h"
#include "../../../../MarlinCore.h" #include <stdlib.h> // size_t
#if HAS_BED_PROBE #if HAS_BED_PROBE
#include "../../../../module/probe.h" #include "../../../../module/probe.h"
#endif #endif
@ -96,7 +97,7 @@ private:
static void WritePGM(const char str[], uint8_t len); static void WritePGM(const char str[], uint8_t len);
static void ProcessRx(); static void ProcessRx();
static inline uint16_t swap16(const uint16_t value) { return (value & 0xffU) << 8U | (value >> 8U); } static inline uint16_t swap16(const uint16_t value) { return (value & 0xFFU) << 8U | (value >> 8U); }
static rx_datagram_state_t rx_datagram_state; static rx_datagram_state_t rx_datagram_state;
static uint8_t rx_datagram_len; static uint8_t rx_datagram_len;
static bool Initialized, no_reentrance; static bool Initialized, no_reentrance;

2
Marlin/src/lcd/extui/lib/mks_ui/tft_multi_language.cpp

@ -23,8 +23,6 @@
#if HAS_TFT_LVGL_UI #if HAS_TFT_LVGL_UI
#include "../../../../MarlinCore.h"
#include "draw_ui.h" #include "draw_ui.h"
#include "tft_multi_language.h" #include "tft_multi_language.h"

4
Marlin/src/lcd/extui/lib/mks_ui/wifi_module.cpp

@ -39,6 +39,10 @@
#include "../../../../module/planner.h" #include "../../../../module/planner.h"
#include "../../../../module/servo.h" #include "../../../../module/servo.h"
#include "../../../../module/probe.h" #include "../../../../module/probe.h"
#if DISABLED(EMERGENCY_PARSER)
#include "../../../../module/motion.h"
#endif
#if ENABLED(POWER_LOSS_RECOVERY) #if ENABLED(POWER_LOSS_RECOVERY)
#include "../../../../feature/powerloss.h" #include "../../../../feature/powerloss.h"
#endif #endif

2
Marlin/src/lcd/marlinui.cpp

@ -1516,7 +1516,7 @@ void MarlinUI::update() {
LCD_MESSAGEPGM(MSG_PRINT_PAUSED); LCD_MESSAGEPGM(MSG_PRINT_PAUSED);
#if ENABLED(PARK_HEAD_ON_PAUSE) #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 pause_show_message(PAUSE_MESSAGE_PARKING, PAUSE_MODE_PAUSE_PRINT); // Show message immediately to let user know about pause in progress
queue.inject_P(PSTR("M25 P\nM24")); queue.inject_P(PSTR("M25 P\nM24"));
#elif ENABLED(SDSUPPORT) #elif ENABLED(SDSUPPORT)
queue.inject_P(PSTR("M25")); queue.inject_P(PSTR("M25"));

25
Marlin/src/lcd/marlinui.h

@ -51,14 +51,12 @@
#include "../module/printcounter.h" #include "../module/printcounter.h"
#endif #endif
#if HAS_WIRED_LCD #if BOTH(HAS_LCD_MENU, ADVANCED_PAUSE_FEATURE)
#include "../feature/pause.h"
#include "../MarlinCore.h" #include "../module/motion.h" // for active_extruder
#endif
#if ENABLED(ADVANCED_PAUSE_FEATURE) #if HAS_WIRED_LCD
#include "../feature/pause.h"
#include "../module/motion.h" // for active_extruder
#endif
enum LCDViewAction : uint8_t { enum LCDViewAction : uint8_t {
LCDVIEW_NONE, LCDVIEW_NONE,
@ -87,12 +85,6 @@
typedef void (*screenFunc_t)(); typedef void (*screenFunc_t)();
typedef void (*menuAction_t)(); typedef void (*menuAction_t)();
#if ENABLED(ADVANCED_PAUSE_FEATURE)
void lcd_pause_show_message(const PauseMessage message,
const PauseMode mode=PAUSE_MODE_SAME,
const uint8_t extruder=active_extruder);
#endif
#if ENABLED(AUTO_BED_LEVELING_UBL) #if ENABLED(AUTO_BED_LEVELING_UBL)
void lcd_mesh_edit_setup(const float &initial); void lcd_mesh_edit_setup(const float &initial);
float lcd_mesh_edit(); float lcd_mesh_edit();
@ -506,6 +498,13 @@ public:
#endif #endif
#if BOTH(HAS_LCD_MENU, ADVANCED_PAUSE_FEATURE)
static void pause_show_message(const PauseMessage message, const PauseMode mode=PAUSE_MODE_SAME, const uint8_t extruder=active_extruder);
#else
static inline void _pause_show_message() {}
#define pause_show_message(...) _pause_show_message()
#endif
// //
// EEPROM: Reset / Init / Load / Store // EEPROM: Reset / Init / Load / Store
// //

2
Marlin/src/lcd/menu/menu_configuration.cpp

@ -161,6 +161,8 @@ void menu_advanced_settings();
#include "../../module/motion.h" #include "../../module/motion.h"
#include "../../gcode/queue.h" #include "../../gcode/queue.h"
extern const char G28_STR[];
void menu_tool_offsets() { void menu_tool_offsets() {
auto _recalc_offsets = []{ auto _recalc_offsets = []{

2
Marlin/src/lcd/menu/menu_delta_calibrate.cpp

@ -53,6 +53,7 @@ void _man_probe_pt(const xy_pos_t &xy) {
#if ENABLED(DELTA_AUTO_CALIBRATION) #if ENABLED(DELTA_AUTO_CALIBRATION)
#include "../../MarlinCore.h" // for wait_for_user_response()
#include "../../gcode/gcode.h" #include "../../gcode/gcode.h"
#if ENABLED(HOST_PROMPT_SUPPORT) #if ENABLED(HOST_PROMPT_SUPPORT)
@ -81,6 +82,7 @@ void _man_probe_pt(const xy_pos_t &xy) {
} }
void _lcd_delta_calibrate_home() { void _lcd_delta_calibrate_home() {
extern const char G28_STR[];
queue.inject_P(G28_STR); queue.inject_P(G28_STR);
ui.goto_screen(_lcd_calibrate_homing); ui.goto_screen(_lcd_calibrate_homing);
} }

4
Marlin/src/lcd/menu/menu_filament.cpp

@ -107,6 +107,8 @@ void _menu_temp_filament_op(const PauseMode mode, const int8_t extruder) {
*/ */
#if E_STEPPERS > 1 || ENABLED(FILAMENT_LOAD_UNLOAD_GCODES) #if E_STEPPERS > 1 || ENABLED(FILAMENT_LOAD_UNLOAD_GCODES)
bool printingIsPaused();
void menu_change_filament() { void menu_change_filament() {
// Say "filament change" when no print is active // Say "filament change" when no print is active
editable.int8 = printingIsPaused() ? PAUSE_MODE_PAUSE_PRINT : PAUSE_MODE_CHANGE_FILAMENT; editable.int8 = printingIsPaused() ? PAUSE_MODE_PAUSE_PRINT : PAUSE_MODE_CHANGE_FILAMENT;
@ -315,7 +317,7 @@ FORCE_INLINE screenFunc_t ap_message_screen(const PauseMessage message) {
return nullptr; return nullptr;
} }
void lcd_pause_show_message( void MarlinUI::pause_show_message(
const PauseMessage message, const PauseMessage message,
const PauseMode mode/*=PAUSE_MODE_SAME*/, const PauseMode mode/*=PAUSE_MODE_SAME*/,
const uint8_t extruder/*=active_extruder*/ const uint8_t extruder/*=active_extruder*/

2
Marlin/src/lcd/menu/menu_motion.cpp

@ -51,6 +51,8 @@
float manual_move_e_origin = 0; float manual_move_e_origin = 0;
#endif #endif
extern const char G28_STR[];
// //
// "Motion" > "Move Axis" submenu // "Motion" > "Move Axis" submenu
// //

1
Marlin/src/module/endstops.cpp

@ -27,7 +27,6 @@
#include "endstops.h" #include "endstops.h"
#include "stepper.h" #include "stepper.h"
#include "../MarlinCore.h"
#include "../sd/cardreader.h" #include "../sd/cardreader.h"
#include "temperature.h" #include "temperature.h"
#include "../lcd/marlinui.h" #include "../lcd/marlinui.h"

13
Marlin/src/module/motion.cpp

@ -236,8 +236,17 @@ void report_current_position_projected() {
} }
/** /**
* sync_plan_position * Run out the planner buffer and re-sync the current
* * position from the last-updated stepper positions.
*/
void quickstop_stepper() {
planner.quick_stop();
planner.synchronize();
set_current_from_steppers_for_axis(ALL_AXES);
sync_plan_position();
}
/**
* Set the planner/stepper positions directly from current_position with * Set the planner/stepper positions directly from current_position with
* no kinematic translation. Used for homing axes and cartesian/core syncing. * no kinematic translation. Used for homing axes and cartesian/core syncing.
*/ */

2
Marlin/src/module/motion.h

@ -212,6 +212,8 @@ void report_current_position_projected();
void get_cartesian_from_steppers(); void get_cartesian_from_steppers();
void set_current_from_steppers_for_axis(const AxisEnum axis); void set_current_from_steppers_for_axis(const AxisEnum axis);
void quickstop_stepper();
/** /**
* sync_plan_position * sync_plan_position
* *

2
Marlin/src/module/probe.cpp

@ -38,7 +38,7 @@
#include "../gcode/gcode.h" #include "../gcode/gcode.h"
#include "../lcd/marlinui.h" #include "../lcd/marlinui.h"
#include "../MarlinCore.h" // for stop(), disable_e_steppers #include "../MarlinCore.h" // for stop(), disable_e_steppers(), wait_for_user_response()
#if HAS_LEVELING #if HAS_LEVELING
#include "../feature/bedlevel/bedlevel.h" #include "../feature/bedlevel/bedlevel.h"

11
Marlin/src/module/temperature.cpp

@ -27,14 +27,17 @@
// Useful when debugging thermocouples // Useful when debugging thermocouples
//#define IGNORE_THERMOCOUPLE_ERRORS //#define IGNORE_THERMOCOUPLE_ERRORS
#include "../MarlinCore.h"
#include "../HAL/shared/Delay.h"
#include "../lcd/marlinui.h"
#include "temperature.h" #include "temperature.h"
#include "endstops.h" #include "endstops.h"
#include "../MarlinCore.h"
#include "planner.h" #include "planner.h"
#include "../HAL/shared/Delay.h"
#include "../lcd/marlinui.h" #if ENABLED(EMERGENCY_PARSER)
#include "motion.h"
#endif
#if ENABLED(DWIN_CREALITY_LCD) #if ENABLED(DWIN_CREALITY_LCD)
#include "../lcd/dwin/e3v2/dwin.h" #include "../lcd/dwin/e3v2/dwin.h"

Loading…
Cancel
Save