Merge pull request #5493 from thinkyhead/rc_fix_recover_unhop

Prevent retract un-hop at wrong height
master
Scott Lahteine 8 years ago committed by GitHub
commit efb8b8425c

@ -2741,6 +2741,8 @@ static void homeaxis(AxisEnum axis) {
void retract(bool retracting, bool swapping = false) { void retract(bool retracting, bool swapping = false) {
static float hop_height;
if (retracting == retracted[active_extruder]) return; if (retracting == retracted[active_extruder]) return;
float old_feedrate_mm_s = feedrate_mm_s; float old_feedrate_mm_s = feedrate_mm_s;
@ -2755,14 +2757,19 @@ static void homeaxis(AxisEnum axis) {
prepare_move_to_destination(); prepare_move_to_destination();
if (retract_zlift > 0.01) { if (retract_zlift > 0.01) {
hop_height = current_position[Z_AXIS];
// Pretend current position is lower
current_position[Z_AXIS] -= retract_zlift; current_position[Z_AXIS] -= retract_zlift;
SYNC_PLAN_POSITION_KINEMATIC(); SYNC_PLAN_POSITION_KINEMATIC();
// Raise up to the old current_position
prepare_move_to_destination(); prepare_move_to_destination();
} }
} }
else { else {
if (retract_zlift > 0.01) { // If the height hasn't been altered, undo the Z hop
if (retract_zlift > 0.01 && hop_height == current_position[Z_AXIS]) {
// Pretend current position is higher. Z will lower on the next move
current_position[Z_AXIS] += retract_zlift; current_position[Z_AXIS] += retract_zlift;
SYNC_PLAN_POSITION_KINEMATIC(); SYNC_PLAN_POSITION_KINEMATIC();
} }
@ -2771,6 +2778,8 @@ static void homeaxis(AxisEnum axis) {
float move_e = swapping ? retract_length_swap + retract_recover_length_swap : retract_length + retract_recover_length; float move_e = swapping ? retract_length_swap + retract_recover_length_swap : retract_length + retract_recover_length;
current_position[E_AXIS] -= move_e / volumetric_multiplier[active_extruder]; current_position[E_AXIS] -= move_e / volumetric_multiplier[active_extruder];
sync_plan_position_e(); sync_plan_position_e();
// Lower Z and recover E
prepare_move_to_destination(); prepare_move_to_destination();
} }

Loading…
Cancel
Save