Commit 1bc7a1c0 authored by MagoKimbra's avatar MagoKimbra

Update 4.1.4 dev

parent 585e86f3
......@@ -18,7 +18,7 @@ If jumping the arduino Vcc do RAMPS 5V rail, take care to not use a power hungry
Instructions for Both Options
-----------------------------
Uncomment the "ENABLE_AUTO_BED_LEVELING" define (commented by default)
Uncomment the "AUTO_BED_LEVELING_FEATURE" define (commented by default)
The following options define the probing positions. These are good starting values.
I recommend to keep a better clearance from borders in the first run and then make the probes as close as possible to borders:
......@@ -52,9 +52,14 @@ In order to get the servo working, you need to enable:
* \#define NUM_SERVOS 1 // Servo index starts with 0 for M280 command
* \#define SERVO_ENDSTOPS {-1, -1, 0} // Servo index for X, Y, Z. Disable with -1
* \// Define nr servo for endstop -1 not define. Servo index start 0
* \#define X_ENDSTOP_SERVO_NR -1
* \#define Y_ENDSTOP_SERVO_NR -1
* \#define Z_ENDSTOP_SERVO_NR 0
* \#define SERVO_ENDSTOP_ANGLES {0,0, 0,0, 165,60} // X,Y,Z Axis Extend and Retract angles
* \#define X_ENDSTOP_SERVO_ANGLES {0,0} // X Axis Extend and Retract angles
* \#define Y_ENDSTOP_SERVO_ANGLES {0,0} // Y Axis Extend and Retract angles
* \#define Z_ENDSTOP_SERVO_ANGLES {90,0} // Z Axis Extend and Retract angles
The first define tells firmware how many servos you have.
The second tells what axis this servo will be attached to. In the example above, we have a servo in Z axis.
......
### Version 4.1.4
* Add Debug_info. Repetier button info for enabled or disabled, or M111 S2 for enabled and M111 S0 for disabled.
* Add improve Topography Auto Bed Level.
* Add Dryrun ABL and verbose width command G29 D or G29 V(0-4).
* Improve Autoconfiguration for Delta printer.
* Add support (test only) for NEXTION HMI LCD.
* Improved firmare test dialog.
* Bugfix for SDCONFIG routine. Now the configuration file will be readed and created only on the root of the SD.
* Improved "Thermal Runaway Protection" now the system will be halted also if the thermistor is missing before the temperature is reached as suggested in Issue #35.
......
......@@ -425,7 +425,6 @@
/**
* Nextion HMI panel
*/
//
//#define NEXTION
// option for invert rotary switch
......
......@@ -90,15 +90,15 @@
//If you have enabled the Auto Bed Levelling and are using the same Z Probe for Z Homing,
//it is highly recommended you let this Z_SAFE_HOMING enabled!!!
//#define Z_SAFE_HOMING
#ifdef Z_SAFE_HOMING
#if ENABLED(Z_SAFE_HOMING)
#define Z_SAFE_HOMING_X_POINT ((X_MIN_POS + X_MAX_POS) / 2) // X point for Z homing when homing all axis (G28)
#define Z_SAFE_HOMING_Y_POINT ((Y_MIN_POS + Y_MAX_POS) / 2) // Y point for Z homing when homing all axis (G28)
#endif
//#define ENABLE_AUTO_BED_LEVELING // Delete the comment to enable (ABL)
//#define Z_PROBE_REPEATABILITY_TEST // Delete the comment to enable
//#define AUTO_BED_LEVELING_FEATURE // Delete the comment to enable (remove // at the start of the line)
//#define Z_PROBE_REPEATABILITY_TEST // If not commented out, Z-Probe Repeatability test will be included if Auto Bed Leveling is Enabled.
#ifdef ENABLE_AUTO_BED_LEVELING
#if ENABLED(AUTO_BED_LEVELING_FEATURE)
// There are 2 different ways to specify probing locations
//
......@@ -115,7 +115,7 @@
// Note: this feature generates 10KB extra code size
#define AUTO_BED_LEVELING_GRID
#ifdef AUTO_BED_LEVELING_GRID
#if ENABLED(AUTO_BED_LEVELING_GRID)
#define MIN_PROBE_EDGE 10 // The probe square sides can be no smaller than this
......@@ -162,7 +162,7 @@
//#define Z_PROBE_ENDSTOP
#endif // ENABLE_AUTO_BED_LEVELING
#endif // AUTO_BED_LEVELING_FEATURE
// The position of the homing switches
......@@ -197,15 +197,3 @@
#define DEFAULT_XYJERK 10.0 // (mm/sec)
#define DEFAULT_ZJERK 0.4 // (mm/sec)
#define DEFAULT_EJERK {5.0,5.0,5.0,5.0} // E0... (mm/sec) per extruder, max initial speed for retract moves
//===========================================================================
//=============================Additional Features===========================
//===========================================================================
// Custom M code points
//#define CUSTOM_M_CODES
#ifdef CUSTOM_M_CODES
#define CUSTOM_M_CODE_SET_Z_PROBE_OFFSET 851
#define Z_PROBE_OFFSET_RANGE_MIN -20
#define Z_PROBE_OFFSET_RANGE_MAX 20
#endif
......@@ -95,10 +95,10 @@
#define Z_SAFE_HOMING_Y_POINT ((Y_MIN_POS + Y_MAX_POS) / 2) // Y point for Z homing when homing all axis (G28)
#endif
//#define ENABLE_AUTO_BED_LEVELING // Delete the comment to enable (ABL)
//#define Z_PROBE_REPEATABILITY_TEST // Delete the comment to enable
//#define AUTO_BED_LEVELING_FEATURE // Delete the comment to enable (remove // at the start of the line)
//#define Z_PROBE_REPEATABILITY_TEST // If not commented out, Z-Probe Repeatability test will be included if Auto Bed Leveling is Enabled.
#ifdef ENABLE_AUTO_BED_LEVELING
#if ENABLED(AUTO_BED_LEVELING_FEATURE)
// There are 2 different ways to specify probing locations
//
......@@ -115,7 +115,7 @@
// Note: this feature generates 10KB extra code size
#define AUTO_BED_LEVELING_GRID
#ifdef AUTO_BED_LEVELING_GRID
#if ENABLED(AUTO_BED_LEVELING_GRID)
#define MIN_PROBE_EDGE 10 // The probe square sides can be no smaller than this
......@@ -162,7 +162,7 @@
//#define Z_PROBE_ENDSTOP
#endif // ENABLE_AUTO_BED_LEVELING
#endif // AUTO_BED_LEVELING_FEATURE
// The position of the homing switches
......@@ -197,15 +197,3 @@
#define DEFAULT_XYJERK 10.0 // (mm/sec)
#define DEFAULT_ZJERK 0.4 // (mm/sec)
#define DEFAULT_EJERK {5.0,5.0,5.0,5.0} // E0... (mm/sec) per extruder, max initial speed for retract moves
//===========================================================================
//=============================Additional Features===========================
//===========================================================================
// Custom M code points
//#define CUSTOM_M_CODES
#ifdef CUSTOM_M_CODES
#define CUSTOM_M_CODE_SET_Z_PROBE_OFFSET 851
#define Z_PROBE_OFFSET_RANGE_MIN -20
#define Z_PROBE_OFFSET_RANGE_MAX 20
#endif
......@@ -118,10 +118,10 @@
#define Z_SAFE_HOMING_Y_POINT ((Y_MIN_POS + Y_MAX_POS) / 2) // Y point for Z homing when homing all axis (G28)
#endif
//#define ENABLE_AUTO_BED_LEVELING // Delete the comment to enable (ABL)
//#define Z_PROBE_REPEATABILITY_TEST // Delete the comment to enable
//#define AUTO_BED_LEVELING_FEATURE // Delete the comment to enable (remove // at the start of the line)
//#define Z_PROBE_REPEATABILITY_TEST // If not commented out, Z-Probe Repeatability test will be included if Auto Bed Leveling is Enabled.
#ifdef ENABLE_AUTO_BED_LEVELING
#if ENABLED(AUTO_BED_LEVELING_FEATURE)
// There are 2 different ways to specify probing locations
//
......@@ -138,7 +138,7 @@
// Note: this feature generates 10KB extra code size
#define AUTO_BED_LEVELING_GRID
#ifdef AUTO_BED_LEVELING_GRID
#if ENABLED(AUTO_BED_LEVELING_GRID)
#define MIN_PROBE_EDGE 10 // The probe square sides can be no smaller than this
......@@ -185,7 +185,7 @@
//#define Z_PROBE_ENDSTOP
#endif // ENABLE_AUTO_BED_LEVELING
#endif // AUTO_BED_LEVELING_FEATURE
// The position of the homing switches
......@@ -221,15 +221,3 @@
#define DEFAULT_XYJERK 5 // (mm/sec)
#define DEFAULT_ZJERK 0.4 // (mm/sec)
#define DEFAULT_EJERK {3.0,3.0,3.0,3.0} // (mm/sec)
//===========================================================================
//=============================Additional Features===========================
//===========================================================================
// Custom M code points
//#define CUSTOM_M_CODES
#ifdef CUSTOM_M_CODES
#define CUSTOM_M_CODE_SET_Z_PROBE_OFFSET 851
#define Z_PROBE_OFFSET_RANGE_MIN -20
#define Z_PROBE_OFFSET_RANGE_MAX 20
#endif
......@@ -70,7 +70,7 @@
* some filament is retracted. The filament retracted is re-added before the next extrusion
* or when the target temperature is less than IDLE_OOZING_MINTEMP and the actual temperature
* is greater than IDLE_OOZING_MINTEMP.
* PS: Always remember to set your extruder target temperature to 0°C before shoudown the printer if you enable this feature.
* PS: Always remember to set your extruder target temperature to 0°C before shoudown the printer if you enable this feature.
*/
//#define IDLE_OOZING_PREVENT
#define IDLE_OOZING_MINTEMP EXTRUDE_MINTEMP + 5
......
......@@ -29,12 +29,12 @@
#include "Marlin.h"
#if ENABLED(ENABLE_AUTO_BED_LEVELING)
#if ENABLED(AUTO_BED_LEVELING_FEATURE)
#include "vector_3.h"
#if ENABLED(AUTO_BED_LEVELING_GRID)
#include "qr_solve.h"
#endif
#endif // ENABLE_AUTO_BED_LEVELING
#endif // AUTO_BED_LEVELING_FEATURE
#include "ultralcd.h"
......@@ -747,7 +747,7 @@ void setup() {
Config_RetrieveSettings();
lcd_init();
#ifndef NEXTION
#if DISABLED(NEXTION)
delay(SPLASH_SCREEN_DURATION); // wait to display the splash screen
#endif
......@@ -771,7 +771,7 @@ void setup() {
digipot_i2c_init();
#endif
#ifdef Z_PROBE_SLED
#if ENABLED(Z_PROBE_SLED)
pinMode(SLED_PIN, OUTPUT);
digitalWrite(SLED_PIN, LOW); // turn it off
#endif // Z_PROBE_SLED
......@@ -788,7 +788,7 @@ void setup() {
digitalWrite(STAT_LED_BLUE, LOW); // turn it off
#endif
#ifdef FIRMWARE_TEST
#if ENABLED(FIRMWARE_TEST)
FirmwareTest();
#endif // FIRMWARE_TEST
}
......@@ -1093,7 +1093,7 @@ XYZ_CONSTS_FROM_CONFIG(float, base_min_pos, MIN_POS);
XYZ_CONSTS_FROM_CONFIG(float, home_bump_mm, HOME_BUMP_MM);
XYZ_CONSTS_FROM_CONFIG(signed char, home_dir, HOME_DIR);
#ifdef DUAL_X_CARRIAGE
#if ENABLED(DUAL_X_CARRIAGE)
#define DXC_FULL_CONTROL_MODE 0
#define DXC_AUTO_PARK_MODE 1
......@@ -1126,9 +1126,21 @@ XYZ_CONSTS_FROM_CONFIG(signed char, home_dir, HOME_DIR);
#endif //DUAL_X_CARRIAGE
static void axis_is_at_home(AxisEnum axis) {
void print_xyz(const char *prefix, const float x, const float y, const float z, bool eol = true) {
ECHO_V(prefix);
ECHO_MV(": (", x);
ECHO_MV(", ", y);
ECHO_MV(", ", z);
ECHO_M(")");
if (eol) ECHO_E;
}
void print_xyz(const char *prefix, const float xyz[], bool eol = true) {
print_xyz(prefix, xyz[X_AXIS], xyz[Y_AXIS], xyz[Z_AXIS], eol);
}
static void set_axis_is_at_home(AxisEnum axis) {
#ifdef DUAL_X_CARRIAGE
#if ENABLED(DUAL_X_CARRIAGE)
if (axis == X_AXIS) {
if (active_extruder != 0) {
current_position[X_AXIS] = x_home_pos(active_extruder);
......@@ -1146,7 +1158,7 @@ static void axis_is_at_home(AxisEnum axis) {
}
#endif
#ifdef SCARA
#if ENABLED(SCARA)
if (axis == X_AXIS || axis == Y_AXIS) {
......@@ -1186,7 +1198,7 @@ static void axis_is_at_home(AxisEnum axis) {
min_pos[axis] = base_min_pos(axis) + home_offset[axis];
max_pos[axis] = base_max_pos(axis) + home_offset[axis];
}
#elif defined(DELTA)
#elif ENABLED(DELTA)
current_position[axis] = base_home_pos[axis] + home_offset[axis];
min_pos[axis] = base_min_pos(axis) + home_offset[axis];
max_pos[axis] = base_max_pos[axis] + home_offset[axis];
......@@ -1196,9 +1208,15 @@ static void axis_is_at_home(AxisEnum axis) {
max_pos[axis] = base_max_pos(axis) + home_offset[axis];
#endif
#if defined(ENABLE_AUTO_BED_LEVELING) && Z_HOME_DIR < 0
#if ENABLED(AUTO_BED_LEVELING_FEATURE) && Z_HOME_DIR < 0
if (axis == Z_AXIS) current_position[Z_AXIS] -= zprobe_zoffset;
#endif
if (debugLevel & DEBUG_INFO) {
ECHO_SMV(DB, "set_axis_is_at_home ", (unsigned long)axis);
ECHO_MV(" > (home_offset[axis]==", home_offset[axis]);
print_xyz(") > current_position", current_position);
}
}
/**
......@@ -1251,7 +1269,7 @@ static void setup_for_endstop_move() {
}
static void clean_up_after_endstop_move() {
#ifdef ENDSTOPS_ONLY_FOR_HOMING
#if ENABLED(ENDSTOPS_ONLY_FOR_HOMING)
enable_endstops(false);
#endif
feedrate = saved_feedrate;
......@@ -1260,7 +1278,7 @@ static void clean_up_after_endstop_move() {
refresh_cmd_timeout();
}
#if defined(CARTESIAN) || defined(COREXY) || defined(COREXZ) || defined(SCARA)
#if ENABLED(CARTESIAN) || ENABLED(COREXY) || ENABLED(COREXZ) || ENABLED(SCARA)
/**
* Plan a move to (X, Y, Z) and set the current_position
......@@ -1270,6 +1288,11 @@ static void clean_up_after_endstop_move() {
float oldFeedRate = feedrate;
feedrate = homing_feedrate[Z_AXIS];
if (debugLevel & DEBUG_INFO) {
ECHO_S(DB);
print_xyz("do_blocking_move_to", x, y, z);
}
current_position[Z_AXIS] = z;
line_to_current_position();
st_synchronize();
......@@ -1288,9 +1311,9 @@ static void clean_up_after_endstop_move() {
inline void do_blocking_move_to_x(float x) { do_blocking_move_to(x, current_position[Y_AXIS], current_position[Z_AXIS]); }
inline void do_blocking_move_to_z(float z) { do_blocking_move_to(current_position[X_AXIS], current_position[Y_AXIS], z); }
#ifdef ENABLE_AUTO_BED_LEVELING
#if ENABLED(AUTO_BED_LEVELING_FEATURE)
#ifdef AUTO_BED_LEVELING_GRID
#if ENABLED(AUTO_BED_LEVELING_GRID)
static void set_bed_level_equation_lsq(double *plane_equation_coefficients) {
vector_3 planeNormal = vector_3(-plane_equation_coefficients[0], -plane_equation_coefficients[1], 1);
planeNormal.debug("planeNormal");
......@@ -1307,6 +1330,11 @@ static void clean_up_after_endstop_move() {
current_position[Y_AXIS] = corrected_position.y;
current_position[Z_AXIS] = corrected_position.z;
if (debugLevel & DEBUG_INFO) {
ECHO_S(DB);
print_xyz("set_bed_level_equation_lsq > current_position", current_position);
}
sync_plan_position();
}
#else // not AUTO_BED_LEVELING_GRID
......@@ -1332,6 +1360,11 @@ static void clean_up_after_endstop_move() {
current_position[Y_AXIS] = corrected_position.y;
current_position[Z_AXIS] = corrected_position.z;
if (debugLevel & DEBUG_INFO) {
ECHO_S(DB);
print_xyz("set_bed_level_equation_3pts > current_position", current_position);
}
sync_plan_position();
}
......@@ -1368,9 +1401,18 @@ static void clean_up_after_endstop_move() {
// Get the current stepper position after bumping an endstop
current_position[Z_AXIS] = st_get_position_mm(Z_AXIS);
sync_plan_position();
if (debugLevel & DEBUG_INFO) {
ECHO_S(DB);
print_xyz("run_z_probe > current_position", current_position);
}
}
static void deploy_z_probe() {
if (debugLevel & DEBUG_INFO) {
ECHO_S(DB);
print_xyz("deploy_z_probe > current_position", current_position);
}
#if HAS_SERVO_ENDSTOPS
// Engage Z Servo endstop if enabled
if (servo_endstop_id[Z_AXIS] >= 0) servo[servo_endstop_id[Z_AXIS]].move(servo_endstop_angle[Z_AXIS][0]);
......@@ -1378,12 +1420,20 @@ static void clean_up_after_endstop_move() {
}
static void stow_z_probe(bool doRaise = true) {
if (debugLevel & DEBUG_INFO) {
ECHO_S(DB);
print_xyz("stow_z_probe > current_position", current_position);
}
#if HAS_SERVO_ENDSTOPS
// Retract Z Servo endstop if enabled
if (servo_endstop_id[Z_AXIS] >= 0) {
#if Z_RAISE_AFTER_PROBING > 0
if (doRaise) {
if (debugLevel & DEBUG_INFO) {
ECHO_LMV(DB, "Raise Z (after) by ", (float)Z_RAISE_AFTER_PROBING);
ECHO_LMV(DB, "> SERVO_ENDSTOPS > do_blocking_move_to_z ", current_position[Z_AXIS] + Z_RAISE_AFTER_PROBING);
}
do_blocking_move_to_z(current_position[Z_AXIS] + Z_RAISE_AFTER_PROBING); // this also updates current_position
st_synchronize();
}
......@@ -1404,19 +1454,39 @@ static void clean_up_after_endstop_move() {
// Probe bed height at position (x,y), returns the measured z value
static float probe_pt(float x, float y, float z_before, ProbeAction probe_action = ProbeDeployAndStow, int verbose_level = 1) {
// move to right place
if (debugLevel & DEBUG_INFO) {
ECHO_LM(DB, "probe_pt >>>");
ECHO_SMV(DB, "> ProbeAction:", (unsigned long)probe_action);
print_xyz(" > current_position", current_position);
ECHO_SMV(DB, "Z Raise to z_before ", z_before);
ECHO_EMV(" > do_blocking_move_to_z ", z_before);
}
// Move Z up to the z_before height, then move the probe to the given XY
do_blocking_move_to_z(z_before); // this also updates current_position
if (debugLevel & DEBUG_INFO) {
ECHO_SMV(DB, "> do_blocking_move_to_xy ", x - X_PROBE_OFFSET_FROM_EXTRUDER);
ECHO_EMV(", ", y - Y_PROBE_OFFSET_FROM_EXTRUDER);
}
do_blocking_move_to_xy(x - X_PROBE_OFFSET_FROM_EXTRUDER, y - Y_PROBE_OFFSET_FROM_EXTRUDER); // this also updates current_position
#ifndef Z_PROBE_SLED
if (probe_action & ProbeDeploy) deploy_z_probe();
#endif // Z_PROBE_SLED
#if DISABLED(Z_PROBE_SLED)
if (probe_action & ProbeDeploy) {
if (debugLevel & DEBUG_INFO) ECHO_LM(DB, "> ProbeDeploy");
deploy_z_probe();
}
#endif
run_z_probe();
float measured_z = current_position[Z_AXIS];
#ifndef Z_PROBE_SLED
if (probe_action & ProbeStow) stow_z_probe();
#if DISABLED(Z_PROBE_SLED)
if (probe_action & ProbeStow) {
if (debugLevel & DEBUG_INFO) ECHO_LM(DB, "> ProbeStow (stow_z_probe will do Z Raise)");
stow_z_probe();
}
#endif
if (verbose_level > 2) {
......@@ -1425,18 +1495,26 @@ static void clean_up_after_endstop_move() {
ECHO_MV(MSG_BED_LEVELLING_Y, y, 3);
ECHO_EMV(MSG_BED_LEVELLING_Z, measured_z, 3);
}
if (debugLevel & DEBUG_INFO) ECHO_LM(DB, "<<< probe_pt");
return measured_z;
}
#endif //ENABLE_AUTO_BED_LEVELING
#endif //AUTO_BED_LEVELING_FEATURE
static void homeaxis(AxisEnum axis) {
#define HOMEAXIS_DO(LETTER) \
((LETTER##_MIN_PIN > -1 && LETTER##_HOME_DIR==-1) || (LETTER##_MAX_PIN > -1 && LETTER##_HOME_DIR==1))
if (debugLevel & DEBUG_INFO) {
ECHO_SMV(DB, ">>> homeaxis(", (unsigned long)axis);
ECHO_EM(")");
}
if (axis == X_AXIS ? HOMEAXIS_DO(X) : axis == Y_AXIS ? HOMEAXIS_DO(Y) : axis == Z_AXIS ? HOMEAXIS_DO(Z) : 0) {
int axis_home_dir =
#ifdef DUAL_X_CARRIAGE
#if ENABLED(DUAL_X_CARRIAGE)
(axis == X_AXIS) ? x_home_dir(active_extruder) :
#endif
home_dir(axis);
......@@ -1445,7 +1523,7 @@ static void clean_up_after_endstop_move() {
current_position[axis] = 0;
sync_plan_position();
#ifdef Z_PROBE_SLED
#if ENABLED(Z_PROBE_SLED)
// Get Probe
if (axis == Z_AXIS) {
if (axis_home_dir < 0) dock_sled(false);
......@@ -1466,7 +1544,7 @@ static void clean_up_after_endstop_move() {
#endif
// Set a flag for Z motor locking
#ifdef Z_DUAL_ENDSTOPS
#if ENABLED(Z_DUAL_ENDSTOPS)
if (axis == Z_AXIS) In_Homing_Process(true);
#endif
......@@ -1497,6 +1575,11 @@ static void clean_up_after_endstop_move() {
line_to_destination();
st_synchronize();
if (debugLevel & DEBUG_INFO) {
ECHO_S(DB);
print_xyz("> TRIGGER ENDSTOP > current_position", current_position);
}
#ifdef Z_DUAL_ENDSTOPS
if (axis == Z_AXIS) {
float adj = fabs(z_endstop_adj);
......@@ -1523,9 +1606,14 @@ static void clean_up_after_endstop_move() {
#endif
// Set the axis position to its home position (plus home offsets)
axis_is_at_home(axis);
set_axis_is_at_home(axis);
sync_plan_position();
if (debugLevel & DEBUG_INFO) {
ECHO_S(DB);
print_xyz("> AFTER set_axis_is_at_home > current_position", current_position);
}
destination[axis] = current_position[axis];
feedrate = 0.0;
endstops_hit_on_purpose(); // clear endstop hit flags
......@@ -1541,23 +1629,32 @@ static void clean_up_after_endstop_move() {
#if SERVO_LEVELING && DISABLED(Z_PROBE_SLED)
// Deploy a probe if there is one, and homing towards the bed
if (axis == Z_AXIS) {
if (axis_home_dir < 0) stow_z_probe();
if (axis_home_dir < 0) {
if (debugLevel & DEBUG_INFO) ECHO_LM(DB, "> SERVO_LEVELING > stow_z_probe");
stow_z_probe();
}
}
else
#endif
{
#if HAS_SERVO_ENDSTOPS
// Retract Servo endstop if enabled
if (servo_endstop_id[axis] >= 0)
if (servo_endstop_id[axis] >= 0) {
if (debugLevel & DEBUG_INFO) ECHO_LM(DB, "> SERVO_ENDSTOPS > Stow with servo.move()");
servo[servo_endstop_id[axis]].move(servo_endstop_angle[axis][1]);
}
#endif
}
}
if (debugLevel & DEBUG_INFO) {
ECHO_SMV(DB, "<<< homeaxis(", (unsigned long)axis);
ECHO_EM(")");
}
}
#define HOMEAXIS(LETTER) homeaxis(LETTER##_AXIS)
#endif // CARTESIAN || COREXY || COREXZ || SCARA
#ifdef DELTA
#if ENABLED(DELTA)
static void homeaxis(AxisEnum axis) {
#define HOMEAXIS_DO(LETTER) \
......@@ -1601,15 +1698,26 @@ static void clean_up_after_endstop_move() {
enable_endstops(false); // Disable endstops while moving away
sync_plan_position();
destination[axis] = endstop_adj[axis];
if (debugLevel & DEBUG_INFO) {
ECHO_SMV(DB, "> endstop_adj = ", endstop_adj[axis]);
print_xyz(" > destination", destination);
}
line_to_destination();
st_synchronize();
enable_endstops(true); // Enable endstops for next homing move
}
if (debugLevel & DEBUG_INFO) ECHO_LMV(DB, "> endstop_adj * axis_home_dir = ", endstop_adj[axis] * axis_home_dir);
// Set the axis position to its home position (plus home offsets)
axis_is_at_home(axis);
set_axis_is_at_home(axis);
sync_plan_position();
if (debugLevel & DEBUG_INFO) {
ECHO_S(DB);
print_xyz("> AFTER set_axis_is_at_home > current_position", current_position);
}
destination[axis] = current_position[axis];
feedrate = 0.0;
endstops_hit_on_purpose(); // clear endstop hit flags
......@@ -1687,6 +1795,7 @@ static void clean_up_after_endstop_move() {
// Reset calibration results to zero.
void reset_bed_level() {
if (debugLevel & DEBUG_INFO) ECHO_LM(DB, "reset_bed_level");
for (int y = 0; y < AUTO_BED_LEVELING_GRID_POINTS; y++) {
for (int x = 0; x < AUTO_BED_LEVELING_GRID_POINTS; x++) {
bed_level[x][y] = 0.0;
......@@ -2471,6 +2580,10 @@ static void clean_up_after_endstop_move() {
}
void prepare_move_raw() {
if (debugLevel & DEBUG_INFO) {
ECHO_S(DB);
print_xyz("prepare_move_raw > destination", destination);
}
refresh_cmd_timeout();
calculate_delta(destination);
plan_buffer_line(delta[X_AXIS], delta[Y_AXIS], delta[Z_AXIS], destination[E_AXIS], feedrate*feedrate_multiplier/60/100.0, active_extruder, active_driver);
......@@ -2611,7 +2724,7 @@ static void clean_up_after_endstop_move() {
} // retract()
#endif //FWRETRACT
#ifdef Z_PROBE_SLED
#if ENABLED(Z_PROBE_SLED)
#ifndef SLED_DOCKING_OFFSET
#define SLED_DOCKING_OFFSET 0
......@@ -2624,6 +2737,8 @@ static void clean_up_after_endstop_move() {
* offset[in] The additional distance to move to adjust docking location
*/
static void dock_sled(bool dock, int offset=0) {
if (debugLevel & DEBUG_INFO) ECHO_LMV(DB, "dock_sled", dock);
if (!axis_known_position[X_AXIS] || !axis_known_position[Y_AXIS]) {
LCD_MESSAGEPGM(MSG_POSITION_UNKNOWN);
ECHO_LM(DB, MSG_POSITION_UNKNOWN);
......@@ -2871,11 +2986,13 @@ inline void gcode_G4() {
*/
inline void gcode_G28() {
if (debugLevel & DEBUG_INFO) ECHO_LM(DB, "gcode_G28 >>>");
// Wait for planner moves to finish!
st_synchronize();
// For auto bed leveling, clear the level matrix
#ifdef ENABLE_AUTO_BED_LEVELING
#if ENABLED(AUTO_BED_LEVELING_FEATURE)
plan_bed_level_matrix.set_to_identity();
#elif defined(DELTA)
reset_bed_level();
......@@ -2904,7 +3021,7 @@ inline void gcode_G28() {
}
#endif
#ifdef DELTA
#if ENABLED(DELTA)
// A delta can only safely home all axis at the same time
// all axis have to home at the same time
......@@ -2929,6 +3046,11 @@ inline void gcode_G28() {
sync_plan_position_delta();
if (debugLevel & DEBUG_INFO) {
ECHO_S(DB);
print_xyz("(DELTA) > current_position", current_position);
}
#else // NOT DELTA
if (home_all_axis || homeZ) {
......@@ -2936,12 +3058,19 @@ inline void gcode_G28() {
#if Z_HOME_DIR > 0 // If homing away from BED do Z first
HOMEAXIS(Z);
if (debugLevel & DEBUG_INFO) {
ECHO_S(DB);
print_xyz("> HOMEAXIS(Z) > current_position", current_position);
}
#elif !defined(Z_SAFE_HOMING) && defined(Z_RAISE_BEFORE_HOMING) && Z_RAISE_BEFORE_HOMING > 0
#elif DISABLED(Z_SAFE_HOMING) && defined(Z_RAISE_BEFORE_HOMING) && Z_RAISE_BEFORE_HOMING > 0
// Raise Z before homing any other axes
destination[Z_AXIS] = -Z_RAISE_BEFORE_HOMING * home_dir(Z_AXIS); // Set destination away from bed
if (debugLevel & DEBUG_INFO) {
ECHO_SMV(DB, "Raise Z (before homing) by ", (float)Z_RAISE_BEFORE_HOMING);
print_xyz(" > (home_all_axis || homeZ) > destination", destination);
}
feedrate = max_feedrate[Z_AXIS] * 60;
line_to_destination();
st_synchronize();
......@@ -2974,10 +3103,15 @@ inline void gcode_G28() {
line_to_destination();
st_synchronize();
axis_is_at_home(X_AXIS);
axis_is_at_home(Y_AXIS);
set_axis_is_at_home(X_AXIS);
set_axis_is_at_home(Y_AXIS);
sync_plan_position();
if (debugLevel & DEBUG_INFO) {
ECHO_S(DB);
print_xyz("> QUICK_HOME > current_position 1", current_position);
}
destination[X_AXIS] = current_position[X_AXIS];
destination[Y_AXIS] = current_position[Y_AXIS];
line_to_destination();
......@@ -2987,11 +3121,15 @@ inline void gcode_G28() {
current_position[X_AXIS] = destination[X_AXIS];
current_position[Y_AXIS] = destination[Y_AXIS];
#ifndef SCARA
#if DISABLED(SCARA)
current_position[Z_AXIS] = destination[Z_AXIS];
#endif
}
if (debugLevel & DEBUG_INFO) {
ECHO_S(DB);
print_xyz("> QUICK_HOME > current_position 2", current_position);
}
}
#endif // QUICK_HOME
#ifdef HOME_Y_BEFORE_X
......@@ -3016,16 +3154,26 @@ inline void gcode_G28() {
#else
HOMEAXIS(X);
#endif
if (debugLevel & DEBUG_INFO) {
ECHO_S(DB);
print_xyz("> homeX", current_position);
}
}
#ifndef HOME_Y_BEFORE_X
#if DISABLED(HOME_Y_BEFORE_X)
// Home Y
if (home_all_axis || homeY) HOMEAXIS(Y);
if (home_all_axis || homeY) {
HOMEAXIS(Y);
if (debugLevel & DEBUG_INFO) {
ECHO_S(DB);
print_xyz("> homeY", current_position);
}
}
#endif
// Home Z last if homing towards the bed
#if Z_HOME_DIR < 0
#ifndef Z_SAFE_HOMING
#if DISABLED(Z_SAFE_HOMING)
if (code_seen('M') && !(homeX || homeY)) {
// Manual G28 bed level
#ifdef ULTIPANEL
......@@ -3116,8 +3264,17 @@ inline void gcode_G28() {
enqueuecommands_P(PSTR("G28"));
#endif // ULTIPANEL
}
else if (home_all_axis || homeZ) HOMEAXIS(Z);
#elif defined(Z_SAFE_HOMING) && defined(ENABLE_AUTO_BED_LEVELING)// Z Safe mode activated.
else if (home_all_axis || homeZ) {
HOMEAXIS(Z);
if (debugLevel & DEBUG_INFO) {
ECHO_S(DB);
print_xyz("> (home_all_axis || homeZ) > final", current_position);
}
}
#elif ENABLED(Z_SAFE_HOMING) && ENABLED(AUTO_BED_LEVELING_FEATURE)// Z Safe mode activated.
if (debugLevel & DEBUG_INFO) ECHO_LM(DB, "> Z_SAFE_HOMING >>>");
if (home_all_axis) {
current_position[Z_AXIS] = 0;
......@@ -3132,6 +3289,13 @@ inline void gcode_G28() {
destination[Y_AXIS] = round(Z_SAFE_HOMING_Y_POINT - Y_PROBE_OFFSET_FROM_EXTRUDER);
destination[Z_AXIS] = -Z_RAISE_BEFORE_HOMING * home_dir(Z_AXIS);
feedrate = xy_travel_speed;
if (debugLevel & DEBUG_INFO) {
ECHO_SMV(DB, "Raise Z (before homing) by ", (float)Z_RAISE_BEFORE_HOMING);
print_xyz(" > home_all_axis > current_position", current_position, false);
print_xyz(" > home_all_axis > destination", destination);
}
// This could potentially move X, Y, Z all together
line_to_destination();
st_synchronize();
......@@ -3161,6 +3325,13 @@ inline void gcode_G28() {
// Set Z destination away from bed and raise the axis
destination[Z_AXIS] = -Z_RAISE_BEFORE_HOMING * home_dir(Z_AXIS); // Set destination away from bed
feedrate = max_feedrate[Z_AXIS] * 60;
if (debugLevel & DEBUG_INFO) {
ECHO_SMV(DB, "Raise Z (before homing) by ", (float)Z_RAISE_BEFORE_HOMING);
print_xyz(" > homeZ > current_position", current_position, false);
print_xyz(" > homeZ > destination", destination);
}
line_to_destination();
st_synchronize();
......@@ -3177,7 +3348,8 @@ inline void gcode_G28() {
ECHO_LM(ER, MSG_POSITION_UNKNOWN);
}
}
#elif defined(Z_SAFE_HOMING)
if (debugLevel & DEBUG_INFO) ECHO_LM(DB, "<<< Z_SAFE_HOMING");
#elif ENABLED(Z_SAFE_HOMING)
if (home_all_axis || homeZ) {
// Let's see if X and Y are homed
......@@ -3189,6 +3361,13 @@ inline void gcode_G28() {
destination[Y_AXIS] = round(Z_SAFE_HOMING_Y_POINT);
destination[Z_AXIS] = current_position[Z_AXIS] = 0;
feedrate = xy_travel_speed;
if (debugLevel & DEBUG_INFO) {
ECHO_SMV(DB, "Raise Z (before homing) by ", (float)Z_RAISE_BEFORE_HOMING);
print_xyz(" > home_all_axis > current_position", current_position, false);
print_xyz(" > home_all_axis > destination", destination);
}
// This could potentially move X, Y, Z all together
line_to_destination();
st_synchronize();
......@@ -3203,6 +3382,7 @@ inline void gcode_G28() {
ECHO_LM(ER, MSG_POSITION_UNKNOWN);
}
}
if (debugLevel & DEBUG_INFO) ECHO_LM(DB, "<<< Z_SAFE_HOMING");
#endif //Z_SAFE_HOMING
#endif //Z_HOME_DIR < 0
......@@ -3210,14 +3390,14 @@ inline void gcode_G28() {
#endif // !DELTA
#ifdef SCARA
#if ENABLED(SCARA)
sync_plan_position_delta();
#endif
clean_up_after_endstop_move();
}
#ifdef ENABLE_AUTO_BED_LEVELING
#if ENABLED(AUTO_BED_LEVELING_FEATURE)
void out_of_range_error(const char *p_edge) {
ECHO_M("?Probe ");
......@@ -3263,6 +3443,8 @@ inline void gcode_G28() {
*/
inline void gcode_G29() {
if (debugLevel & DEBUG_INFO) ECHO_LM(DB, "gcode_G29 >>>");
// Don't allow auto-leveling without homing first
if (!axis_known_position[X_AXIS] || !axis_known_position[Y_AXIS]) {
LCD_MESSAGEPGM(MSG_POSITION_UNKNOWN);
......@@ -3270,16 +3452,16 @@ inline void gcode_G28() {
return;
}
int verbose_level = code_seen('V') || code_seen('v') ? code_value_short() : 1;
int verbose_level = code_seen('V') ? code_value_short() : 1;
if (verbose_level < 0 || verbose_level > 4) {
ECHO_LM(ER,"?(V)erbose Level is implausible (0-4).");
return;
}
bool dryrun = code_seen('D') || code_seen('d'),
bool dryrun = code_seen('D'),
deploy_probe_for_each_reading = code_seen('E');
#ifdef AUTO_BED_LEVELING_GRID
#if ENABLED(AUTO_BED_LEVELING_GRID)
bool do_topography_map = verbose_level > 2 || code_seen('T');
......@@ -3332,7 +3514,7 @@ inline void gcode_G28() {
#endif // AUTO_BED_LEVELING_GRID
#ifdef Z_PROBE_SLED
#if ENABLED(Z_PROBE_SLED)
dock_sled(false); // engage (un-dock) the probe
#endif
......@@ -3355,7 +3537,7 @@ inline void gcode_G28() {
setup_for_endstop_move();
feedrate = homing_feedrate[Z_AXIS];
#ifdef AUTO_BED_LEVELING_GRID
#if ENABLED(AUTO_BED_LEVELING_GRID)
// probe at the points of a lattice grid
const int xGridSpacing = (right_probe_bed_position - left_probe_bed_position) / (auto_bed_leveling_grid_points - 1),
......@@ -3370,8 +3552,7 @@ inline void gcode_G28() {
int abl2 = auto_bed_leveling_grid_points * auto_bed_leveling_grid_points;
double eqnAMatrix[abl2 * 3], // "A" matrix of the linear system of equations
eqnBVector[abl2], // "B" vector of Z points
mean = 0.0;
eqnBVector[abl2]; // "B" vector of Z points
int probePointCounter = 0;
bool zig = true;
......@@ -3401,6 +3582,13 @@ inline void gcode_G28() {
float measured_z,
z_before = probePointCounter ? Z_RAISE_BETWEEN_PROBINGS + current_position[Z_AXIS] : Z_RAISE_BEFORE_PROBING;
if (probePointCounter) {
if (debugLevel & DEBUG_INFO) ECHO_LMV(DB, "z_before = (between) ", (float)(Z_RAISE_BETWEEN_PROBINGS + current_position[Z_AXIS]));
}
else {
if (debugLevel & DEBUG_INFO) ECHO_LMV(DB, "z_before = (before) ", (float)Z_RAISE_BEFORE_PROBING);
}
// Enhanced G29 - Do not retract servo between probes
ProbeAction act;
if (deploy_probe_for_each_reading) // G29 E - Stow between probes
......@@ -3414,8 +3602,6 @@ inline void gcode_G28() {
measured_z = probe_pt(xProbe, yProbe, z_before, act, verbose_level);
mean += measured_z;
eqnBVector[probePointCounter] = measured_z;
eqnAMatrix[probePointCounter + 0 * abl2] = xProbe;
eqnAMatrix[probePointCounter + 1 * abl2] = yProbe;
......@@ -3428,52 +3614,94 @@ inline void gcode_G28() {
} //xProbe
} //yProbe
if (debugLevel & DEBUG_INFO) {
ECHO_S(DB);
print_xyz("> probing complete > current_position", current_position);
}
clean_up_after_endstop_move();
// solve lsq problem
double plane_equation_coefficients[3];
qr_solve(plane_equation_coefficients, abl2, 3, eqnAMatrix, eqnBVector);
mean /= abl2;
double *plane_equation_coefficients = qr_solve(abl2, 3, eqnAMatrix, eqnBVector);
if (verbose_level) {
ECHO_SMV(DB, "Eqn coefficients: a: ", plane_equation_coefficients[0], 8);
ECHO_MV(" b: ", plane_equation_coefficients[1], 8);
ECHO_EMV(" d: ", plane_equation_coefficients[2], 8);
if (verbose_level > 2) {
ECHO_LMV(DB, "Mean of sampled points: ", mean, 8);
}
}
if (!dryrun) set_bed_level_equation_lsq(plane_equation_coefficients);
free(plane_equation_coefficients);
matrix_3x3 inverse_bed_level_matrix = matrix_3x3::transpose(plan_bed_level_matrix); // inverse bed level matrix
// In the special case of an rotation matrix "the inverse" = "the transposed" matrix.
// search minimum and maximum point on bed in rotated coordinates
float rot_min_diff = Z_MAX_POS,
rot_max_diff = -Z_MAX_POS,
min_diff = Z_MAX_POS;
for (int8_t i = 0; i < abl2; i++) {
vector_3 probe_point = vector_3(eqnAMatrix[i + 0 * abl2], eqnAMatrix[i + 1 * abl2], eqnBVector[i]);
probe_point.apply_rotation(inverse_bed_level_matrix);
rot_min_diff = min(rot_min_diff, probe_point.z);
rot_max_diff = max(rot_max_diff, probe_point.z);
min_diff = min(min_diff, eqnBVector[i]);
}
// Show the Topography map if enabled
if (do_topography_map) {
// search minimum measured Z
ECHO_LM(DB, "+-----------+");
ECHO_LM(DB, "|...Back....|");
ECHO_LM(DB, "|Left..Right|");
ECHO_LM(DB, "|...Front...|");
ECHO_LM(DB, "+-----------+");
ECHO_LM(DB, "Measured Bed Topography:");
ECHO_LM(DB, "Bed Height Topography: \n");
ECHO_LM(DB, "+-----------+\n");
ECHO_LM(DB, "|...Back....|\n");
ECHO_LM(DB, "|Left..Right|\n");
ECHO_LM(DB, "|...Front...|\n");
ECHO_LM(DB, "+-----------+\n");
for (int8_t yy = auto_bed_leveling_grid_points - 1; yy >= 0; yy--) {
ECHO_S(DB);
for (int8_t xx = 0; xx < auto_bed_leveling_grid_points; xx++) {
int8_t ind = yy * auto_bed_leveling_grid_points + xx;
float min_diff = 999;
float diff = eqnBVector[ind];
for (int yy = auto_bed_leveling_grid_points - 1; yy >= 0; yy--) {
if (diff >= 0.0)
ECHO_M(" +"); // Include + for column alignment
else
ECHO_M(" ");
ECHO_V(diff, 5);
} // xx
ECHO_E;
} // yy
ECHO_E;
ECHO_LM(DB, "Corrected Bed Topography:");
for (int8_t yy = auto_bed_leveling_grid_points - 1; yy >= 0; yy--) {
ECHO_S(DB);
for (int xx = 0; xx < auto_bed_leveling_grid_points; xx++) {
int ind = yy * auto_bed_leveling_grid_points + xx;
float diff = eqnBVector[ind] - mean;
for (int8_t xx = 0; xx < auto_bed_leveling_grid_points; xx++) {
int8_t ind = yy * auto_bed_leveling_grid_points + xx;
float x_tmp = eqnAMatrix[ind + 0 * abl2],
y_tmp = eqnAMatrix[ind + 1 * abl2],
z_tmp = 0;
float diff = eqnBVector[ind] - min_diff;
apply_rotation_xyz(plan_bed_level_matrix,x_tmp,y_tmp,z_tmp);
if (diff >= 0.0)
ECHO_M(" +"); // Include + for column alignment
else
ECHO_M(" ");
ECHO_V(diff, 5);
} // xx
ECHO_E;
} // yy
ECHO_E;
ECHO_LM(DB, "Corrected Bed Topography in new coordinates:");
for (int8_t yy = auto_bed_leveling_grid_points - 1; yy >= 0; yy--) {
ECHO_S(DB);
for (int8_t xx = 0; xx < auto_bed_leveling_grid_points; xx++) {
int8_t ind = yy * auto_bed_leveling_grid_points + xx;
if (eqnBVector[ind] - z_tmp < min_diff)
min_diff = eqnBVector[ind] - z_tmp;
vector_3 probe_point = vector_3(eqnAMatrix[ind + 0 * abl2], eqnAMatrix[ind + 1 * abl2], eqnBVector[ind]);
probe_point.apply_rotation(inverse_bed_level_matrix);
float diff = probe_point.z - rot_min_diff;
if (diff >= 0.0)
ECHO_M(" +"); // Include + for column alignment
......@@ -3484,19 +3712,18 @@ inline void gcode_G28() {
ECHO_E;
} // yy
ECHO_E;
if (verbose_level > 3) {
ECHO_LM(DB, " Corrected Bed Height vs. Bed Topology: \n");
for (int yy = auto_bed_leveling_grid_points - 1; yy >= 0; yy--) {
ECHO_LM(DB, "Height from Bed to Nozzle");
ECHO_LM(DB, "(+) above, or (-) below surface :");
for (int8_t yy = auto_bed_leveling_grid_points - 1; yy >= 0; yy--) {
ECHO_S(DB);
for (int xx = 0; xx < auto_bed_leveling_grid_points; xx++) {
int ind = yy * auto_bed_leveling_grid_points + xx;
float x_tmp = eqnAMatrix[ind + 0 * abl2],
y_tmp = eqnAMatrix[ind + 1 * abl2],
z_tmp = 0;
for (int8_t xx = 0; xx < auto_bed_leveling_grid_points; xx++) {
int8_t ind = yy * auto_bed_leveling_grid_points + xx;
apply_rotation_xyz(plan_bed_level_matrix,x_tmp,y_tmp,z_tmp);
vector_3 probe_point = vector_3(eqnAMatrix[ind + 0 * abl2], eqnAMatrix[ind + 1 * abl2], eqnBVector[ind]);
probe_point.apply_rotation(inverse_bed_level_matrix);
float diff = -(probe_point.z - rot_max_diff);
float diff = eqnBVector[ind] - z_tmp - min_diff;
if (diff >= 0.0)
ECHO_M(" +"); // Include + for column alignment
else
......@@ -3506,10 +3733,12 @@ inline void gcode_G28() {
ECHO_E;
} // yy
ECHO_E;
}
} //do_topography_map
#else // !AUTO_BED_LEVELING_GRID
if (debugLevel & DEBUG_INFO) ECHO_LM(DB, "> 3-point Leveling");
// Actions for each probe
ProbeAction p1, p2, p3;
if (deploy_probe_for_each_reading)
......@@ -3527,48 +3756,27 @@ inline void gcode_G28() {
#endif // !AUTO_BED_LEVELING_GRID
if (verbose_level > 0)
plan_bed_level_matrix.debug("Bed Level Correction Matrix:");
plan_bed_level_matrix.debug(" Bed Level Correction Matrix:");
if (!dryrun) {
// Correct the Z height difference from z-probe position and hotend tip position.
// The Z height on homing is measured by Z-Probe, but the probe is quite far from the hotend.
// When the bed is uneven, this height must be corrected.
float x_tmp = current_position[X_AXIS] + X_PROBE_OFFSET_FROM_EXTRUDER,
y_tmp = current_position[Y_AXIS] + Y_PROBE_OFFSET_FROM_EXTRUDER,
z_tmp = current_position[Z_AXIS],
real_z = st_get_position_mm(Z_AXIS); //get the real Z (since plan_get_position is now correcting the plane)
apply_rotation_xyz(plan_bed_level_matrix, x_tmp, y_tmp, z_tmp); // Apply the correction sending the probe offset
// Get the current Z position and send it to the planner.
//
// >> (z_tmp - real_z) : The rotated current Z minus the uncorrected Z (most recent plan_set_position/sync_plan_position)
//
// >> zprobe_zoffset : Z distance from nozzle to probe (set by default, M851, EEPROM, or Menu)
//
// >> Z_RAISE_AFTER_PROBING : The distance the probe will have lifted after the last probe
//
// >> Should home_offset[Z_AXIS] be included?
//
// Discussion: home_offset[Z_AXIS] was applied in G28 to set the starting Z.
// If Z is not tweaked in G29 -and- the Z probe in G29 is not actually "homing" Z...
// then perhaps it should not be included here. The purpose of home_offset[] is to
// adjust for inaccurate endstops, not for reasonably accurate probes. If it were
// added here, it could be seen as a compensating factor for the Z probe.
//
current_position[Z_AXIS] = -zprobe_zoffset + (z_tmp - real_z)
uint8_t ind = abl2-1; // last point probe = current point
vector_3 probe_point = vector_3(eqnAMatrix[ind + 0 * abl2], eqnAMatrix[ind + 1 * abl2], eqnBVector[ind]);
probe_point.apply_rotation(inverse_bed_level_matrix);
current_position[Z_AXIS] = -zprobe_zoffset + (probe_point.z - rot_max_diff)
#if HAS_SERVO_ENDSTOPS || ENABLED(Z_PROBE_SLED)
+ Z_RAISE_AFTER_PROBING
#endif
;
// current_position[Z_AXIS] += home_offset[Z_AXIS]; // The probe determines Z=0, not "Z home"
sync_plan_position();
if (debugLevel & DEBUG_INFO) ECHO_LMV(DB, "> AFTER apply_rotation_xyz > current_position[Z_AXIS]= ", current_position[Z_AXIS], 5);
}
#ifdef Z_PROBE_SLED
#if ENABLED(Z_PROBE_SLED)
dock_sled(true); // dock the probe
#endif
if (debugLevel & DEBUG_INFO) ECHO_LM(DB, "<<< gcode_G29");
}
#if DISABLED(Z_PROBE_SLED)
......@@ -3590,14 +3798,16 @@ inline void gcode_G28() {
stow_z_probe(); // Retract Z Servo endstop if available
}
#endif // !Z_PROBE_SLED
#endif // ENABLE_AUTO_BED_LEVELING
#endif // AUTO_BED_LEVELING_FEATURE
#if defined(DELTA) && defined(Z_PROBE_ENDSTOP)
#if ENABLED(DELTA) && ENABLED(Z_PROBE_ENDSTOP)
/**
* G29: Delta Z-Probe, probes the bed at more points.
*/
inline void gcode_G29() {
if (debugLevel & DEBUG_INFO) ECHO_LM(DB, "gcode_G29 >>>");
if (code_seen('D')) {
print_bed_level();
return;
......@@ -3612,6 +3822,8 @@ inline void gcode_G28() {
calibrate_print_surface(z_probe_offset[Z_AXIS] + (code_seen(axis_codes[Z_AXIS]) ? code_value() : 0.0));
retract_z_probe();
if (debugLevel & DEBUG_INFO) ECHO_LM(DB, "<<< gcode_G29");
clean_up_after_endstop_move();
}
......@@ -3646,6 +3858,7 @@ inline void gcode_G28() {
deploy_z_probe();
probe_value = probe_bed(x, y);
if (debugLevel & DEBUG_INFO) {
ECHO_SMV(DB, "Bed Z-Height at X:", x);
ECHO_MV(" Y:", y);
ECHO_EMV(" = ", probe_value, 4);
......@@ -3654,6 +3867,7 @@ inline void gcode_G28() {
ECHO_MV(", ", saved_position[Y_AXIS]);
ECHO_MV(", ", saved_position[Z_AXIS]);
ECHO_EM("]");
}
retract_z_probe();
return;
}
......@@ -4208,7 +4422,7 @@ inline void gcode_M42() {
} // code_seen('S')
}
#if defined(ENABLE_AUTO_BED_LEVELING) && defined(Z_PROBE_REPEATABILITY_TEST)
#if ENABLED(AUTO_BED_LEVELING_FEATURE) && ENABLED(Z_PROBE_REPEATABILITY_TEST)
/**
* M48: Z-Probe repeatability measurement function.
*
......@@ -4431,7 +4645,7 @@ inline void gcode_M42() {
}
#endif // ENABLE_AUTO_BED_LEVELING && Z_PROBE_REPEATABILITY_TEST
#endif // AUTO_BED_LEVELING_FEATURE && Z_PROBE_REPEATABILITY_TEST
#if HAS_POWER_SWITCH
......@@ -4674,12 +4888,17 @@ inline void gcode_M111() {
debugLevel = code_seen('S') ? code_value_short() : DEBUG_INFO|DEBUG_COMMUNICATION;
if (debugLevel & DEBUG_ECHO) ECHO_LM(DB, MSG_DEBUG_ECHO);
//if (debugLevel & DEBUG_INFO) ECHO_LM(DB, MSG_DEBUG_INFO);
if (debugLevel & DEBUG_INFO) ECHO_LM(DB, MSG_DEBUG_INFO);
//if (debugLevel & DEBUG_ERRORS) ECHO_LM(DB, MSG_DEBUG_ERRORS);
if (debugLevel & DEBUG_DRYRUN) {
ECHO_LM(DB, MSG_DEBUG_DRYRUN);
disable_all_heaters();
}
#if ENABLED(DEBUG_LEVELING_FEATURE)
if (debugLevel & DEBUG_LEVELING) {
ECHO_LM(DB, MSG_DEBUG_LEVELING);
}
#endif
}
/**
......@@ -5539,7 +5758,7 @@ inline void gcode_M226() {
*/
inline void gcode_M400() { st_synchronize(); }
#if defined(ENABLE_AUTO_BED_LEVELING) && !defined(Z_PROBE_SLED) && SERVO_LEVELING
#if ENABLED(AUTO_BED_LEVELING_FEATURE) && DISABLED(Z_PROBE_SLED) && SERVO_LEVELING
#if SERVO_LEVELING
void raise_z_for_servo() {
......@@ -5926,7 +6145,7 @@ inline void gcode_M503() {
}
#endif // DUAL_X_CARRIAGE
#ifdef ENABLE_AUTO_BED_LEVELING
#if ENABLED(AUTO_BED_LEVELING_FEATURE)
//M666: Set Z probe offset
inline void gcode_M666() {
if (code_seen('P')) {
......@@ -5939,7 +6158,7 @@ inline void gcode_M503() {
}
#endif
#ifdef DELTA
#if ENABLED(DELTA)
//M666: Set delta endstop and geometry adjustment
inline void gcode_M666() {
if (code_seen('A')) {
......@@ -6094,29 +6313,6 @@ inline void gcode_M999() {
FlushSerialRequestResend();
}
#ifdef CUSTOM_M_CODE_SET_Z_PROBE_OFFSET
inline void gcode_SET_Z_PROBE_OFFSET() {
float value;
if (code_seen('Z')) {
value = code_value();
if (Z_PROBE_OFFSET_RANGE_MIN <= value && value <= Z_PROBE_OFFSET_RANGE_MAX) {
zprobe_zoffset = value;
ECHO_LM(DB, MSG_ZPROBE_ZOFFSET " " OK);
}
else {
ECHO_SM(DB, MSG_ZPROBE_ZOFFSET);
ECHO_MV(MSG_Z_MIN, Z_PROBE_OFFSET_RANGE_MIN);
ECHO_EMV(MSG_Z_MAX, Z_PROBE_OFFSET_RANGE_MAX);
}
}
else {
ECHO_LMV(DB, MSG_ZPROBE_ZOFFSET " : ", zprobe_zoffset);
}
}
#endif // CUSTOM_M_CODE_SET_Z_PROBE_OFFSET
/**
* T0-T3: Switch tool, usually switching extruders
*
......@@ -6177,7 +6373,7 @@ inline void gcode_T(uint8_t tmp_extruder) {
active_extruder = target_extruder;
// This function resets the max/min values - the current position may be overwritten below.
axis_is_at_home(X_AXIS);
set_axis_is_at_home(X_AXIS);
if (dual_x_carriage_mode == DXC_FULL_CONTROL_MODE) {
current_position[X_AXIS] = inactive_extruder_x_pos;
......@@ -6429,10 +6625,10 @@ void process_next_command() {
case 28: //G28: Home all axes, one at a time
gcode_G28(); gcode_M114(); break;
#ifdef ENABLE_AUTO_BED_LEVELING
#if ENABLED(AUTO_BED_LEVELING_FEATURE)
case 29: // G29 Detailed Z-Probe, probes the bed at 3 or more points.
gcode_G29(); gcode_M114(); break;
#ifndef Z_PROBE_SLED
#if DISABLED(Z_PROBE_SLED)
case 30: // G30 Single Z Probe
gcode_G30(); break;
#else // Z_PROBE_SLED
......@@ -6440,7 +6636,7 @@ void process_next_command() {
case 32: // G32: undock the sled
dock_sled(codenum == 31); break;
#endif // Z_PROBE_SLED
#endif // ENABLE_AUTO_BED_LEVELING
#endif // AUTO_BED_LEVELING_FEATURE
#if defined(DELTA) && defined(Z_PROBE_ENDSTOP)
case 29: // G29 Detailed Z-Probe, probes the bed at more points.
......@@ -6527,7 +6723,7 @@ void process_next_command() {
case 42: // M42 -Change pin status via gcode
gcode_M42(); break;
#if defined(ENABLE_AUTO_BED_LEVELING) && defined(Z_PROBE_REPEATABILITY_TEST)
#if ENABLED(AUTO_BED_LEVELING_FEATURE) && ENABLED(Z_PROBE_REPEATABILITY_TEST)
case 48: // M48 Z-Probe repeatability
gcode_M48(); break;
#endif
......@@ -6553,7 +6749,7 @@ void process_next_command() {
case 104: // M104
gcode_M104(); break;
case 105: // M105 Read current temperature
gcode_M105(); return; break; // "ok" already printed
gcode_M105(); return; // "ok" already printed
#if HAS_FAN
case 106: //M106 Fan On
......@@ -6775,7 +6971,7 @@ void process_next_command() {
gcode_M605(); break;
#endif
#if defined(ENABLE_AUTO_BED_LEVELING) || defined(DELTA)
#if ENABLED(AUTO_BED_LEVELING_FEATURE) || ENABLED(DELTA)
case 666: // M666 Set Z probe offset or set delta endstop and geometry adjustment
gcode_M666(); break;
#endif
......@@ -6795,11 +6991,6 @@ void process_next_command() {
case 999: // M999: Restart after being Stopped
gcode_M999(); break;
#ifdef CUSTOM_M_CODE_SET_Z_PROBE_OFFSET
case CUSTOM_M_CODE_SET_Z_PROBE_OFFSET:
gcode_SET_Z_PROBE_OFFSET(); break;
#endif // CUSTOM_M_CODE_SET_Z_PROBE_OFFSET
}
break;
......@@ -6845,7 +7036,7 @@ void clamp_to_software_endstops(float target[3]) {
NOLESS(target[Y_AXIS], min_pos[Y_AXIS]);
float negative_z_offset = 0;
#ifdef ENABLE_AUTO_BED_LEVELING
#if ENABLED(AUTO_BED_LEVELING_FEATURE)
if (zprobe_zoffset < 0) negative_z_offset += zprobe_zoffset;
if (home_offset[Z_AXIS] < 0) negative_z_offset += home_offset[Z_AXIS];
#endif
......@@ -7025,6 +7216,11 @@ void prepare_move() {
if (!prepare_move_cartesian()) return;
#endif
#ifdef IDLE_OOZING_PREVENT || EXTRUDER_RUNOUT_PREVENT
axis_last_activity = millis();
axis_is_moving = false;
#endif
set_current_to_destination();
}
......
......@@ -102,4 +102,3 @@ void NexText::detachPop(void)
{
NexTouch::detachPop();
}
......@@ -316,8 +316,8 @@ void CardReader::openFile(char* name, bool read, bool replace_current/*=true*/,
subdirname[dirname_end - dirname_start] = 0;
ECHO_EV(subdirname);
if (!myDir.open(curDir, subdirname, O_READ)) {
ECHO_MV(MSG_SD_OPEN_FILE_FAIL, subdirname);
ECHO_C('.');
ECHO_SMV(ER, MSG_SD_OPEN_FILE_FAIL, subdirname);
ECHO_EM(".");
return;
}
else {
......@@ -357,12 +357,12 @@ void CardReader::openFile(char* name, bool read, bool replace_current/*=true*/,
}
else { //write
if (!file.open(curDir, fname, O_CREAT | O_APPEND | O_WRITE | O_TRUNC)) {
ECHO_MV(MSG_SD_OPEN_FILE_FAIL, fname);
ECHO_PGM(".\n");
ECHO_SMV(ER, MSG_SD_OPEN_FILE_FAIL, fname);
ECHO_EM(".");
}
else {
saving = true;
ECHO_EMV(MSG_SD_WRITE_TO_FILE, name);
ECHO_LMV(DB, MSG_SD_WRITE_TO_FILE, name);
if(lcd_status) lcd_setstatus(fname);
}
}
......@@ -389,8 +389,8 @@ void CardReader::removeFile(char* name) {
subdirname[dirname_end - dirname_start] = 0;
ECHO_EV(subdirname);
if (!myDir.open(curDir, subdirname, O_READ)) {
ECHO_MV(MSG_SD_OPEN_FILE_FAIL, subdirname);
ECHO_C('.');
ECHO_SMV(DB, MSG_SD_OPEN_FILE_FAIL, subdirname);
ECHO_EM(".");
return;
}
......
......@@ -366,7 +366,7 @@
/**
* Auto Bed Leveling
*/
#if ENABLED(ENABLE_AUTO_BED_LEVELING)
#if ENABLED(AUTO_BED_LEVELING_FEATURE)
// Boundaries for probing based on set limits
#define MIN_PROBE_X (max(X_MIN_POS, X_MIN_POS + X_PROBE_OFFSET_FROM_EXTRUDER))
#define MAX_PROBE_X (min(X_MAX_POS, X_MAX_POS + X_PROBE_OFFSET_FROM_EXTRUDER))
......
......@@ -488,7 +488,7 @@ void Config_ResetDefault() {
max_z_jerk = DEFAULT_ZJERK;
home_offset[X_AXIS] = home_offset[Y_AXIS] = home_offset[Z_AXIS] = 0;
#if ENABLED(ENABLE_AUTO_BED_LEVELING)
#if ENABLED(AUTO_BED_LEVELING_FEATURE)
zprobe_zoffset = Z_PROBE_OFFSET_FROM_EXTRUDER;
#elif !defined(DELTA)
zprobe_zoffset = 0;
......@@ -718,7 +718,7 @@ void Config_ResetDefault() {
ECHO_LM(DB, "Z2 Endstop adjustement (mm):");
}
ECHO_LMV(DB, " M666 Z", z_endstop_adj );
#elif ENABLED(ENABLE_AUTO_BED_LEVELING)
#elif ENABLED(AUTO_BED_LEVELING_FEATURE)
if (!forReplay) {
ECHO_LM(DB, "Z Probe offset (mm)");
}
......
......@@ -113,7 +113,6 @@
#define MSG_COUNT_X " Count X: "
#define MSG_ERR_KILLED "Printer halted. kill() called!"
#define MSG_ERR_STOPPED "Printer stopped due to errors. Fix the error and use M999 to restart. (Temperature is reset. Set it after restarting)"
#define MSG_RESEND "Resend: "
#define MSG_UNKNOWN_COMMAND "Unknown command: \""
#define MSG_ACTIVE_DRIVER "Active Driver: "
#define MSG_ACTIVE_EXTRUDER "Active Extruder: "
......
......@@ -749,7 +749,7 @@
#define LED_PIN -1
//pin for controlling the PSU.
#define PS_ON_PIN 14 //Alex, Do this work on the card?
#define PS_ON_PIN 14
//Alex extras from Gen3+
#define KILL_PIN -1
......@@ -916,7 +916,7 @@
#define ORIG_HEATER_BED_PIN 8 // BED
#define ORIG_TEMP_BED_PIN 14 // ANALOG NUMBERING
#if ENABLED(REPRAP_DISCOUNT_SMART_CONTROLLER) || ENABLED(G3D_PANEL)
#if defined(REPRAP_DISCOUNT_SMART_CONTROLLER) || defined(G3D_PANEL)
#define KILL_PIN 41
#else
#define KILL_PIN -1
......@@ -3607,7 +3607,6 @@
#define BEEPER_PIN -1
#define LCD_PINS_RS -1
#define LCD_PINS_ENABLE -1
#define LCD_PINS_D4 -1
......@@ -3615,7 +3614,6 @@
#define LCD_PINS_D6 -1
#define LCD_PINS_D7 -1
//buttons are directly attached using keypad
#define BTN_EN1 -1
#define BTN_EN2 -1
......
......@@ -74,14 +74,14 @@ float mintravelfeedrate;
unsigned long axis_steps_per_sqr_second[3 + EXTRUDERS];
uint8_t last_extruder;
#if ENABLED(ENABLE_AUTO_BED_LEVELING)
#if ENABLED(AUTO_BED_LEVELING_FEATURE)
// Transform required to compensate for bed level
matrix_3x3 plan_bed_level_matrix = {
1.0, 0.0, 0.0,
0.0, 1.0, 0.0,
0.0, 0.0, 1.0
};
#endif // ENABLE_AUTO_BED_LEVELING
#endif // AUTO_BED_LEVELING_FEATURE
#if ENABLED(AUTOTEMP)
float autotemp_max = 250;
......@@ -480,11 +480,11 @@ float junction_deviation = 0.1;
// Add a new linear movement to the buffer. steps[X_AXIS], _y and _z is the absolute position in
// mm. Microseconds specify how many microseconds the move should take to perform. To aid acceleration
// calculation the caller must also provide the physical length of the line in millimeters.
#if ENABLED(ENABLE_AUTO_BED_LEVELING)
#if ENABLED(AUTO_BED_LEVELING_FEATURE)
void plan_buffer_line(float x, float y, float z, const float &e, float feed_rate, const uint8_t &extruder, const uint8_t &driver)
#else
void plan_buffer_line(const float &x, const float &y, const float &z, const float &e, float feed_rate, const uint8_t &extruder, const uint8_t &driver)
#endif // ENABLE_AUTO_BED_LEVELING
#endif // AUTO_BED_LEVELING_FEATURE
{
// Calculate the buffer head after we push this byte
int next_buffer_head = next_block_index(block_buffer_head);
......@@ -493,7 +493,7 @@ float junction_deviation = 0.1;
// Rest here until there is room in the buffer.
while (block_buffer_tail == next_buffer_head) idle();
#if ENABLED(ENABLE_AUTO_BED_LEVELING)
#if ENABLED(AUTO_BED_LEVELING_FEATURE)
apply_rotation_xyz(plan_bed_level_matrix, x, y, z);
#endif
......@@ -1040,7 +1040,7 @@ float junction_deviation = 0.1;
} // plan_buffer_line()
#if ENABLED(ENABLE_AUTO_BED_LEVELING)
#if ENABLED(AUTO_BED_LEVELING_FEATURE)
vector_3 plan_get_position() {
vector_3 position = vector_3(st_get_position_mm(X_AXIS), st_get_position_mm(Y_AXIS), st_get_position_mm(Z_AXIS));
......@@ -1053,15 +1053,15 @@ float junction_deviation = 0.1;
return position;
}
#endif // ENABLE_AUTO_BED_LEVELING
#endif // AUTO_BED_LEVELING_FEATURE
#if ENABLED(ENABLE_AUTO_BED_LEVELING)
#if ENABLED(AUTO_BED_LEVELING_FEATURE)
void plan_set_position(float x, float y, float z, const float &e)
#else
void plan_set_position(const float &x, const float &y, const float &z, const float &e)
#endif // ENABLE_AUTO_BED_LEVELING
#endif // AUTO_BED_LEVELING_FEATURE
{
#if ENABLED(ENABLE_AUTO_BED_LEVELING)
#if ENABLED(AUTO_BED_LEVELING_FEATURE)
apply_rotation_xyz(plan_bed_level_matrix, x, y, z);
#endif
......
......@@ -82,7 +82,7 @@ extern volatile unsigned char block_buffer_head;
extern volatile unsigned char block_buffer_tail;
FORCE_INLINE uint8_t movesplanned() { return BLOCK_MOD(block_buffer_head - block_buffer_tail + BLOCK_BUFFER_SIZE); }
#if ENABLED(ENABLE_AUTO_BED_LEVELING)
#if ENABLED(AUTO_BED_LEVELING_FEATURE)
#include "vector_3.h"
......@@ -110,7 +110,7 @@ FORCE_INLINE uint8_t movesplanned() { return BLOCK_MOD(block_buffer_head - block
#else
void plan_buffer_line(const float &x, const float &y, const float &z, const float &e, float feed_rate, const uint8_t &extruder, const uint8_t &driver);
void plan_set_position(const float &x, const float &y, const float &z, const float &e);
#endif // ENABLE_AUTO_BED_LEVELING
#endif // AUTO_BED_LEVELING_FEATURE
void plan_set_e_position(const float &e);
......
......@@ -260,7 +260,7 @@ double r8mat_amax ( int m, int n, double a[] )
return value;
}
void r8mat_copy( double a2[], int m, int n, double a1[] )
double *r8mat_copy_new ( int m, int n, double a1[] )
/******************************************************************************/
/*
......@@ -294,9 +294,12 @@ void r8mat_copy( double a2[], int m, int n, double a1[] )
Output, double R8MAT_COPY_NEW[M*N], the copy of A1.
*/
{
double *a2;
int i;
int j;
a2 = ( double * ) malloc ( m * n * sizeof ( double ) );
for ( j = 0; j < n; j++ )
{
for ( i = 0; i < m; i++ )
......@@ -304,6 +307,8 @@ void r8mat_copy( double a2[], int m, int n, double a1[] )
a2[i+j*m] = a1[i+j*m];
}
}
return a2;
}
/******************************************************************************/
......@@ -721,13 +726,14 @@ void dqrank ( double a[], int lda, int m, int n, double tol, int *kr,
int j;
int job;
int k;
double work[n];
double *work;
for ( i = 0; i < n; i++ )
{
jpvt[i] = 0;
}
work = ( double * ) malloc ( n * sizeof ( double ) );
job = 1;
dqrdc ( a, lda, m, n, qraux, jpvt, work, job );
......@@ -744,6 +750,8 @@ void dqrank ( double a[], int lda, int m, int n, double tol, int *kr,
*kr = j + 1;
}
free ( work );
return;
}
/******************************************************************************/
......@@ -1837,7 +1845,7 @@ void dswap ( int n, double x[], int incx, double y[], int incy )
/******************************************************************************/
void qr_solve ( double x[], int m, int n, double a[], double b[] )
double *qr_solve ( int m, int n, double a[], double b[] )
/******************************************************************************/
/*
......@@ -1887,22 +1895,34 @@ void qr_solve ( double x[], int m, int n, double a[], double b[] )
Output, double QR_SOLVE[N], the least squares solution.
*/
{
double a_qr[n*m];
double *a_qr;
int ind;
int itask;
int jpvt[n];
int *jpvt;
int kr;
int lda;
double qraux[n];
double r[m];
double *qraux;
double *r;
double tol;
double *x;
r8mat_copy( a_qr, m, n, a );
a_qr = r8mat_copy_new ( m, n, a );
lda = m;
tol = r8_epsilon ( ) / r8mat_amax ( m, n, a_qr );
x = ( double * ) malloc ( n * sizeof ( double ) );
jpvt = ( int * ) malloc ( n * sizeof ( int ) );
qraux = ( double * ) malloc ( n * sizeof ( double ) );
r = ( double * ) malloc ( m * sizeof ( double ) );
itask = 1;
ind = dqrls ( a_qr, lda, m, n, tol, &kr, b, x, r, jpvt, qraux, itask );
free ( a_qr );
free ( jpvt );
free ( qraux );
free ( r );
return x;
}
/******************************************************************************/
......
......@@ -17,6 +17,6 @@ int dqrsl ( double a[], int lda, int n, int k, double qraux[], double y[],
double qy[], double qty[], double b[], double rsd[], double ab[], int job );
void dscal ( int n, double sa, double x[], int incx );
void dswap ( int n, double x[], int incx, double y[], int incy );
void qr_solve ( double x[], int m, int n, double a[], double b[] );
double *qr_solve ( int m, int n, double a[], double b[] );
#endif
......@@ -124,7 +124,7 @@
/**
* Auto Bed Leveling
*/
#if ENABLED(ENABLE_AUTO_BED_LEVELING)
#if ENABLED(AUTO_BED_LEVELING_FEATURE)
/**
* Require a Z Min pin
......@@ -134,7 +134,7 @@
#if ENABLED(Z_PROBE_REPEATABILITY_TEST)
#error You must have a Z_MIN or Z_PROBE endstop to enable Z_PROBE_REPEATABILITY_TEST.
#else
#error ENABLE_AUTO_BED_LEVELING requires a Z_MIN or Z_PROBE endstop. Z_MIN_PIN or Z_PROBE_PIN must point to a valid hardware pin.
#error AUTO_BED_LEVELING_FEATURE requires a Z_MIN or Z_PROBE endstop. Z_MIN_PIN or Z_PROBE_PIN must point to a valid hardware pin.
#endif
#endif
#endif
......@@ -203,7 +203,7 @@
#endif // !AUTO_BED_LEVELING_GRID
#endif // ENABLE_AUTO_BED_LEVELING
#endif // AUTO_BED_LEVELING_FEATURE
/**
* ULTIPANEL encoder
......
......@@ -666,7 +666,7 @@ ISR(TIMER1_COMPA_vect) {
STEP_START(e,E);
#endif
#ifdef STEPPER_HIGH_LOW_DELAY
#if ENABLED(STEPPER_HIGH_LOW_DELAY)
delayMicroseconds(STEPPER_HIGH_LOW_DELAY);
#endif
......
......@@ -221,4 +221,3 @@ void L6470_init()
#endif
}
#endif
......@@ -626,69 +626,30 @@ const short temptable_11[][2] PROGMEM = {
// Hisens thermistor B25/50 =3950 +/-1%
const short temptable_13[][2] PROGMEM = {
{22.5 * OVERSAMPLENR, 300},
{24.125 * OVERSAMPLENR, 295},
{25.875 * OVERSAMPLENR, 290},
{27.8125 * OVERSAMPLENR, 285},
{29.9375 * OVERSAMPLENR, 280},
{32.25 * OVERSAMPLENR, 275},
{34.8125 * OVERSAMPLENR, 270},
{37.625 * OVERSAMPLENR, 265},
{40.6875 * OVERSAMPLENR, 260},
{44.0625 * OVERSAMPLENR, 255},
{47.75 * OVERSAMPLENR, 250},
{51.8125 * OVERSAMPLENR, 245},
{56.3125 * OVERSAMPLENR, 240},
{61.25 * OVERSAMPLENR, 235},
{66.75 * OVERSAMPLENR, 230},
{72.8125 * OVERSAMPLENR, 225},
{79.5 * OVERSAMPLENR, 220},
{87 * OVERSAMPLENR, 215},
{95.3125 * OVERSAMPLENR, 210},
{104.1875 * OVERSAMPLENR, 205},
{112.75 * OVERSAMPLENR, 200},
{123.125 * OVERSAMPLENR, 195},
{135.75 * OVERSAMPLENR, 190},
{148.3125 * OVERSAMPLENR, 185},
{163.8125 * OVERSAMPLENR, 180},
{179 * OVERSAMPLENR, 175},
{211.125 * OVERSAMPLENR, 170},
{216.125 * OVERSAMPLENR, 165},
{236.5625 * OVERSAMPLENR, 160},
{258.5 * OVERSAMPLENR, 155},
{279.875 * OVERSAMPLENR, 150},
{305.375 * OVERSAMPLENR, 145},
{333.25 * OVERSAMPLENR, 140},
{362.5625 * OVERSAMPLENR, 135},
{393.6875 * OVERSAMPLENR, 130},
{425 * OVERSAMPLENR, 125},
{460.625 * OVERSAMPLENR, 120},
{495.1875 * OVERSAMPLENR, 115},
{530.875 * OVERSAMPLENR, 110},
{567.25 * OVERSAMPLENR, 105},
{601.625 * OVERSAMPLENR, 100},
{637.875 * OVERSAMPLENR, 95},
{674.5625 * OVERSAMPLENR, 90},
{710 * OVERSAMPLENR, 85},
{744.125 * OVERSAMPLENR, 80},
{775.9375 * OVERSAMPLENR, 75},
{806.875 * OVERSAMPLENR, 70},
{835.1875 * OVERSAMPLENR, 65},
{861.125 * OVERSAMPLENR, 60},
{884.375 * OVERSAMPLENR, 55},
{904.5625 * OVERSAMPLENR, 50},
{923.8125 * OVERSAMPLENR, 45},
{940.375 * OVERSAMPLENR, 40},
{954.625 * OVERSAMPLENR, 35},
{966.875 * OVERSAMPLENR, 30},
{977.0625 * OVERSAMPLENR, 25},
{986 * OVERSAMPLENR, 20},
{993.375 * OVERSAMPLENR, 15},
{999.5 * OVERSAMPLENR, 10},
{1004.5 * OVERSAMPLENR, 5},
{1008.5 * OVERSAMPLENR, 0}
};
{20.04*OVERSAMPLENR, 300 },
{23.19*OVERSAMPLENR, 290 },
{26.71*OVERSAMPLENR, 280 },
{31.23*OVERSAMPLENR, 270 },
{36.52*OVERSAMPLENR, 260 },
{42.75*OVERSAMPLENR, 250 },
{50.68*OVERSAMPLENR, 240 },
{60.22*OVERSAMPLENR, 230 },
{72.03*OVERSAMPLENR, 220 },
{86.84*OVERSAMPLENR, 210 },
{102.79*OVERSAMPLENR, 200 },
{124.46*OVERSAMPLENR, 190 },
{151.02*OVERSAMPLENR, 180 },
{182.86*OVERSAMPLENR, 170 },
{220.72*OVERSAMPLENR, 160 },
{316.96*OVERSAMPLENR, 140 },
{447.17*OVERSAMPLENR, 120 },
{590.61*OVERSAMPLENR, 100 },
{737.31*OVERSAMPLENR, 80 },
{857.77*OVERSAMPLENR, 60 },
{939.52*OVERSAMPLENR, 40 },
{986.03*OVERSAMPLENR, 20 },
{1008.7*OVERSAMPLENR, 0}
};
#endif
#if (THERMISTORHEATER_0 == 20) || (THERMISTORHEATER_1 == 20) || (THERMISTORHEATER_2 == 20) || (THERMISTORBED == 20) // PT100 with INA826 amp on Ultimaker v2.0 electronics
......
......@@ -724,7 +724,7 @@ static void lcd_prepare_menu() {
//
// Level Bed
//
#if ENABLED(ENABLE_AUTO_BED_LEVELING)
#if ENABLED(AUTO_BED_LEVELING_FEATURE)
if (axis_known_position[X_AXIS] && axis_known_position[Y_AXIS])
MENU_ITEM(gcode, MSG_LEVEL_BED, PSTR("G29"));
#elif DISABLED(DELTA) && DISABLED(Z_SAFE_HOMING) && Z_HOME_DIR < 0
......@@ -1165,7 +1165,7 @@ static void lcd_control_temperature_preheat_gum_settings_menu() {
static void lcd_control_motion_menu() {
START_MENU(lcd_control_menu);
MENU_ITEM(back, MSG_CONTROL, lcd_control_menu);
#if ENABLED(ENABLE_AUTO_BED_LEVELING)
#if ENABLED(AUTO_BED_LEVELING_FEATURE)
MENU_ITEM_EDIT(float32, MSG_ZPROBE_ZOFFSET, &zprobe_zoffset, -50, 50);
#endif
MENU_ITEM_EDIT(float5, MSG_ACC, &acceleration, 10, 99000);
......
......@@ -19,7 +19,7 @@
#include <math.h>
#include "Marlin.h"
#if ENABLED(ENABLE_AUTO_BED_LEVELING)
#if ENABLED(AUTO_BED_LEVELING_FEATURE)
#include "vector_3.h"
vector_3::vector_3() : x(0), y(0), z(0) { }
......@@ -131,4 +131,4 @@ void matrix_3x3::debug(const char title[]) {
}
}
#endif // ENABLE_AUTO_BED_LEVELING
#endif // AUTO_BED_LEVELING_FEATURE
......@@ -19,7 +19,7 @@
#ifndef VECTOR_3_H
#define VECTOR_3_H
#if ENABLED(ENABLE_AUTO_BED_LEVELING)
#if ENABLED(AUTO_BED_LEVELING_FEATURE)
class matrix_3x3;
struct vector_3
......@@ -57,6 +57,6 @@ struct matrix_3x3
void apply_rotation_xyz(matrix_3x3 rotationMatrix, float &x, float& y, float& z);
#endif // ENABLE_AUTO_BED_LEVELING
#endif // AUTO_BED_LEVELING_FEATURE
#endif // VECTOR_3_H
......@@ -34,7 +34,7 @@ Adding commands to facilitate purging of hotend.
Step per unit varied for each extruder as well as the feedrate.
The addition of a different feedrate for retraction.
Adding Debug Dryrun used by repetier.
Added total Power on time writec in SD CARD.
Added total Power on time writed in SD CARD.
Added total Power consumption writed in SD CARD.
Added anti extruder idle oozing system.
## Credits
......
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