Browse Source

Fix and improve Power-Loss Recovery (#21779, #21894)

Co-authored-by: Scott Lahteine <thinkyhead@users.noreply.github.com>
vanilla_fb_2.0.x
tobuh 4 years ago
committed by Scott Lahteine
parent
commit
31d3a781a8
  1. 17
      Marlin/src/feature/pause.cpp
  2. 173
      Marlin/src/feature/powerloss.cpp
  3. 3
      Marlin/src/feature/powerloss.h
  4. 2
      Marlin/src/gcode/feature/pause/M125.cpp
  5. 2
      Marlin/src/gcode/sd/M24_M25.cpp
  6. 2
      Marlin/src/inc/SanityCheck.h
  7. 10
      Marlin/src/lcd/extui/dgus/mks/DGUSDisplayDef.cpp
  8. 8
      buildroot/tests/rambo

17
Marlin/src/feature/pause.cpp

@ -406,6 +406,15 @@ bool pause_print(const_float_t retract, const xyz_pos_t &park_point, const bool
// Save current position
resume_position = current_position;
// Will the nozzle be parking?
const bool do_park = !axes_should_home();
#if ENABLED(POWER_LOSS_RECOVERY)
// Save PLR info in case the power goes out while parked
const float park_raise = do_park ? nozzle.park_mode_0_height(park_point.z) - current_position.z : POWER_LOSS_ZRAISE;
if (was_sd_printing && recovery.enabled) recovery.save(true, park_raise, do_park);
#endif
// Wait for buffered blocks to complete
planner.synchronize();
@ -419,9 +428,8 @@ bool pause_print(const_float_t retract, const xyz_pos_t &park_point, const bool
unscaled_e_move(retract, PAUSE_PARK_RETRACT_FEEDRATE);
}
// Park the nozzle by doing a Minimum Z Raise followed by an XY Move
if (!axes_should_home())
nozzle.park(0, park_point);
// If axes don't need to home then the nozzle can park
if (do_park) nozzle.park(0, park_point); // Park the nozzle by doing a Minimum Z Raise followed by an XY Move
#if ENABLED(DUAL_X_CARRIAGE)
const int8_t saved_ext = active_extruder;
@ -429,7 +437,8 @@ bool pause_print(const_float_t retract, const xyz_pos_t &park_point, const bool
set_duplication_enabled(false, DXC_ext);
#endif
if (unload_length) // Unload the filament
// Unload the filament, if specified
if (unload_length)
unload_filament(unload_length, show_lcd, PAUSE_MODE_CHANGE_FILAMENT);
#if ENABLED(DUAL_X_CARRIAGE)

173
Marlin/src/feature/powerloss.cpp

@ -144,7 +144,7 @@ void PrintJobRecovery::prepare() {
/**
* Save the current machine state to the power-loss recovery file
*/
void PrintJobRecovery::save(const bool force/*=false*/, const float zraise/*=0*/) {
void PrintJobRecovery::save(const bool force/*=false*/, const float zraise/*=POWER_LOSS_ZRAISE*/, const bool raised/*=false*/) {
// We don't check IS_SD_PRINTING here so a save may occur during a pause
@ -181,14 +181,12 @@ void PrintJobRecovery::save(const bool force/*=false*/, const float zraise/*=0*/
info.current_position = current_position;
info.feedrate = uint16_t(MMS_TO_MMM(feedrate_mm_s));
info.zraise = zraise;
info.flag.raised = raised; // Was Z raised before power-off?
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);
#if HAS_MULTI_EXTRUDER
info.active_extruder = active_extruder;
#endif
TERN_(HAS_MULTI_EXTRUDER, info.active_extruder = active_extruder);
#if DISABLED(NO_VOLUMETRICS)
info.flag.volumetric_enabled = parser.volumetric_enabled;
@ -289,8 +287,9 @@ void PrintJobRecovery::save(const bool force/*=false*/, const float zraise/*=0*/
constexpr float zraise = 0;
#endif
// Save, including the limited Z raise
if (IS_SD_PRINTING()) save(true, zraise);
// Save the current position, distance that Z was (or should be) raised,
// and a flag whether the raise was already done here.
if (IS_SD_PRINTING()) save(true, zraise, ENABLED(BACKUP_POWER_SUPPLY));
// Disable all heaters to reduce power loss
thermalManager.disable_all_heaters();
@ -350,10 +349,10 @@ void PrintJobRecovery::resume() {
}
#endif
// Restore all hotend temperatures
// Heat hotend enough to soften material
#if HAS_HOTEND
HOTEND_LOOP() {
const celsius_t et = info.target_temperature[e];
const celsius_t et = _MAX(info.target_temperature[e], 180);
if (et) {
#if HAS_MULTI_HOTEND
sprintf_P(cmd, PSTR("T%iS"), e);
@ -365,37 +364,58 @@ void PrintJobRecovery::resume() {
}
#endif
// Interpret the saved Z according to flags
const float z_print = info.current_position.z,
z_raised = z_print + info.zraise;
//
// Home the axes that can safely be homed, and
// establish the current position as best we can.
//
gcode.process_subcommands_now_P(PSTR("G92.9E0")); // Reset E to 0
#if Z_HOME_DIR > 0
// If Z homing goes to max...
gcode.process_subcommands_now_P(PSTR(
"G92.9 E0\n" // Reset E to 0
"G28R0" // Home all axes (no raise)
));
float z_now = z_raised;
// If Z homing goes to max then just move back to the "raised" position
sprintf_P(cmd, PSTR(
"G28R0\n" // Home all axes (no raise)
"G1Z%sF1200" // Move Z down to (raised) height
), dtostrf(z_now, 1, 3, str_1));
gcode.process_subcommands_now(cmd);
#else
// If a Z raise occurred at outage restore Z, otherwise raise Z now
sprintf_P(cmd, PSTR("G92.9 E0 " TERN(BACKUP_POWER_SUPPLY, "Z%s", "Z0\nG1Z%s")), dtostrf(info.zraise, 1, 3, str_1));
gcode.process_subcommands_now(cmd);
#if ENABLED(POWER_LOSS_RECOVER_ZHOME) && defined(POWER_LOSS_ZHOME_POS)
#define HOMING_Z_DOWN 1
#else
#define HOME_XY_ONLY 1
#endif
// Home safely with no Z raise
gcode.process_subcommands_now_P(PSTR(
"G28R0" // No raise during G28
#if IS_CARTESIAN && (DISABLED(POWER_LOSS_RECOVER_ZHOME) || defined(POWER_LOSS_ZHOME_POS))
"XY" // Don't home Z on Cartesian unless overridden
#endif
));
float z_now = info.flag.raised ? z_raised : z_print;
// Reset E to 0 and set Z to the real position
#if HOME_XY_ONLY
sprintf_P(cmd, PSTR("G92.9Z%s"), dtostrf(z_now, 1, 3, str_1));
gcode.process_subcommands_now(cmd);
#endif
// Does Z need to be raised now? It should be raised before homing XY.
if (z_raised > z_now) {
z_now = z_raised;
sprintf_P(cmd, PSTR("G1Z%sF600"), dtostrf(z_now, 1, 3, str_1));
gcode.process_subcommands_now(cmd);
}
// Home XY with no Z raise, and also home Z here if Z isn't homing down below.
gcode.process_subcommands_now_P(PSTR("G28R0" TERN_(HOME_XY_ONLY, "XY"))); // No raise during G28
#endif
#if ENABLED(POWER_LOSS_RECOVER_ZHOME) && defined(POWER_LOSS_ZHOME_POS)
// Move to a safe XY position where Z can home while avoiding the print.
// If Z_SAFE_HOMING is enabled, its position must also be outside the print area!
#if HOMING_Z_DOWN
// Move to a safe XY position and home Z while avoiding the print.
constexpr xy_pos_t p = POWER_LOSS_ZHOME_POS;
sprintf_P(cmd, PSTR("G1X%sY%sF1000\nG28Z"), dtostrf(p.x, 1, 3, str_1), dtostrf(p.y, 1, 3, str_2));
gcode.process_subcommands_now(cmd);
@ -404,9 +424,24 @@ void PrintJobRecovery::resume() {
// Mark all axes as having been homed (no effect on current_position)
set_all_homed();
#if HAS_LEVELING
// Restore Z fade and possibly re-enable bed leveling compensation.
// Leveling may already be enabled due to the ENABLE_LEVELING_AFTER_G28 option.
// TODO: Add a G28 parameter to leave leveling disabled.
sprintf_P(cmd, PSTR("M420S%cZ%s"), '0' + (char)info.flag.leveling, dtostrf(info.fade, 1, 1, str_1));
gcode.process_subcommands_now(cmd);
#if HOME_XY_ONLY
// The physical Z was adjusted at power-off so undo the M420S1 correction to Z with G92.9.
sprintf_P(cmd, PSTR("G92.9Z%s"), dtostrf(z_now, 1, 1, str_1));
gcode.process_subcommands_now(cmd);
#endif
#endif
#if ENABLED(POWER_LOSS_RECOVER_ZHOME)
// Z was homed. Now move Z back up to the saved Z height, plus the POWER_LOSS_ZRAISE.
sprintf_P(cmd, PSTR("G1Z%sF500"), dtostrf(info.current_position.z + POWER_LOSS_ZRAISE, 1, 3, str_1));
// Z was homed down to the bed, so move up to the raised height.
z_now = z_raised;
sprintf_P(cmd, PSTR("G1Z%sF600"), dtostrf(z_now, 1, 3, str_1));
gcode.process_subcommands_now(cmd);
#endif
@ -429,8 +464,23 @@ void PrintJobRecovery::resume() {
#endif
#endif
// Select the previously active tool (with no_move)
#if HAS_MULTI_EXTRUDER
// Restore all hotend temperatures
#if HAS_HOTEND
HOTEND_LOOP() {
const celsius_t et = info.target_temperature[e];
if (et) {
#if HAS_MULTI_HOTEND
sprintf_P(cmd, PSTR("T%iS"), e);
gcode.process_subcommands_now(cmd);
#endif
sprintf_P(cmd, PSTR("M109S%i"), et);
gcode.process_subcommands_now(cmd);
}
}
#endif
// Restore the previously active tool (with no_move)
#if HAS_MULTI_EXTRUDER || HAS_MULTI_HOTEND
sprintf_P(cmd, PSTR("T%i S"), info.active_extruder);
gcode.process_subcommands_now(cmd);
#endif
@ -457,15 +507,6 @@ void PrintJobRecovery::resume() {
fwretract.current_hop = info.retract_hop;
#endif
#if HAS_LEVELING
// Restore leveling state before 'G92 Z' to ensure
// the Z stepper count corresponds to the native Z.
if (info.fade || info.flag.leveling) {
sprintf_P(cmd, PSTR("M420S%cZ%s"), '0' + (char)info.flag.leveling, dtostrf(info.fade, 1, 1, str_1));
gcode.process_subcommands_now(cmd);
}
#endif
#if ENABLED(GRADIENT_MIX)
memcpy(&mixer.gradient, &info.gradient, sizeof(info.gradient));
#endif
@ -492,14 +533,8 @@ void PrintJobRecovery::resume() {
);
gcode.process_subcommands_now(cmd);
// Move back to the saved Z
dtostrf(info.current_position.z, 1, 3, str_1);
#if Z_HOME_DIR > 0 || ENABLED(POWER_LOSS_RECOVER_ZHOME)
sprintf_P(cmd, PSTR("G1 Z%s F500"), str_1);
#else
gcode.process_subcommands_now_P(PSTR("G1 Z0 F200"));
sprintf_P(cmd, PSTR("G92.9 Z%s"), str_1);
#endif
// Move back down to the saved Z for printing
sprintf_P(cmd, PSTR("G1Z%sF600"), dtostrf(z_print, 1, 3, str_1));
gcode.process_subcommands_now(cmd);
// Restore the feedrate
@ -552,7 +587,15 @@ void PrintJobRecovery::resume() {
}
DEBUG_EOL();
DEBUG_ECHOLNPAIR("zraise: ", info.zraise);
DEBUG_ECHOLNPAIR("feedrate: ", info.feedrate);
DEBUG_ECHOLNPAIR("zraise: ", info.zraise, " ", info.flag.raised ? "(before)" : "");
#if ENABLED(GCODE_REPEAT_MARKERS)
DEBUG_ECHOLNPAIR("repeat index: ", info.stored_repeat.index);
LOOP_L_N(i, info.stored_repeat.index)
DEBUG_ECHOLNPAIR("..... sdpos: ", info.stored_repeat.marker.sdpos, " count: ", info.stored_repeat.marker.counter);
#endif
#if HAS_HOME_OFFSET
DEBUG_ECHOPGM("home_offset: ");
@ -572,12 +615,16 @@ void PrintJobRecovery::resume() {
DEBUG_EOL();
#endif
DEBUG_ECHOLNPAIR("feedrate: ", info.feedrate);
#if HAS_MULTI_EXTRUDER
DEBUG_ECHOLNPAIR("active_extruder: ", info.active_extruder);
#endif
#if DISABLED(NO_VOLUMETRICS)
DEBUG_ECHOPGM("filament_size:");
LOOP_L_N(i, EXTRUDERS) DEBUG_ECHOLNPAIR(" ", info.filament_size[i]);
DEBUG_EOL();
#endif
#if HAS_HOTEND
DEBUG_ECHOPGM("target_temperature: ");
HOTEND_LOOP() {
@ -601,8 +648,9 @@ void PrintJobRecovery::resume() {
#endif
#if HAS_LEVELING
DEBUG_ECHOLNPAIR("leveling: ", info.flag.leveling, " fade: ", info.fade);
DEBUG_ECHOLNPAIR("leveling: ", info.flag.leveling ? "ON" : "OFF", " fade: ", info.fade);
#endif
#if ENABLED(FWRETRACT)
DEBUG_ECHOPGM("retract: ");
for (int8_t e = 0; e < EXTRUDERS; e++) {
@ -612,11 +660,28 @@ void PrintJobRecovery::resume() {
DEBUG_EOL();
DEBUG_ECHOLNPAIR("retract_hop: ", info.retract_hop);
#endif
// Mixing extruder and gradient
#if BOTH(MIXING_EXTRUDER, GRADIENT_MIX)
DEBUG_ECHOLNPAIR("gradient: ", info.gradient.enabled ? "ON" : "OFF");
#endif
DEBUG_ECHOLNPAIR("sd_filename: ", info.sd_filename);
DEBUG_ECHOLNPAIR("sdpos: ", info.sdpos);
DEBUG_ECHOLNPAIR("print_job_elapsed: ", info.print_job_elapsed);
DEBUG_ECHOLNPAIR("dryrun: ", AS_DIGIT(info.flag.dryrun));
DEBUG_ECHOLNPAIR("allow_cold_extrusion: ", info.flag.allow_cold_extrusion);
DEBUG_ECHOPGM("axis_relative:");
if (TEST(info.axis_relative, REL_X)) DEBUG_ECHOPGM(" REL_X");
if (TEST(info.axis_relative, REL_Y)) DEBUG_ECHOPGM(" REL_Y");
if (TEST(info.axis_relative, REL_Z)) DEBUG_ECHOPGM(" REL_Z");
if (TEST(info.axis_relative, REL_E)) DEBUG_ECHOPGM(" REL_E");
if (TEST(info.axis_relative, E_MODE_ABS)) DEBUG_ECHOPGM(" E_MODE_ABS");
if (TEST(info.axis_relative, E_MODE_REL)) DEBUG_ECHOPGM(" E_MODE_REL");
DEBUG_EOL();
DEBUG_ECHOLNPAIR("flag.dryrun: ", AS_DIGIT(info.flag.dryrun));
DEBUG_ECHOLNPAIR("flag.allow_cold_extrusion: ", AS_DIGIT(info.flag.allow_cold_extrusion));
DEBUG_ECHOLNPAIR("flag.volumetric_enabled: ", AS_DIGIT(info.flag.volumetric_enabled));
}
else
DEBUG_ECHOLNPGM("INVALID DATA");

3
Marlin/src/feature/powerloss.h

@ -117,6 +117,7 @@ typedef struct {
// Misc. Marlin flags
struct {
bool raised:1; // Raised before saved
bool dryrun:1; // M111 S8
bool allow_cold_extrusion:1; // M302 P1
#if ENABLED(HAS_LEVELING)
@ -182,7 +183,7 @@ class PrintJobRecovery {
static inline void cancel() { purge(); IF_DISABLED(NO_SD_AUTOSTART, card.autofile_begin()); }
static void load();
static void save(const bool force=ENABLED(SAVE_EACH_CMD_MODE), const float zraise=0);
static void save(const bool force=ENABLED(SAVE_EACH_CMD_MODE), const float zraise=POWER_LOSS_ZRAISE, const bool raised=false);
#if PIN_EXISTS(POWER_LOSS)
static inline void outage() {

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

@ -78,8 +78,6 @@ void GcodeSuite::M125() {
// If possible, show an LCD prompt with the 'P' flag
const bool show_lcd = TERN0(HAS_LCD_MENU, parser.boolval('P'));
TERN_(POWER_LOSS_RECOVERY, if (recovery.enabled) recovery.save(true));
if (pause_print(retract, park_point, show_lcd, 0)) {
if (ENABLED(EXTENSIBLE_UI) || BOTH(EMERGENCY_PARSER, HOST_PROMPT_SUPPORT) || !sd_printing || show_lcd) {
wait_for_confirmation(false, 0);

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

@ -105,7 +105,7 @@ void GcodeSuite::M25() {
if (IS_SD_PRINTING()) card.pauseSDPrint();
#endif
#if ENABLED(POWER_LOSS_RECOVERY)
#if ENABLED(POWER_LOSS_RECOVERY) && DISABLED(DGUS_LCD_UI_MKS)
if (recovery.enabled) recovery.save(true);
#endif

2
Marlin/src/inc/SanityCheck.h

@ -2903,6 +2903,8 @@ static_assert( _ARR_TEST(3,0) && _ARR_TEST(3,1) && _ARR_TEST(3,2)
#error "POWER_LOSS_RECOVER_ZHOME cannot be used with Z_SAFE_HOMING."
#elif BOTH(POWER_LOSS_PULLUP, POWER_LOSS_PULLDOWN)
#error "You can't enable POWER_LOSS_PULLUP and POWER_LOSS_PULLDOWN at the same time."
#elif ENABLED(POWER_LOSS_RECOVER_ZHOME) && Z_HOME_DIR > 0
#error "POWER_LOSS_RECOVER_ZHOME is not needed on a machine that homes to ZMAX."
#elif BOTH(IS_CARTESIAN, POWER_LOSS_RECOVER_ZHOME) && Z_HOME_DIR < 0 && !defined(POWER_LOSS_ZHOME_POS)
#error "POWER_LOSS_RECOVER_ZHOME requires POWER_LOSS_ZHOME_POS for a Cartesian that homes to ZMIN."
#endif

10
Marlin/src/lcd/extui/dgus/mks/DGUSDisplayDef.cpp

@ -39,6 +39,10 @@
#include "../../../../module/stepper/trinamic.h"
#endif
#if ENABLED(POWER_LOSS_RECOVERY)
#include "../../../../../feature/powerloss.h"
#endif
#if ENABLED(DGUS_UI_MOVE_DIS_OPTION)
uint16_t distanceToMove = 10;
#endif
@ -78,8 +82,13 @@ constexpr feedRate_t park_speed_xy = TERN(NOZZLE_PARK_FEATURE, NOZZLE_PARK_XY_FE
void MKS_pause_print_move() {
queue.exhaust();
position_before_pause = current_position;
// Save the current position, the raise amount, and 'already raised'
TERN_(POWER_LOSS_RECOVERY, if (recovery.enabled) recovery.save(true, mks_park_pos.z, true));
destination.z = _MIN(current_position.z + mks_park_pos.z, Z_MAX_POS);
prepare_internal_move_to_destination(park_speed_z);
destination.set(X_MIN_POS + mks_park_pos.x, Y_MIN_POS + mks_park_pos.y);
prepare_internal_move_to_destination(park_speed_xy);
}
@ -89,6 +98,7 @@ void MKS_resume_print_move() {
prepare_internal_move_to_destination(park_speed_xy);
destination.z = position_before_pause.z;
prepare_internal_move_to_destination(park_speed_z);
TERN_(POWER_LOSS_RECOVERY, if (recovery.enabled) recovery.save(true));
}
float z_offset_add = 0;

8
buildroot/tests/rambo

@ -14,9 +14,9 @@ opt_set MOTHERBOARD BOARD_RAMBO \
EXTRUDERS 2 TEMP_SENSOR_0 -2 TEMP_SENSOR_1 1 TEMP_SENSOR_BED 2 \
TEMP_SENSOR_PROBE 1 TEMP_PROBE_PIN 12 \
TEMP_SENSOR_CHAMBER 3 TEMP_CHAMBER_PIN 3 HEATER_CHAMBER_PIN 45 \
Z_HOME_DIR 1 GRID_MAX_POINTS_X 16 \
GRID_MAX_POINTS_X 16 \
FANMUX0_PIN 53
opt_disable USE_ZMIN_PLUG Z_MIN_PROBE_USES_Z_MIN_ENDSTOP_PIN USE_WATCHDOG
opt_disable Z_MIN_PROBE_USES_Z_MIN_ENDSTOP_PIN USE_WATCHDOG
opt_enable USE_ZMAX_PLUG REPRAP_DISCOUNT_SMART_CONTROLLER LCD_PROGRESS_BAR LCD_PROGRESS_BAR_TEST \
FIX_MOUNTED_PROBE CODEPENDENT_XY_HOMING PIDTEMPBED PROBE_TEMP_COMPENSATION \
PREHEAT_BEFORE_PROBING PROBING_HEATERS_OFF PROBING_FANS_OFF PROBING_STEPPERS_OFF WAIT_FOR_BED_HEATER \
@ -32,7 +32,7 @@ opt_enable USE_ZMAX_PLUG REPRAP_DISCOUNT_SMART_CONTROLLER LCD_PROGRESS_BAR LCD_P
SKEW_CORRECTION SKEW_CORRECTION_FOR_Z SKEW_CORRECTION_GCODE \
BACKLASH_COMPENSATION BACKLASH_GCODE BAUD_RATE_GCODE BEZIER_CURVE_SUPPORT \
FWRETRACT ARC_P_CIRCLES CNC_WORKSPACE_PLANES CNC_COORDINATE_SYSTEMS \
PSU_CONTROL AUTO_POWER_CONTROL POWER_LOSS_RECOVERY POWER_LOSS_PIN POWER_LOSS_STATE POWER_LOSS_RECOVER_ZHOME \
PSU_CONTROL AUTO_POWER_CONTROL POWER_LOSS_RECOVERY POWER_LOSS_PIN POWER_LOSS_STATE POWER_LOSS_RECOVER_ZHOME POWER_LOSS_ZHOME_POS \
SLOW_PWM_HEATERS THERMAL_PROTECTION_CHAMBER LIN_ADVANCE EXTRA_LIN_ADVANCE_K \
HOST_ACTION_COMMANDS HOST_PROMPT_SUPPORT PINS_DEBUGGING MAX7219_DEBUG M114_DETAIL
opt_add DEBUG_POWER_LOSS_RECOVERY
@ -43,7 +43,7 @@ exec_test $1 $2 "RAMBO | EXTRUDERS 2 | CHAR LCD + SD | FIX Probe | ABL-Linear |
#
restore_configs
opt_set MOTHERBOARD BOARD_RAMBO \
EXTRUDERS 0 TEMP_SENSOR_0 999 DUMMY_THERMISTOR_999_VALUE 170 \
EXTRUDERS 0 TEMP_SENSOR_0 999 DUMMY_THERMISTOR_999_VALUE 170 Z_HOME_DIR 1 \
DIGIPOT_MOTOR_CURRENT '{ 120, 120, 120, 120, 120 }' \
LEVEL_CORNERS_LEVELING_ORDER '{ LF, RF }'
opt_enable USE_XMAX_PLUG USE_YMAX_PLUG USE_ZMAX_PLUG \

Loading…
Cancel
Save