Commit 77059690 authored by MagoKimbra's avatar MagoKimbra

Fix Delta Autocalibration

parent dda444c5
...@@ -188,7 +188,6 @@ ...@@ -188,7 +188,6 @@
// default settings // default settings
#define DEFAULT_AXIS_STEPS_PER_UNIT {80,80,3200,625,625,625,625} // X, Y, Z, E0, E1, E2, E3 default steps per unit #define DEFAULT_AXIS_STEPS_PER_UNIT {80,80,3200,625,625,625,625} // X, Y, Z, E0, E1, E2, E3 default steps per unit
#define DEFAULT_MAX_FEEDRATE {300,300,2,100,100,100,100} // X, Y, Z, E0, E1, E2, E3 (mm/sec) #define DEFAULT_MAX_FEEDRATE {300,300,2,100,100,100,100} // X, Y, Z, E0, E1, E2, E3 (mm/sec)
#define DEFAULT_RETRACTION_MAX_FEEDRATE {110,110,110,110} // E0, E1, E2, E3 (mm/sec)
#define DEFAULT_MAX_ACCELERATION {3000,3000,50,1000,1000,1000,1000} // X, Y, Z, E0, E1, E2, E3 maximum start speed for accelerated moves. #define DEFAULT_MAX_ACCELERATION {3000,3000,50,1000,1000,1000,1000} // X, Y, Z, E0, E1, E2, E3 maximum start speed for accelerated moves.
#define DEFAULT_ACCELERATION 2500 // X, Y, Z and E max acceleration in mm/s^2 for printing moves #define DEFAULT_ACCELERATION 2500 // X, Y, Z and E max acceleration in mm/s^2 for printing moves
......
...@@ -188,7 +188,6 @@ ...@@ -188,7 +188,6 @@
// default settings // default settings
#define DEFAULT_AXIS_STEPS_PER_UNIT {80,80,3200,625,625,625,625} // X, Y, Z, E0, E1, E2, E3 default steps per unit #define DEFAULT_AXIS_STEPS_PER_UNIT {80,80,3200,625,625,625,625} // X, Y, Z, E0, E1, E2, E3 default steps per unit
#define DEFAULT_MAX_FEEDRATE {300,300,2,100,100,100,100} // X, Y, Z, E0, E1, E2, E3 (mm/sec) #define DEFAULT_MAX_FEEDRATE {300,300,2,100,100,100,100} // X, Y, Z, E0, E1, E2, E3 (mm/sec)
#define DEFAULT_RETRACTION_MAX_FEEDRATE {110,110,110,110} // E0, E1, E2, E3 (mm/sec)
#define DEFAULT_MAX_ACCELERATION {3000,3000,50,1000,1000,1000,1000} // X, Y, Z, E0, E1, E2, E3 maximum start speed for accelerated moves. #define DEFAULT_MAX_ACCELERATION {3000,3000,50,1000,1000,1000,1000} // X, Y, Z, E0, E1, E2, E3 maximum start speed for accelerated moves.
#define DEFAULT_ACCELERATION 2500 // X, Y, Z and E max acceleration in mm/s^2 for printing moves #define DEFAULT_ACCELERATION 2500 // X, Y, Z and E max acceleration in mm/s^2 for printing moves
......
...@@ -47,7 +47,7 @@ ...@@ -47,7 +47,7 @@
#define Z_PROBE_RETRACT_START_LOCATION {0, 0, 30, 0} // X, Y, Z, E start location for z-probe retract sequence #define Z_PROBE_RETRACT_START_LOCATION {0, 0, 30, 0} // X, Y, Z, E start location for z-probe retract sequence
#define Z_PROBE_RETRACT_END_LOCATION {0, 0, 30, 0} // X, Y, Z, E end location for z-probe retract sequence #define Z_PROBE_RETRACT_END_LOCATION {0, 0, 30, 0} // X, Y, Z, E end location for z-probe retract sequence
#define Z_RAISE_BETWEEN_PROBINGS 2 // How much the extruder will be raised when travelling from between next probing points #define Z_RAISE_BETWEEN_PROBINGS 2 // How much the extruder will be raised when travelling from between next probing points
#define AUTOLEVEL_GRID 24 // Distance between autolevel Z probing points, should be less than print surface radius/3. #define AUTOLEVEL_GRID 20 // Distance between autolevel Z probing points, should be less than print surface radius/3.
//=========================================================================== //===========================================================================
//=============================Mechanical Settings=========================== //=============================Mechanical Settings===========================
...@@ -139,7 +139,6 @@ ...@@ -139,7 +139,6 @@
// delta speeds must be the same on xyz // delta speeds must be the same on xyz
#define DEFAULT_AXIS_STEPS_PER_UNIT {80,80,80,451,625,625,625} // X, Y, Z, E0, E1, E2, E3 #define DEFAULT_AXIS_STEPS_PER_UNIT {80,80,80,451,625,625,625} // X, Y, Z, E0, E1, E2, E3
#define DEFAULT_MAX_FEEDRATE {300,300,300,45,100,100,100} // X, Y, Z, E0, E1, E2, E3 (mm/sec) #define DEFAULT_MAX_FEEDRATE {300,300,300,45,100,100,100} // X, Y, Z, E0, E1, E2, E3 (mm/sec)
#define DEFAULT_RETRACTION_MAX_FEEDRATE {150,150,150,150} // E0, E1, E2, E3 (mm/sec)
#define DEFAULT_MAX_ACCELERATION {2000,2000,2000,1000,1000,1000,1000} // X, Y, Z, E0, E1, E2, E3 maximum start speed for accelerated moves. #define DEFAULT_MAX_ACCELERATION {2000,2000,2000,1000,1000,1000,1000} // X, Y, Z, E0, E1, E2, E3 maximum start speed for accelerated moves.
#define DEFAULT_ACCELERATION 1000 // X, Y, Z and E max acceleration in mm/s^2 for printing moves #define DEFAULT_ACCELERATION 1000 // X, Y, Z and E max acceleration in mm/s^2 for printing moves
......
...@@ -210,7 +210,6 @@ ...@@ -210,7 +210,6 @@
// default settings // default settings
#define DEFAULT_AXIS_STEPS_PER_UNIT {103.69,103.69,200/1.25,1000,1000,1000,1000} // X, Y, Z, E0, E1, E2, E3 #define DEFAULT_AXIS_STEPS_PER_UNIT {103.69,103.69,200/1.25,1000,1000,1000,1000} // X, Y, Z, E0, E1, E2, E3
#define DEFAULT_MAX_FEEDRATE {300,300,4,45,45,45,45} // X, Y, Z, E0, E1, E2, E3 (mm/sec) #define DEFAULT_MAX_FEEDRATE {300,300,4,45,45,45,45} // X, Y, Z, E0, E1, E2, E3 (mm/sec)
#define DEFAULT_RETRACTION_MAX_FEEDRATE {80,80,80,80} // E0, E1, E2, E3 (mm/sec)
#define DEFAULT_MAX_ACCELERATION {5000,5000,50,5000,5000,5000,5000} // X, Y, Z, E0, E1, E2, E3 maximum start speed for accelerated moves. #define DEFAULT_MAX_ACCELERATION {5000,5000,50,5000,5000,5000,5000} // X, Y, Z, E0, E1, E2, E3 maximum start speed for accelerated moves.
#define DEFAULT_ACCELERATION 400 // X, Y, Z and E max acceleration in mm/s^2 for printing moves #define DEFAULT_ACCELERATION 400 // X, Y, Z and E max acceleration in mm/s^2 for printing moves
......
...@@ -51,7 +51,6 @@ typedef unsigned long millis_t; ...@@ -51,7 +51,6 @@ typedef unsigned long millis_t;
#include "comunication.h" #include "comunication.h"
void get_command(); void get_command();
void process_commands();
void manage_inactivity(bool ignore_stepper_queue=false); void manage_inactivity(bool ignore_stepper_queue=false);
...@@ -138,6 +137,7 @@ void manage_inactivity(bool ignore_stepper_queue=false); ...@@ -138,6 +137,7 @@ void manage_inactivity(bool ignore_stepper_queue=false);
* X_HEAD and Y_HEAD is used for systems that don't have a 1:1 relationship between X_AXIS and X Head movement, like CoreXY bots. * X_HEAD and Y_HEAD is used for systems that don't have a 1:1 relationship between X_AXIS and X Head movement, like CoreXY bots.
*/ */
enum AxisEnum {X_AXIS=0, Y_AXIS=1, A_AXIS=0, B_AXIS=1, Z_AXIS=2, E_AXIS=3, X_HEAD=4, Y_HEAD=5}; enum AxisEnum {X_AXIS=0, Y_AXIS=1, A_AXIS=0, B_AXIS=1, Z_AXIS=2, E_AXIS=3, X_HEAD=4, Y_HEAD=5};
enum EndstopEnum {X_MIN=0, Y_MIN=1, Z_MIN=2, Z_PROBE=3, X_MAX=4, Y_MAX=5, Z_MAX=6}; enum EndstopEnum {X_MIN=0, Y_MIN=1, Z_MIN=2, Z_PROBE=3, X_MAX=4, Y_MAX=5, Z_MAX=6};
void enable_all_steppers(); void enable_all_steppers();
...@@ -160,9 +160,9 @@ void adjust_delta(float cartesian[3]); ...@@ -160,9 +160,9 @@ void adjust_delta(float cartesian[3]);
void prepare_move_raw(); void prepare_move_raw();
extern float delta[3]; extern float delta[3];
extern float delta_tmp[3]; extern float delta_tmp[3];
extern float delta_tower1_x,delta_tower1_y; extern float delta_tower1_x, delta_tower1_y;
extern float delta_tower2_x,delta_tower2_y; extern float delta_tower2_x, delta_tower2_y;
extern float delta_tower3_x,delta_tower3_y; extern float delta_tower3_x, delta_tower3_y;
#endif #endif
#ifdef SCARA #ifdef SCARA
void calculate_delta(float cartesian[3]); void calculate_delta(float cartesian[3]);
...@@ -241,6 +241,7 @@ extern float home_offset[3]; ...@@ -241,6 +241,7 @@ extern float home_offset[3];
extern float tower_adj[6]; extern float tower_adj[6];
extern float delta_radius; extern float delta_radius;
extern float delta_diagonal_rod; extern float delta_diagonal_rod;
extern float delta_segments_per_second;
#elif defined(Z_DUAL_ENDSTOPS) #elif defined(Z_DUAL_ENDSTOPS)
extern float z_endstop_adj; extern float z_endstop_adj;
#endif #endif
......
...@@ -336,7 +336,7 @@ bool target_direction; ...@@ -336,7 +336,7 @@ bool target_direction;
float delta_diagonal_rod; // = DEFAULT_DELTA_DIAGONAL_ROD; float delta_diagonal_rod; // = DEFAULT_DELTA_DIAGONAL_ROD;
float delta_diagonal_rod_2; float delta_diagonal_rod_2;
float delta_segments_per_second = DELTA_SEGMENTS_PER_SECOND; float delta_segments_per_second = DELTA_SEGMENTS_PER_SECOND;
float ac_prec = AUTOCALIBRATION_PRECISION / 2; float ac_prec = AUTOCALIBRATION_PRECISION;
float bed_radius = PRINTER_RADIUS; float bed_radius = PRINTER_RADIUS;
float delta_tower1_x, delta_tower1_y; float delta_tower1_x, delta_tower1_y;
float delta_tower2_x, delta_tower2_y; float delta_tower2_x, delta_tower2_y;
...@@ -458,6 +458,8 @@ bool target_direction; ...@@ -458,6 +458,8 @@ bool target_direction;
//================================ Functions ================================ //================================ Functions ================================
//=========================================================================== //===========================================================================
void process_next_command();
bool setTargetedHotend(int code); bool setTargetedHotend(int code);
#ifdef PREVENT_DANGEROUS_EXTRUDE #ifdef PREVENT_DANGEROUS_EXTRUDE
...@@ -766,17 +768,17 @@ void loop() { ...@@ -766,17 +768,17 @@ void loop() {
// Write the string from the read buffer to SD // Write the string from the read buffer to SD
card.write_command(command); card.write_command(command);
if (card.logging) if (card.logging)
process_commands(); // The card is saving because it's logging process_next_command(); // The card is saving because it's logging
else else
ECHO_L(OK); ECHO_L(OK);
} }
} }
else else
process_commands(); process_next_command();
#else #else
process_commands(); process_next_command();
#endif // SDSUPPORT #endif // SDSUPPORT
...@@ -790,6 +792,15 @@ void loop() { ...@@ -790,6 +792,15 @@ void loop() {
lcd_update(); lcd_update();
} }
void gcode_line_error(const char *err, bool doFlush = true) {
ECHO_S(ER);
PS_PGM(err);
ECHO_EV(gcode_LastN);
//Serial.println(gcode_N);
if (doFlush) FlushSerialRequestResend();
serial_count = 0;
}
/** /**
* Add to the circular command queue the next command from: * Add to the circular command queue the next command from:
* - The command-injection queue (queued_commands_P) * - The command-injection queue (queued_commands_P)
...@@ -810,23 +821,31 @@ void get_command() { ...@@ -810,23 +821,31 @@ void get_command() {
} }
#endif #endif
//
// Loop while serial characters are incoming and the queue is not full
//
while (MYSERIAL.available() > 0 && commands_in_queue < BUFSIZE) { while (MYSERIAL.available() > 0 && commands_in_queue < BUFSIZE) {
#ifdef NO_TIMEOUTS #ifdef NO_TIMEOUTS
last_command_time = ms; last_command_time = ms;
#endif #endif
serial_char = MYSERIAL.read(); serial_char = MYSERIAL.read();
if (serial_char == '\n' || serial_char == '\r' || //
serial_count >= (MAX_CMD_SIZE - 1) // If the character ends the line, or the line is full...
) { //
if (serial_char == '\n' || serial_char == '\r' || serial_count >= MAX_CMD_SIZE - 1) {
// end of line == end of comment // end of line == end of comment
comment_mode = false; comment_mode = false;
if (!serial_count) return; // shortcut for empty lines if (!serial_count) return; // empty lines just exit
char *command = command_queue[cmd_queue_index_w]; char *command = command_queue[cmd_queue_index_w];
command[serial_count] = 0; // terminate string command[serial_count] = 0; // terminate string
// this item in the queue is not from sd
#ifdef SDSUPPORT #ifdef SDSUPPORT
fromsd[cmd_queue_index_w] = false; fromsd[cmd_queue_index_w] = false;
#endif #endif
...@@ -835,9 +854,7 @@ void get_command() { ...@@ -835,9 +854,7 @@ void get_command() {
strchr_pointer = strchr(command, 'N'); strchr_pointer = strchr(command, 'N');
gcode_N = (strtol(strchr_pointer + 1, NULL, 10)); gcode_N = (strtol(strchr_pointer + 1, NULL, 10));
if (gcode_N != gcode_LastN + 1 && strstr_P(command, PSTR("M110")) == NULL) { if (gcode_N != gcode_LastN + 1 && strstr_P(command, PSTR("M110")) == NULL) {
ECHO_LMV(ER, MSG_ERR_LINE_NO, gcode_LastN); gcode_line_error(PSTR(MSG_ERR_LINE_NO));
FlushSerialRequestResend();
serial_count = 0;
return; return;
} }
...@@ -848,27 +865,22 @@ void get_command() { ...@@ -848,27 +865,22 @@ void get_command() {
strchr_pointer = strchr(command, '*'); strchr_pointer = strchr(command, '*');
if (strtol(strchr_pointer + 1, NULL, 10) != checksum) { if (strtol(strchr_pointer + 1, NULL, 10) != checksum) {
ECHO_LMV(ER, MSG_ERR_CHECKSUM_MISMATCH, gcode_LastN); gcode_line_error(PSTR(MSG_ERR_CHECKSUM_MISMATCH));
FlushSerialRequestResend();
serial_count = 0;
return; return;
} }
//if no errors, continue parsing // if no errors, continue parsing
} }
else { else {
ECHO_LMV(ER, MSG_ERR_NO_CHECKSUM, gcode_LastN); gcode_line_error(PSTR(MSG_ERR_NO_CHECKSUM));
FlushSerialRequestResend();
serial_count = 0;
return; return;
} }
gcode_LastN = gcode_N; gcode_LastN = gcode_N;
//if no errors, continue parsing // if no errors, continue parsing
} }
else { // if we don't receive 'N' but still see '*' else { // if we don't receive 'N' but still see '*'
if ((strchr(command, '*') != NULL)) { if ((strchr(command, '*') != NULL)) {
ECHO_LMV(ER, MSG_ERR_NO_LINENUMBER_WITH_CHECKSUM, gcode_LastN); gcode_line_error(PSTR(MSG_ERR_NO_LINENUMBER_WITH_CHECKSUM), false);
serial_count = 0;
return; return;
} }
} }
...@@ -899,7 +911,7 @@ void get_command() { ...@@ -899,7 +911,7 @@ void get_command() {
serial_count = 0; //clear buffer serial_count = 0; //clear buffer
} }
else if (serial_char == '\\') { // Handle escapes else if (serial_char == '\\') { // Handle escapes
if (MYSERIAL.available() > 0 && commands_in_queue < BUFSIZE) { if (MYSERIAL.available() > 0 && commands_in_queue < BUFSIZE) {
// if we have one more character, copy it over // if we have one more character, copy it over
serial_char = MYSERIAL.read(); serial_char = MYSERIAL.read();
command_queue[cmd_queue_index_w][serial_count++] = serial_char; command_queue[cmd_queue_index_w][serial_count++] = serial_char;
...@@ -1949,8 +1961,7 @@ static void setup_for_endstop_move() { ...@@ -1949,8 +1961,7 @@ static void setup_for_endstop_move() {
*/ */
} }
inline void delta_autocalibration(int iterations){ inline void delta_autocalibration(int iterations) {
//int iterations = 100; // Maximum number of iterations
int loopcount = 1; int loopcount = 1;
float adj_r_target, adj_dr_target; float adj_r_target, adj_dr_target;
float adj_r_target_delta = 0, adj_dr_target_delta = 0; float adj_r_target_delta = 0, adj_dr_target_delta = 0;
...@@ -1963,28 +1974,32 @@ static void setup_for_endstop_move() { ...@@ -1963,28 +1974,32 @@ static void setup_for_endstop_move() {
boolean adj_dr_allowed = true; boolean adj_dr_allowed = true;
float h_endstop = -100, l_endstop = 100; float h_endstop = -100, l_endstop = 100;
float probe_error, ftemp; float probe_error, ftemp;
float start_prec = 0.01;
ECHO_SMV(DB, "Starting Auto Calibration... Calibration precision: +/- ", ac_prec, 3); float saved_delta_diagonal_rod = delta_diagonal_rod;
ECHO_EMV("mm Total Iteration: ", iterations);
LCD_MESSAGEPGM("Auto Calibration...");
if (code_seen('D')) { if (code_seen('D')) {
delta_diagonal_rod = code_value(); delta_diagonal_rod = code_value();
adj_dr_allowed = false; adj_dr_allowed = false;
ECHO_SMV(DB, "Using diagional rod length: ", delta_diagonal_rod); ECHO_SMV(DB, "Using diagonal rod length: ", delta_diagonal_rod);
ECHO_EM("mm (will not be adjusted)"); ECHO_EM("mm (will not be adjusted)");
} }
ECHO_SMV(DB, "Starting Auto Calibration... Calibration precision: +/- ", ac_prec, 3);
ECHO_MV("mm Start Precision: +/- ", start_prec, 3);
ECHO_EMV("mm Total Iteration: ", iterations);
LCD_MESSAGEPGM("Auto Calibration...");
// First Check for control endstop // First Check for control endstop
ECHO_LM(DB, "First check for adjust Z-Height"); ECHO_LM(DB, "First check for adjust Z-Height");
home_delta_axis(); home_delta_axis();
deploy_z_probe(); deploy_z_probe();
//Probe all points //Probe all points
bed_probe_all(); bed_probe_all();
//Show calibration report
//Show calibration report
calibration_report(); calibration_report();
//Check that endstop are within limits //Check that endstop are within limits
if (bed_level_x + endstop_adj[0] > h_endstop) h_endstop = bed_level_x + endstop_adj[0]; if (bed_level_x + endstop_adj[0] > h_endstop) h_endstop = bed_level_x + endstop_adj[0];
if (bed_level_x + endstop_adj[0] < l_endstop) l_endstop = bed_level_x + endstop_adj[0]; if (bed_level_x + endstop_adj[0] < l_endstop) l_endstop = bed_level_x + endstop_adj[0];
...@@ -2011,6 +2026,8 @@ static void setup_for_endstop_move() { ...@@ -2011,6 +2026,8 @@ static void setup_for_endstop_move() {
do { do {
ECHO_LMV(DB, "Iteration: ", loopcount); ECHO_LMV(DB, "Iteration: ", loopcount);
ECHO_SMV(DB, "Precision: +/- ", start_prec, 3);
ECHO_EM("mm");
if ((bed_level_c > 3) or (bed_level_c < -3)) { if ((bed_level_c > 3) or (bed_level_c < -3)) {
//Build height is not set correctly .. //Build height is not set correctly ..
...@@ -2020,7 +2037,7 @@ static void setup_for_endstop_move() { ...@@ -2020,7 +2037,7 @@ static void setup_for_endstop_move() {
ECHO_EM(" mm.."); ECHO_EM(" mm..");
} }
else { else {
if ((bed_level_x < -ac_prec) or (bed_level_x > ac_prec) or (bed_level_y < -ac_prec) or (bed_level_y > ac_prec) or (bed_level_z < -ac_prec) or (bed_level_z > ac_prec)) { if ((bed_level_x < -start_prec) or (bed_level_x > start_prec) or (bed_level_y < -start_prec) or (bed_level_y > start_prec) or (bed_level_z < -start_prec) or (bed_level_z > start_prec)) {
//Endstop req adjustment //Endstop req adjustment
ECHO_LM(DB, "Adjusting Endstop.."); ECHO_LM(DB, "Adjusting Endstop..");
endstop_adj[0] += bed_level_x / 1.05; endstop_adj[0] += bed_level_x / 1.05;
...@@ -2049,15 +2066,16 @@ static void setup_for_endstop_move() { ...@@ -2049,15 +2066,16 @@ static void setup_for_endstop_move() {
adj_dr_target = (bed_level_ox + bed_level_oy + bed_level_oz) / 3; adj_dr_target = (bed_level_ox + bed_level_oy + bed_level_oz) / 3;
//Determine which parameters require adjustment //Determine which parameters require adjustment
if ((bed_level_c >= adj_r_target - ac_prec) and (bed_level_c <= adj_r_target + ac_prec)) adj_r_done = true; if ((bed_level_c >= adj_r_target - start_prec) and (bed_level_c <= adj_r_target + start_prec)) adj_r_done = true;
else adj_r_done = false; else adj_r_done = false;
if ((adj_dr_target >= adj_r_target - ac_prec) and (adj_dr_target <= adj_r_target + ac_prec)) adj_dr_done = true; if ((adj_dr_target >= adj_r_target - start_prec) and (adj_dr_target <= adj_r_target + start_prec)) adj_dr_done = true;
else adj_dr_done = false; else adj_dr_done = false;
if ((bed_level_x != bed_level_ox) or (bed_level_y != bed_level_oy) or (bed_level_z != bed_level_oz)) adj_tower_done = false; if ((bed_level_x != bed_level_ox) or (bed_level_y != bed_level_oy) or (bed_level_z != bed_level_oz)) adj_tower_done = false;
else adj_tower_done = true; else adj_tower_done = true;
if ((adj_r_done == false) or (adj_dr_done == false) or (adj_tower_done == false)) { if ((adj_r_done == false) or (adj_dr_done == false) or (adj_tower_done == false)) {
//delta geometry adjustment required //delta geometry adjustment required
ECHO_LM(DB, "Adjusting Delta Geometry.."); ECHO_LM(DB, "Adjusting Delta Geometry..");
//set initial direction and magnitude for delta radius & diagonal rod adjustment //set initial direction and magnitude for delta radius & diagonal rod adjustment
if (adj_r == 0) { if (adj_r == 0) {
if (adj_r_target > bed_level_c) adj_r = 1; if (adj_r_target > bed_level_c) adj_r = 1;
...@@ -2083,6 +2101,7 @@ static void setup_for_endstop_move() { ...@@ -2083,6 +2101,7 @@ static void setup_for_endstop_move() {
} }
if (adj_dr_allowed == false) adj_dr_done = true; if (adj_dr_allowed == false) adj_dr_done = true;
if (adj_dr_done == false) { if (adj_dr_done == false) {
ECHO_SMV(DB, "Adjusting Diagonal Rod Length (", delta_diagonal_rod); ECHO_SMV(DB, "Adjusting Diagonal Rod Length (", delta_diagonal_rod);
ECHO_MV(" -> ", delta_diagonal_rod + adj_dr); ECHO_MV(" -> ", delta_diagonal_rod + adj_dr);
...@@ -2104,19 +2123,19 @@ static void setup_for_endstop_move() { ...@@ -2104,19 +2123,19 @@ static void setup_for_endstop_move() {
//Check to see if auto calc is complete to within limits.. //Check to see if auto calc is complete to within limits..
if (adj_dr_allowed == true) { if (adj_dr_allowed == true) {
if ((bed_level_x >= -ac_prec) and (bed_level_x <= ac_prec) if ((bed_level_x >= -start_prec) and (bed_level_x <= start_prec)
and (bed_level_y >= -ac_prec) and (bed_level_y <= ac_prec) and (bed_level_y >= -start_prec) and (bed_level_y <= start_prec)
and (bed_level_z >= -ac_prec) and (bed_level_z <= ac_prec) and (bed_level_z >= -start_prec) and (bed_level_z <= start_prec)
and (bed_level_c >= -ac_prec) and (bed_level_c <= ac_prec) and (bed_level_c >= -start_prec) and (bed_level_c <= start_prec)
and (bed_level_ox >= -ac_prec) and (bed_level_ox <= ac_prec) and (bed_level_ox >= -start_prec) and (bed_level_ox <= start_prec)
and (bed_level_oy >= -ac_prec) and (bed_level_oy <= ac_prec) and (bed_level_oy >= -start_prec) and (bed_level_oy <= start_prec)
and (bed_level_oz >= -ac_prec) and (bed_level_oz <= ac_prec)) loopcount = iterations; and (bed_level_oz >= -start_prec) and (bed_level_oz <= start_prec)) loopcount = iterations;
} }
else { else {
if ((bed_level_x >= -ac_prec) and (bed_level_x <= ac_prec) if ((bed_level_x >= -start_prec) and (bed_level_x <= start_prec)
and (bed_level_y >= -ac_prec) and (bed_level_y <= ac_prec) and (bed_level_y >= -start_prec) and (bed_level_y <= start_prec)
and (bed_level_z >= -ac_prec) and (bed_level_z <= ac_prec) and (bed_level_z >= -start_prec) and (bed_level_z <= start_prec)
and (bed_level_c >= -ac_prec) and (bed_level_c <= ac_prec)) loopcount = iterations; and (bed_level_c >= -start_prec) and (bed_level_c <= start_prec)) loopcount = iterations;
} }
//set delta radius and diagonal rod targets //set delta radius and diagonal rod targets
...@@ -2178,7 +2197,7 @@ static void setup_for_endstop_move() { ...@@ -2178,7 +2197,7 @@ static void setup_for_endstop_move() {
if (bed_level_z < bed_level_oz) adj_RadiusC = 0.5; if (bed_level_z < bed_level_oz) adj_RadiusC = 0.5;
if (bed_level_z > bed_level_oz) adj_RadiusC = -0.5; if (bed_level_z > bed_level_oz) adj_RadiusC = -0.5;
#ifdef DEBUG_MESSAGES #ifdef DEBUG_MESSAGES
ECHO_LMV(DB, "adj_RadiusC set to ",adj_RadiusC); ECHO_LMV(DB, "adj_RadiusC set to ", adj_RadiusC);
#endif #endif
} }
} }
...@@ -2190,7 +2209,7 @@ static void setup_for_endstop_move() { ...@@ -2190,7 +2209,7 @@ static void setup_for_endstop_move() {
if (bed_level_x < bed_level_ox) adj_RadiusA = 0.5; if (bed_level_x < bed_level_ox) adj_RadiusA = 0.5;
if (bed_level_x > bed_level_ox) adj_RadiusA = -0.5; if (bed_level_x > bed_level_ox) adj_RadiusA = -0.5;
#ifdef DEBUG_MESSAGES #ifdef DEBUG_MESSAGES
ECHO_LMV(DB, "adj_RadiusA set to ",adj_RadiusA); ECHO_LMV(DB, "adj_RadiusA set to ", adj_RadiusA);
#endif #endif
} }
} }
...@@ -2202,7 +2221,7 @@ static void setup_for_endstop_move() { ...@@ -2202,7 +2221,7 @@ static void setup_for_endstop_move() {
if (bed_level_y < bed_level_oy) adj_RadiusB = 0.5; if (bed_level_y < bed_level_oy) adj_RadiusB = 0.5;
if (bed_level_y > bed_level_oy) adj_RadiusB = -0.5; if (bed_level_y > bed_level_oy) adj_RadiusB = -0.5;
#ifdef DEBUG_MESSAGES #ifdef DEBUG_MESSAGES
ECHO_LMV(DB, "adj_RadiusB set to ",adj_RadiusB); ECHO_LMV(DB, "adj_RadiusB set to ", adj_RadiusB);
#endif #endif
} }
} }
...@@ -2223,11 +2242,11 @@ static void setup_for_endstop_move() { ...@@ -2223,11 +2242,11 @@ static void setup_for_endstop_move() {
if (((adj_RadiusC > 0) and (bed_level_z > bed_level_oz)) or ((adj_RadiusC < 0) and (bed_level_z < bed_level_oz))) adj_RadiusC = -(adj_RadiusC / 2); if (((adj_RadiusC > 0) and (bed_level_z > bed_level_oz)) or ((adj_RadiusC < 0) and (bed_level_z < bed_level_oz))) adj_RadiusC = -(adj_RadiusC / 2);
//Delta radius adjustment complete? //Delta radius adjustment complete?
if ((bed_level_c >= (adj_r_target - ac_prec)) and (bed_level_c <= (adj_r_target + ac_prec))) adj_r_done = true; if ((bed_level_c >= (adj_r_target - start_prec)) and (bed_level_c <= (adj_r_target + start_prec))) adj_r_done = true;
else adj_r_done = false; else adj_r_done = false;
//Diag Rod adjustment complete? //Diag Rod adjustment complete?
if ((adj_dr_target >= (adj_r_target - ac_prec)) and (adj_dr_target <= (adj_r_target + ac_prec))) adj_dr_done = true; if ((adj_dr_target >= (adj_r_target - start_prec)) and (adj_dr_target <= (adj_r_target + start_prec))) adj_dr_done = true;
else adj_dr_done = false; else adj_dr_done = false;
#ifdef DEBUG_MESSAGES #ifdef DEBUG_MESSAGES
...@@ -2238,27 +2257,30 @@ static void setup_for_endstop_move() { ...@@ -2238,27 +2257,30 @@ static void setup_for_endstop_move() {
ECHO_MV(" ox: ", bed_level_ox); ECHO_MV(" ox: ", bed_level_ox);
ECHO_MV(" oy: ", bed_level_oy); ECHO_MV(" oy: ", bed_level_oy);
ECHO_EMV(" oz: ", bed_level_oz); ECHO_EMV(" oz: ", bed_level_oz);
ECHO_EMV("radius:", delta_radius, 4); ECHO_SMV(DB, "radius:", delta_radius, 4);
ECHO_EMV(" diagrod:", delta_diagonal_rod, 4); ECHO_EMV(" diagonal rod:", delta_diagonal_rod, 4);
ECHO_SM(DB, "Radius Adj Complete: "); ECHO_SM(DB, "Radius Adj Complete: ");
if (adj_r_done == true) ECHO_M("Yes"); if (adj_r_done == true) ECHO_M("Yes");
else ECHO_M("No"); else ECHO_M("No");
ECHO_M(" DiagRod Adj Complete: "); ECHO_M(" Diagonal Rod Adj Complete: ");
if (adj_dr_done == true) ECHO_EM("Yes"); if (adj_dr_done == true) ECHO_EM("Yes");
else ECHO_EM("No"); else ECHO_EM("No");
ECHO_SMV(DB, "RadiusA Error: ",radiusErrorA); ECHO_SMV(DB, "RadiusA Error: ", radiusErrorA);
ECHO_MV(" (adjust: ",adj_RadiusA); ECHO_MV(" (adjust: ", adj_RadiusA);
ECHO_EM(")"); ECHO_EM(")");
ECHO_SMV(DB, "RadiusB Error: ",radiusErrorB); ECHO_SMV(DB, "RadiusB Error: ", radiusErrorB);
ECHO_MV(" (adjust: ",adj_RadiusB); ECHO_MV(" (adjust: ", adj_RadiusB);
ECHO_EM(")"); ECHO_EM(")");
ECHO_SMV(DB, "RadiusC Error: ",radiusErrorC); ECHO_SMV(DB, "RadiusC Error: ", radiusErrorC);
ECHO_MV(" (adjust: ",adj_RadiusC); ECHO_MV(" (adjust: ", adj_RadiusC);
ECHO_EM(")"); ECHO_EM(")");
ECHO_LMV(DB, "DeltaAlphaA: ",adj_AlphaA); ECHO_LMV(DB, "DeltaAlphaA: ", adj_AlphaA);
ECHO_LMV(DB, "DeltaAlphaB: ",adj_AlphaB); ECHO_LMV(DB, "DeltaAlphaB: ", adj_AlphaB);
ECHO_LMV(DB, "DeltaAlphaC: ",adj_AlphaC); ECHO_LMV(DB, "DeltaAlphaC: ", adj_AlphaC);
#endif #endif
//if (start_prec < ac_prec) start_prec += 0.01;
} while (((adj_r_done == false) or (adj_dr_done = false)) and (loopcount < iterations)); } while (((adj_r_done == false) or (adj_dr_done = false)) and (loopcount < iterations));
} }
else { else {
...@@ -2276,23 +2298,24 @@ static void setup_for_endstop_move() { ...@@ -2276,23 +2298,24 @@ static void setup_for_endstop_move() {
//Check to see if autocalc is complete to within limits.. //Check to see if autocalc is complete to within limits..
if (adj_dr_allowed == true) { if (adj_dr_allowed == true) {
if ((bed_level_x >= -ac_prec) and (bed_level_x <= ac_prec) if ((bed_level_x >= -start_prec) and (bed_level_x <= start_prec)
and (bed_level_y >= -ac_prec) and (bed_level_y <= ac_prec) and (bed_level_y >= -start_prec) and (bed_level_y <= start_prec)
and (bed_level_z >= -ac_prec) and (bed_level_z <= ac_prec) and (bed_level_z >= -start_prec) and (bed_level_z <= start_prec)
and (bed_level_c >= -ac_prec) and (bed_level_c <= ac_prec) and (bed_level_c >= -start_prec) and (bed_level_c <= start_prec)
and (bed_level_ox >= -ac_prec) and (bed_level_ox <= ac_prec) and (bed_level_ox >= -start_prec) and (bed_level_ox <= start_prec)
and (bed_level_oy >= -ac_prec) and (bed_level_oy <= ac_prec) and (bed_level_oy >= -start_prec) and (bed_level_oy <= start_prec)
and (bed_level_oz >= -ac_prec) and (bed_level_oz <= ac_prec)) loopcount = iterations; and (bed_level_oz >= -start_prec) and (bed_level_oz <= start_prec)) loopcount = iterations;
} }
else { else {
if ((bed_level_x >= -ac_prec) and (bed_level_x <= ac_prec) if ((bed_level_x >= -start_prec) and (bed_level_x <= start_prec)
and (bed_level_y >= -ac_prec) and (bed_level_y <= ac_prec) and (bed_level_y >= -start_prec) and (bed_level_y <= start_prec)
and (bed_level_z >= -ac_prec) and (bed_level_z <= ac_prec) and (bed_level_z >= -start_prec) and (bed_level_z <= start_prec)
and (bed_level_c >= -ac_prec) and (bed_level_c <= ac_prec)) loopcount = iterations; and (bed_level_c >= -start_prec) and (bed_level_c <= start_prec)) loopcount = iterations;
} }
} }
loopcount ++; loopcount ++;
if (start_prec < ac_prec) start_prec += 0.01;
manage_heater(); manage_heater();
manage_inactivity(); manage_inactivity();
...@@ -2303,21 +2326,15 @@ static void setup_for_endstop_move() { ...@@ -2303,21 +2326,15 @@ static void setup_for_endstop_move() {
ECHO_LM(DB, "Auto Calibration Complete"); ECHO_LM(DB, "Auto Calibration Complete");
LCD_MESSAGEPGM("Complete"); LCD_MESSAGEPGM("Complete");
ECHO_LM(DB, "Issue M500 Command to save calibration settings to EPROM (if enabled)"); ECHO_LM(DB, "Issue M500 Command to save calibration settings to EPROM (if enabled)");
/*
if ((abs(delta_diagonal_rod - saved_delta_diagonal_rod) > 1) and (adj_dr_allowed == true)) {
ECHO_SMV(DB, "WARNING: The length of diagonal rods specified (", saved_delta_diagonal_rod);
ECHO_EV(" mm) appears to be incorrect");
ECHO_LM(DB, "If you have measured your rods and you believe that this value is correct, this could indicate");
ECHO_LM(DB,"excessive twisting movement of carriages and/or loose screws/joints on carriages or end effector");
}
*/
retract_z_probe(); if ((abs(delta_diagonal_rod - saved_delta_diagonal_rod) > 1) and (adj_dr_allowed == true)) {
ECHO_SMV(DB, "WARNING: The length of diagonal rods specified (", saved_delta_diagonal_rod);
ECHO_EV(" mm) appears to be incorrect");
ECHO_LM(DB, "If you have measured your rods and you believe that this value is correct, this could indicate");
ECHO_LM(DB,"excessive twisting movement of carriages and/or loose screws/joints on carriages or end effector");
}
//Restore saved variables retract_z_probe();
feedrate = saved_feedrate;
feedrate_multiplier = saved_feedrate_multiplier;
return;
} }
#endif //DELTA #endif //DELTA
...@@ -3542,22 +3559,10 @@ inline void gcode_G28(boolean home_x = false, boolean home_y = false) { ...@@ -3542,22 +3559,10 @@ inline void gcode_G28(boolean home_x = false, boolean home_y = false) {
feedrate_multiplier = 100; feedrate_multiplier = 100;
if (code_seen('A')) { if (code_seen('A')) {
if (code_has_value()) ac_prec = (float)(code_value() / 2); if (code_has_value()) ac_prec = code_value();
delta_autocalibration(iterations); delta_autocalibration(iterations);
return;
} }
home_delta_axis();
deploy_z_probe();
//Probe all points
bed_probe_all();
//Show calibration report
calibration_report();
retract_z_probe();
//reset LCD alert message //reset LCD alert message
lcd_reset_alert_level(); lcd_reset_alert_level();
...@@ -4484,15 +4489,16 @@ inline void gcode_M115() { ...@@ -4484,15 +4489,16 @@ inline void gcode_M115() {
ECHO_M(MSG_M115_REPORT); ECHO_M(MSG_M115_REPORT);
} }
/** #ifdef ULTIPANEL
* M117: Set LCD Status Message
*/ /**
inline void gcode_M117() { * M117: Set LCD Status Message
char* codepos = strchr_pointer + 5; */
char* starpos = strchr(codepos, '*'); inline void gcode_M117() {
if (starpos) *starpos = '\0'; lcd_setstatus(strchr_pointer + 5);
lcd_setstatus(codepos); }
}
#endif
/** /**
* M119: Output endstop states to serial output * M119: Output endstop states to serial output
...@@ -6049,11 +6055,11 @@ inline void gcode_T() { ...@@ -6049,11 +6055,11 @@ inline void gcode_T() {
} }
} }
/**
/***************************************************** * Process Commands and dispatch them to handlers
*** Process Commands and dispatch them to handlers *** * This is called from the main loop()
******************************************************/ */
void process_commands() { void process_next_command() {
if ((debugLevel & DEBUG_ECHO)) { if ((debugLevel & DEBUG_ECHO)) {
ECHO_LV(DB, command_queue[cmd_queue_index_r]); ECHO_LV(DB, command_queue[cmd_queue_index_r]);
...@@ -6203,7 +6209,7 @@ void process_commands() { ...@@ -6203,7 +6209,7 @@ void process_commands() {
gcode_M18_M84(); break; gcode_M18_M84(); break;
case 85: // M85 case 85: // M85
gcode_M85(); break; gcode_M85(); break;
case 92: // M92 case 92: // M92 Set the steps-per-unit for one or more axes
gcode_M92(); break; gcode_M92(); break;
case 104: // M104 case 104: // M104
gcode_M104(); break; gcode_M104(); break;
...@@ -6223,18 +6229,22 @@ void process_commands() { ...@@ -6223,18 +6229,22 @@ void process_commands() {
gcode_M111(); break; gcode_M111(); break;
case 112: // M112 Emergency Stop case 112: // M112 Emergency Stop
gcode_M112(); break; gcode_M112(); break;
case 114: // M114 case 114: // M114 Report current position
gcode_M114(); break; gcode_M114(); break;
case 115: // M115 case 115: // M115 Report capabilities
gcode_M115(); break; gcode_M115(); break;
case 117: // M117 display message
gcode_M117(); break; #ifdef ULTIPANEL
case 119: // M119 case 117: // M117 display message
gcode_M119(); break; gcode_M117(); break;
case 120: // M120 #endif
case 119: // M119 Report endstop states
gcode_M119(); break;
case 120: // M120 Enable endstops
gcode_M120(); break; gcode_M120(); break;
case 121: // M121 case 121: // M121 Disable endstops
gcode_M121(); break; gcode_M121(); break;
#ifdef BARICUDA #ifdef BARICUDA
// PWM for HEATER_1_PIN // PWM for HEATER_1_PIN
......
...@@ -14,15 +14,14 @@ ...@@ -14,15 +14,14 @@
* *
*/ */
#define EEPROM_VERSION "V21" #define EEPROM_VERSION "V22"
/** /**
* V21 EEPROM Layout: * V22 EEPROM Layout:
* *
* ver * ver
* M92 XYZ E0 E1 E2 E3 axis_steps_per_unit (x7) * M92 XYZ E0 E1 E2 E3 axis_steps_per_unit (x7)
* M203 XYZ E0 E1 E2 E3 max_feedrate (x7) * M203 XYZ E0 E1 E2 E3 max_feedrate (x7)
* M??? E0 E1 E2 E3 retraction_feedrate (x4)
* M201 XYZ E0 E1 E2 E3 max_acceleration_units_per_sq_second (x7) * M201 XYZ E0 E1 E2 E3 max_acceleration_units_per_sq_second (x7)
* M204 P acceleration * M204 P acceleration
* M204 R retract_acceleration * M204 R retract_acceleration
...@@ -45,7 +44,7 @@ ...@@ -45,7 +44,7 @@
* M666 R delta_radius * M666 R delta_radius
* M666 D delta_diagonal_rod * M666 D delta_diagonal_rod
* M666 H Z max_pos * M666 H Z max_pos
* M666 P z_probe_offset * M666 P XYZ XYZ probe_offset (x3)
* *
* Z_DUAL_ENDSTOPS * Z_DUAL_ENDSTOPS
* M666 Z z_endstop_adj * M666 Z z_endstop_adj
...@@ -127,17 +126,16 @@ void _EEPROM_readData(int &pos, uint8_t* value, uint8_t size) { ...@@ -127,17 +126,16 @@ void _EEPROM_readData(int &pos, uint8_t* value, uint8_t size) {
#define EEPROM_WRITE_VAR(pos, value) _EEPROM_writeData(pos, (uint8_t*)&value, sizeof(value)) #define EEPROM_WRITE_VAR(pos, value) _EEPROM_writeData(pos, (uint8_t*)&value, sizeof(value))
#define EEPROM_READ_VAR(pos, value) _EEPROM_readData(pos, (uint8_t*)&value, sizeof(value)) #define EEPROM_READ_VAR(pos, value) _EEPROM_readData(pos, (uint8_t*)&value, sizeof(value))
/**
* Store Configuration Settings - M500
*/
#define DUMMY_PID_VALUE 3000.0f #define DUMMY_PID_VALUE 3000.0f
#define EEPROM_OFFSET 100 #define EEPROM_OFFSET 100
#define LIFETIME_EEPROM_OFFSET 600
#define LIFETIME_MAGIC "L99"
#ifdef EEPROM_SETTINGS #ifdef EEPROM_SETTINGS
/**
* Store Configuration Settings - M500
*/
void Config_StoreSettings() { void Config_StoreSettings() {
float dummy = 0.0f; float dummy = 0.0f;
char ver[4] = "000"; char ver[4] = "000";
...@@ -145,7 +143,6 @@ void Config_StoreSettings() { ...@@ -145,7 +143,6 @@ void Config_StoreSettings() {
EEPROM_WRITE_VAR(i, ver); // invalidate data first EEPROM_WRITE_VAR(i, ver); // invalidate data first
EEPROM_WRITE_VAR(i, axis_steps_per_unit); EEPROM_WRITE_VAR(i, axis_steps_per_unit);
EEPROM_WRITE_VAR(i, max_feedrate); EEPROM_WRITE_VAR(i, max_feedrate);
EEPROM_WRITE_VAR(i, max_retraction_feedrate);
EEPROM_WRITE_VAR(i, max_acceleration_units_per_sq_second); EEPROM_WRITE_VAR(i, max_acceleration_units_per_sq_second);
EEPROM_WRITE_VAR(i, acceleration); EEPROM_WRITE_VAR(i, acceleration);
EEPROM_WRITE_VAR(i, retract_acceleration); EEPROM_WRITE_VAR(i, retract_acceleration);
...@@ -293,7 +290,6 @@ void Config_RetrieveSettings() { ...@@ -293,7 +290,6 @@ void Config_RetrieveSettings() {
// version number match // version number match
EEPROM_READ_VAR(i, axis_steps_per_unit); EEPROM_READ_VAR(i, axis_steps_per_unit);
EEPROM_READ_VAR(i, max_feedrate); EEPROM_READ_VAR(i, max_feedrate);
EEPROM_READ_VAR(i, max_retraction_feedrate);
EEPROM_READ_VAR(i, max_acceleration_units_per_sq_second); EEPROM_READ_VAR(i, max_acceleration_units_per_sq_second);
// steps per sq second need to be updated to agree with the units per sq second (as they are what is used in the planner) // steps per sq second need to be updated to agree with the units per sq second (as they are what is used in the planner)
...@@ -441,36 +437,33 @@ void Config_RetrieveSettings() { ...@@ -441,36 +437,33 @@ void Config_RetrieveSettings() {
* Reset Configuration Settings - M502 * Reset Configuration Settings - M502
*/ */
void Config_ResetDefault() { void Config_ResetDefault() {
float tmp1[] = DEFAULT_AXIS_STEPS_PER_UNIT; float tmp1[] = DEFAULT_AXIS_STEPS_PER_UNIT;
float tmp2[] = DEFAULT_MAX_FEEDRATE; float tmp2[] = DEFAULT_MAX_FEEDRATE;
float tmp3[] = DEFAULT_RETRACTION_MAX_FEEDRATE; long tmp3[] = DEFAULT_MAX_ACCELERATION;
long tmp4[] = DEFAULT_MAX_ACCELERATION;
#ifdef PIDTEMP #ifdef PIDTEMP
float tmp5[] = DEFAULT_Kp; float tmp4[] = DEFAULT_Kp;
float tmp6[] = DEFAULT_Ki; float tmp5[] = DEFAULT_Ki;
float tmp7[] = DEFAULT_Kd; float tmp6[] = DEFAULT_Kd;
#endif // PIDTEMP #endif // PIDTEMP
#if defined(HOTEND_OFFSET_X) && defined(HOTEND_OFFSET_Y) #if defined(HOTEND_OFFSET_X) && defined(HOTEND_OFFSET_Y)
float tmp8[] = HOTEND_OFFSET_X; float tmp7[] = HOTEND_OFFSET_X;
float tmp9[] = HOTEND_OFFSET_Y; float tmp8[] = HOTEND_OFFSET_Y;
#else #else
float tmp7[] = {0,0,0,0};
float tmp8[] = {0,0,0,0}; float tmp8[] = {0,0,0,0};
float tmp9[] = {0,0,0,0};
#endif #endif
for (int i = 0; i < 3 + EXTRUDERS; i++) { for (int i = 0; i < 3 + EXTRUDERS; i++) {
axis_steps_per_unit[i] = tmp1[i]; axis_steps_per_unit[i] = tmp1[i];
max_feedrate[i] = tmp2[i]; max_feedrate[i] = tmp2[i];
max_acceleration_units_per_sq_second[i] = tmp4[i]; max_acceleration_units_per_sq_second[i] = tmp3[i];
} }
for (int i = 0; i < EXTRUDERS; i++) { for (int i = 0; i < EXTRUDERS; i++) {
max_retraction_feedrate[i] = tmp3[i];
#if HOTENDS > 1 #if HOTENDS > 1
hotend_offset[X_AXIS][i] = tmp8[i]; hotend_offset[X_AXIS][i] = tmp7[i];
hotend_offset[Y_AXIS][i] = tmp9[i]; hotend_offset[Y_AXIS][i] = tmp8[i];
#endif #endif
#ifdef SCARA #ifdef SCARA
if (i < sizeof(axis_scaling) / sizeof(*axis_scaling)) if (i < sizeof(axis_scaling) / sizeof(*axis_scaling))
...@@ -527,9 +520,9 @@ void Config_ResetDefault() { ...@@ -527,9 +520,9 @@ void Config_ResetDefault() {
#ifdef PIDTEMP #ifdef PIDTEMP
for (int e = 0; e < HOTENDS; e++) for (int e = 0; e < HOTENDS; e++)
{ {
Kp[e] = tmp5[e]; Kp[e] = tmp4[e];
Ki[e] = scalePID_i(tmp6[e]); Ki[e] = scalePID_i(tmp5[e]);
Kd[e] = scalePID_d(tmp7[e]); Kd[e] = scalePID_d(tmp6[e]);
} }
// call updatePID (similar to when we have processed M301) // call updatePID (similar to when we have processed M301)
updatePID(); updatePID();
...@@ -623,21 +616,6 @@ void Config_PrintSettings(bool forReplay) { ...@@ -623,21 +616,6 @@ void Config_PrintSettings(bool forReplay) {
#endif //EXTRUDERS > 1 #endif //EXTRUDERS > 1
ECHO_E; ECHO_E;
if (!forReplay) {
ECHO_LM(DB, "Retraction Steps per unit:");
}
ECHO_SMV(DB, " E0 ",max_retraction_feedrate[0]);
#if EXTRUDERS > 1
ECHO_MV(" E1 ", max_retraction_feedrate[1]);
#if EXTRUDERS > 2
ECHO_MV(" E2 ", max_retraction_feedrate[2]);
#if EXTRUDERS > 3
ECHO_MV(" E3 ", max_retraction_feedrate[3]);
#endif //EXTRUDERS > 3
#endif //EXTRUDERS > 2
#endif //EXTRUDERS > 1
ECHO_E;
if (!forReplay) { if (!forReplay) {
ECHO_LM(DB, "Maximum Acceleration (mm/s2):"); ECHO_LM(DB, "Maximum Acceleration (mm/s2):");
} }
......
...@@ -4,8 +4,6 @@ ...@@ -4,8 +4,6 @@
#include "Configuration.h" #include "Configuration.h"
void Config_ResetDefault(); void Config_ResetDefault();
void load_lifetime_stats();
void save_lifetime_stats();
#ifndef DISABLE_M503 #ifndef DISABLE_M503
void Config_PrintSettings(bool forReplay=false); void Config_PrintSettings(bool forReplay=false);
......
...@@ -61,7 +61,6 @@ ...@@ -61,7 +61,6 @@
millis_t minsegmenttime; millis_t minsegmenttime;
float max_feedrate[3 + EXTRUDERS]; // Max speeds in mm per minute float max_feedrate[3 + EXTRUDERS]; // Max speeds in mm per minute
float max_retraction_feedrate[EXTRUDERS]; // set the max speeds for retraction
float axis_steps_per_unit[3 + EXTRUDERS]; float axis_steps_per_unit[3 + EXTRUDERS];
unsigned long max_acceleration_units_per_sq_second[3 + EXTRUDERS]; // Use M201 to override by software unsigned long max_acceleration_units_per_sq_second[3 + EXTRUDERS]; // Use M201 to override by software
float minimumfeedrate; float minimumfeedrate;
...@@ -411,7 +410,6 @@ void check_axes_activity() { ...@@ -411,7 +410,6 @@ void check_axes_activity() {
#ifdef LASERBEAM #ifdef LASERBEAM
tail_laser_ttl_modulation = block_buffer[block_index].laser_ttlmodulation; tail_laser_ttl_modulation = block_buffer[block_index].laser_ttlmodulation;
#endif #endif
while (block_index != block_buffer_head) { while (block_index != block_buffer_head) {
block = &block_buffer[block_index]; block = &block_buffer[block_index];
for (int i=0; i<NUM_AXIS; i++) if (block->steps[i]) axis_active[i]++; for (int i=0; i<NUM_AXIS; i++) if (block->steps[i]) axis_active[i]++;
...@@ -432,11 +430,12 @@ void check_axes_activity() { ...@@ -432,11 +430,12 @@ void check_axes_activity() {
#ifdef FAN_KICKSTART_TIME #ifdef FAN_KICKSTART_TIME
static millis_t fan_kick_end; static millis_t fan_kick_end;
if (tail_fan_speed) { if (tail_fan_speed) {
millis_t ms = millis();
if (fan_kick_end == 0) { if (fan_kick_end == 0) {
// Just starting up fan - run at full power. // Just starting up fan - run at full power.
fan_kick_end = millis() + FAN_KICKSTART_TIME; fan_kick_end = ms + FAN_KICKSTART_TIME;
tail_fan_speed = 255; tail_fan_speed = 255;
} else if (fan_kick_end > millis()) } else if (fan_kick_end > ms)
// Fan still spinning up. // Fan still spinning up.
tail_fan_speed = 255; tail_fan_speed = 255;
} else { } else {
...@@ -463,7 +462,6 @@ void check_axes_activity() { ...@@ -463,7 +462,6 @@ void check_axes_activity() {
#endif #endif
#endif #endif
// add Laser TTL Modulation(PWM) Control
#ifdef LASERBEAM #ifdef LASERBEAM
analogWrite(LASER_TTL_PIN, tail_laser_ttl_modulation); analogWrite(LASER_TTL_PIN, tail_laser_ttl_modulation);
#endif #endif
...@@ -572,8 +570,6 @@ float junction_deviation = 0.1; ...@@ -572,8 +570,6 @@ float junction_deviation = 0.1;
block->valve_pressure = ValvePressure; block->valve_pressure = ValvePressure;
block->e_to_p_pressure = EtoPPressure; block->e_to_p_pressure = EtoPPressure;
#endif #endif
// Add update block variables for LASER BEAM control
#ifdef LASERBEAM #ifdef LASERBEAM
block->laser_ttlmodulation = laser_ttl_modulation; block->laser_ttlmodulation = laser_ttl_modulation;
#endif #endif
...@@ -635,7 +631,7 @@ float junction_deviation = 0.1; ...@@ -635,7 +631,7 @@ float junction_deviation = 0.1;
#if EXTRUDERS > 1 #if EXTRUDERS > 1
case 1: case 1:
enable_e1(); enable_e1();
g_uc_extruder_last_move[1] = BLOCK_BUFFER_SIZE*2; g_uc_extruder_last_move[1] = BLOCK_BUFFER_SIZE * 2;
if (g_uc_extruder_last_move[0] == 0) disable_e0(); if (g_uc_extruder_last_move[0] == 0) disable_e0();
#if EXTRUDERS > 2 #if EXTRUDERS > 2
if (g_uc_extruder_last_move[2] == 0) disable_e2(); if (g_uc_extruder_last_move[2] == 0) disable_e2();
...@@ -647,7 +643,7 @@ float junction_deviation = 0.1; ...@@ -647,7 +643,7 @@ float junction_deviation = 0.1;
#if EXTRUDERS > 2 #if EXTRUDERS > 2
case 2: case 2:
enable_e2(); enable_e2();
g_uc_extruder_last_move[2] = BLOCK_BUFFER_SIZE*2; g_uc_extruder_last_move[2] = BLOCK_BUFFER_SIZE * 2;
if (g_uc_extruder_last_move[0] == 0) disable_e0(); if (g_uc_extruder_last_move[0] == 0) disable_e0();
if (g_uc_extruder_last_move[1] == 0) disable_e1(); if (g_uc_extruder_last_move[1] == 0) disable_e1();
#if EXTRUDERS > 3 #if EXTRUDERS > 3
...@@ -657,7 +653,7 @@ float junction_deviation = 0.1; ...@@ -657,7 +653,7 @@ float junction_deviation = 0.1;
#if EXTRUDERS > 3 #if EXTRUDERS > 3
case 3: case 3:
enable_e3(); enable_e3();
g_uc_extruder_last_move[3] = BLOCK_BUFFER_SIZE*2; g_uc_extruder_last_move[3] = BLOCK_BUFFER_SIZE * 2;
if (g_uc_extruder_last_move[0] == 0) disable_e0(); if (g_uc_extruder_last_move[0] == 0) disable_e0();
if (g_uc_extruder_last_move[1] == 0) disable_e1(); if (g_uc_extruder_last_move[1] == 0) disable_e1();
if (g_uc_extruder_last_move[2] == 0) disable_e2(); if (g_uc_extruder_last_move[2] == 0) disable_e2();
...@@ -794,24 +790,12 @@ float junction_deviation = 0.1; ...@@ -794,24 +790,12 @@ float junction_deviation = 0.1;
// Calculate and limit speed in mm/sec for each axis // Calculate and limit speed in mm/sec for each axis
float current_speed[NUM_AXIS]; float current_speed[NUM_AXIS];
float speed_factor = 1.0; //factor <=1 do decrease speed float speed_factor = 1.0; //factor <=1 do decrease speed
for (int i = 0; i < 3; i++) { for (int i = 0; i < NUM_AXIS; i++) {
current_speed[i] = delta_mm[i] * inverse_second; current_speed[i] = delta_mm[i] * inverse_second;
float cs = fabs(current_speed[i]), mf = max_feedrate[i]; float cs = fabs(current_speed[i]), mf = max_feedrate[i];
if (cs > mf) speed_factor = min(speed_factor, mf / cs); if (cs > mf) speed_factor = min(speed_factor, mf / cs);
} }
current_speed[E_AXIS] = delta_mm[E_AXIS] * inverse_second;
if (target[E_AXIS] < position[E_AXIS])
{
if(fabs(current_speed[E_AXIS]) > max_retraction_feedrate[extruder])
speed_factor = min(speed_factor, max_retraction_feedrate[extruder]/ fabs(current_speed[E_AXIS]));
}
else
{
if(fabs(current_speed[E_AXIS]) > max_feedrate[E_AXIS + extruder])
speed_factor = min(speed_factor, max_feedrate[E_AXIS + extruder] / fabs(current_speed[E_AXIS]));
}
// Max segement time in us. // Max segement time in us.
#ifdef XY_FREQUENCY_LIMIT #ifdef XY_FREQUENCY_LIMIT
#define MAX_FREQ_TIME (1000000.0 / XY_FREQUENCY_LIMIT) #define MAX_FREQ_TIME (1000000.0 / XY_FREQUENCY_LIMIT)
...@@ -1026,11 +1010,15 @@ float junction_deviation = 0.1; ...@@ -1026,11 +1010,15 @@ float junction_deviation = 0.1;
#endif // ENABLE_AUTO_BED_LEVELING #endif // ENABLE_AUTO_BED_LEVELING
#ifdef ENABLE_AUTO_BED_LEVELING #ifdef ENABLE_AUTO_BED_LEVELING
void plan_set_position(float x, float y, float z, const float &e) { void plan_set_position(float x, float y, float z, const float &e)
apply_rotation_xyz(plan_bed_level_matrix, x, y, z); apply_rotation_xyz(plan_bed_level_matrix, x, y, z);
#else #else
void plan_set_position(const float &x, const float &y, const float &z, const float &e) { void plan_set_position(const float &x, const float &y, const float &z, const float &e)
#endif // ENABLE_AUTO_BED_LEVELING #endif // ENABLE_AUTO_BED_LEVELING
{
#ifdef ENABLE_AUTO_BED_LEVELING
apply_rotation_xyz(plan_bed_level_matrix, x, y, z);
#endif
float nx = position[X_AXIS] = lround(x * axis_steps_per_unit[X_AXIS]), float nx = position[X_AXIS] = lround(x * axis_steps_per_unit[X_AXIS]),
ny = position[Y_AXIS] = lround(y * axis_steps_per_unit[Y_AXIS]), ny = position[Y_AXIS] = lround(y * axis_steps_per_unit[Y_AXIS]),
...@@ -1049,6 +1037,6 @@ void plan_set_e_position(const float &e) { ...@@ -1049,6 +1037,6 @@ void plan_set_e_position(const float &e) {
// Calculate the steps/s^2 acceleration rates, based on the mm/s^s // Calculate the steps/s^2 acceleration rates, based on the mm/s^s
void reset_acceleration_rates() { void reset_acceleration_rates() {
for (int i = 0; i < 3 + EXTRUDERS; i++) for (int i = 0; i < 3 + EXTRUDERS; i++)
axis_steps_per_sqr_second[i] = max_acceleration_units_per_sq_second[i] * axis_steps_per_unit[i]; axis_steps_per_sqr_second[i] = max_acceleration_units_per_sq_second[i] * axis_steps_per_unit[i];
} }
...@@ -120,7 +120,6 @@ void plan_set_e_position(const float &e); ...@@ -120,7 +120,6 @@ void plan_set_e_position(const float &e);
extern millis_t minsegmenttime; extern millis_t minsegmenttime;
extern float max_feedrate[3 + EXTRUDERS]; // set the max speeds extern float max_feedrate[3 + EXTRUDERS]; // set the max speeds
extern float max_retraction_feedrate[EXTRUDERS]; // set the max speeds for retraction
extern float axis_steps_per_unit[3 + EXTRUDERS]; extern float axis_steps_per_unit[3 + EXTRUDERS];
extern unsigned long max_acceleration_units_per_sq_second[3 + EXTRUDERS]; // Use M201 to override by software extern unsigned long max_acceleration_units_per_sq_second[3 + EXTRUDERS]; // Use M201 to override by software
extern float minimumfeedrate; extern float minimumfeedrate;
......
Markdown is supported
0% or
You are about to add 0 people to the discussion. Proceed with caution.
Finish editing this message first!
Please register or to comment