From 853a295762be4110703b902cf5c0b9da6f3d88ec Mon Sep 17 00:00:00 2001 From: kliment Date: Wed, 13 Apr 2011 11:17:56 +0200 Subject: Terminate current move after endstop hit - avoids lockup --- Tonokip_Firmware/Tonokip_Firmware.pde | 26 ++++++++++++++------------ 1 file changed, 14 insertions(+), 12 deletions(-) (limited to 'Tonokip_Firmware/Tonokip_Firmware.pde') diff --git a/Tonokip_Firmware/Tonokip_Firmware.pde b/Tonokip_Firmware/Tonokip_Firmware.pde index 21be99e..487ddbe 100644 --- a/Tonokip_Firmware/Tonokip_Firmware.pde +++ b/Tonokip_Firmware/Tonokip_Firmware.pde @@ -741,12 +741,6 @@ void linear_move(unsigned long x_steps_remaining, unsigned long y_steps_remainin if (destination_e > current_e) digitalWrite(E_DIR_PIN,!INVERT_E_DIR); else digitalWrite(E_DIR_PIN,INVERT_E_DIR); - //Only enable axis that are moving. If the axis doesn't need to move then it can stay disabled depending on configuration. - if(x_steps_remaining) enable_x(); - if(y_steps_remaining) enable_y(); - if(z_steps_remaining) { enable_z(); do_z_step(); z_steps_remaining--;} - if(e_steps_remaining) {enable_e(); do_e_step(); e_steps_remaining--;} - if(X_MIN_PIN > -1) if(!direction_x) if(digitalRead(X_MIN_PIN) != ENDSTOPS_INVERTING) x_steps_remaining=0; if(Y_MIN_PIN > -1) if(!direction_y) if(digitalRead(Y_MIN_PIN) != ENDSTOPS_INVERTING) y_steps_remaining=0; if(Z_MIN_PIN > -1) if(!direction_z) if(digitalRead(Z_MIN_PIN) != ENDSTOPS_INVERTING) z_steps_remaining=0; @@ -754,6 +748,14 @@ void linear_move(unsigned long x_steps_remaining, unsigned long y_steps_remainin if(Y_MAX_PIN > -1) if(direction_y) if(digitalRead(Y_MAX_PIN) != ENDSTOPS_INVERTING) y_steps_remaining=0; if(Z_MAX_PIN > -1) if(direction_z) if(digitalRead(Z_MAX_PIN) != ENDSTOPS_INVERTING) z_steps_remaining=0; + + //Only enable axis that are moving. If the axis doesn't need to move then it can stay disabled depending on configuration. + if(x_steps_remaining) enable_x(); + if(y_steps_remaining) enable_y(); + if(z_steps_remaining) { enable_z(); do_z_step(); z_steps_remaining--;} + if(e_steps_remaining) {enable_e(); do_e_step(); e_steps_remaining--;} + + previous_millis_heater = millis(); unsigned long start_move_micros = micros(); @@ -823,10 +825,10 @@ void linear_move(unsigned long x_steps_remaining, unsigned long y_steps_remainin if(x_steps_remaining || y_steps_remaining) { - if(X_MIN_PIN > -1) if(!direction_x) if(digitalRead(X_MIN_PIN) != ENDSTOPS_INVERTING) x_steps_remaining=0; - if(Y_MIN_PIN > -1) if(!direction_y) if(digitalRead(Y_MIN_PIN) != ENDSTOPS_INVERTING) y_steps_remaining=0; - if(X_MAX_PIN > -1) if(direction_x) if(digitalRead(X_MAX_PIN) != ENDSTOPS_INVERTING) x_steps_remaining=0; - if(Y_MAX_PIN > -1) if(direction_y) if(digitalRead(Y_MAX_PIN) != ENDSTOPS_INVERTING) y_steps_remaining=0; + if(X_MIN_PIN > -1) if(!direction_x) if(digitalRead(X_MIN_PIN) != ENDSTOPS_INVERTING) break; + if(Y_MIN_PIN > -1) if(!direction_y) if(digitalRead(Y_MIN_PIN) != ENDSTOPS_INVERTING) break; + if(X_MAX_PIN > -1) if(direction_x) if(digitalRead(X_MAX_PIN) != ENDSTOPS_INVERTING) break; + if(Y_MAX_PIN > -1) if(direction_y) if(digitalRead(Y_MAX_PIN) != ENDSTOPS_INVERTING) break; if(steep_y) { timediff = micros() - previous_micros_y; while(timediff >= interval && y_steps_remaining>0) { @@ -857,8 +859,8 @@ void linear_move(unsigned long x_steps_remaining, unsigned long y_steps_remainin } if(z_steps_remaining) { - if(Z_MIN_PIN > -1) if(!direction_z) if(digitalRead(Z_MIN_PIN) != ENDSTOPS_INVERTING) z_steps_remaining=0; - if(Z_MAX_PIN > -1) if(direction_z) if(digitalRead(Z_MAX_PIN) != ENDSTOPS_INVERTING) z_steps_remaining=0; + if(Z_MIN_PIN > -1) if(!direction_z) if(digitalRead(Z_MIN_PIN) != ENDSTOPS_INVERTING) break; + if(Z_MAX_PIN > -1) if(direction_z) if(digitalRead(Z_MAX_PIN) != ENDSTOPS_INVERTING) break; timediff=micros()-previous_micros_z; while(timediff >= z_interval && z_steps_remaining) { do_z_step(); z_steps_remaining--; timediff-=z_interval;} } -- cgit v1.2.1