Consolidate "bedlevel" code
This commit is contained in:
parent
71aefc2e22
commit
551752eac7
File diff suppressed because it is too large
Load diff
|
@ -48,10 +48,6 @@ void idle(
|
||||||
|
|
||||||
void manage_inactivity(bool ignore_stepper_queue = false);
|
void manage_inactivity(bool ignore_stepper_queue = false);
|
||||||
|
|
||||||
#if ENABLED(DUAL_X_CARRIAGE) || ENABLED(DUAL_NOZZLE_DUPLICATION_MODE)
|
|
||||||
extern bool extruder_duplication_enabled;
|
|
||||||
#endif
|
|
||||||
|
|
||||||
#if HAS_X2_ENABLE
|
#if HAS_X2_ENABLE
|
||||||
#define enable_X() do{ X_ENABLE_WRITE( X_ENABLE_ON); X2_ENABLE_WRITE( X_ENABLE_ON); }while(0)
|
#define enable_X() do{ X_ENABLE_WRITE( X_ENABLE_ON); X2_ENABLE_WRITE( X_ENABLE_ON); }while(0)
|
||||||
#define disable_X() do{ X_ENABLE_WRITE(!X_ENABLE_ON); X2_ENABLE_WRITE(!X_ENABLE_ON); axis_known_position[X_AXIS] = false; }while(0)
|
#define disable_X() do{ X_ENABLE_WRITE(!X_ENABLE_ON); X2_ENABLE_WRITE(!X_ENABLE_ON); axis_known_position[X_AXIS] = false; }while(0)
|
||||||
|
@ -179,13 +175,6 @@ extern bool Running;
|
||||||
inline bool IsRunning() { return Running; }
|
inline bool IsRunning() { return Running; }
|
||||||
inline bool IsStopped() { return !Running; }
|
inline bool IsStopped() { return !Running; }
|
||||||
|
|
||||||
/**
|
|
||||||
* Feedrate scaling and conversion
|
|
||||||
*/
|
|
||||||
extern int16_t feedrate_percentage;
|
|
||||||
|
|
||||||
#define MMS_SCALED(MM_S) ((MM_S)*feedrate_percentage*0.01)
|
|
||||||
|
|
||||||
extern float filament_size[EXTRUDERS]; // cross-sectional area of filament (in millimeters), typically around 1.75 or 2.85, 0 disables the volumetric calculations for the extruder.
|
extern float filament_size[EXTRUDERS]; // cross-sectional area of filament (in millimeters), typically around 1.75 or 2.85, 0 disables the volumetric calculations for the extruder.
|
||||||
extern float volumetric_multiplier[EXTRUDERS]; // reciprocal of cross-sectional area of filament (in square millimeters), stored this way to reduce computational burden in planner
|
extern float volumetric_multiplier[EXTRUDERS]; // reciprocal of cross-sectional area of filament (in square millimeters), stored this way to reduce computational burden in planner
|
||||||
|
|
||||||
|
@ -197,71 +186,23 @@ extern volatile bool wait_for_heatup;
|
||||||
extern volatile bool wait_for_user;
|
extern volatile bool wait_for_user;
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
// Hotend Offsets
|
|
||||||
#if HOTENDS > 1
|
|
||||||
extern float hotend_offset[XYZ][HOTENDS];
|
|
||||||
#endif
|
|
||||||
|
|
||||||
// Software Endstops
|
|
||||||
extern float soft_endstop_min[XYZ], soft_endstop_max[XYZ];
|
|
||||||
|
|
||||||
#if HAS_WORKSPACE_OFFSET || ENABLED(DUAL_X_CARRIAGE)
|
|
||||||
void update_software_endstops(const AxisEnum axis);
|
|
||||||
#endif
|
|
||||||
|
|
||||||
#if IS_KINEMATIC
|
|
||||||
extern float delta[ABC];
|
|
||||||
void inverse_kinematics(const float logical[XYZ]);
|
|
||||||
#endif
|
|
||||||
|
|
||||||
#if ENABLED(DELTA)
|
|
||||||
extern float endstop_adj[ABC],
|
|
||||||
delta_radius,
|
|
||||||
delta_diagonal_rod,
|
|
||||||
delta_calibration_radius,
|
|
||||||
delta_segments_per_second,
|
|
||||||
delta_tower_angle_trim[2],
|
|
||||||
delta_clip_start_height;
|
|
||||||
void recalc_delta_settings(float radius, float diagonal_rod);
|
|
||||||
#elif IS_SCARA
|
|
||||||
void forward_kinematics_SCARA(const float &a, const float &b);
|
|
||||||
#endif
|
|
||||||
|
|
||||||
#if ENABLED(AUTO_BED_LEVELING_BILINEAR)
|
|
||||||
extern int bilinear_grid_spacing[2], bilinear_start[2];
|
|
||||||
extern float bilinear_grid_factor[2],
|
|
||||||
z_values[GRID_MAX_POINTS_X][GRID_MAX_POINTS_Y];
|
|
||||||
float bilinear_z_offset(const float logical[XYZ]);
|
|
||||||
#endif
|
|
||||||
|
|
||||||
#if ENABLED(AUTO_BED_LEVELING_UBL)
|
#if ENABLED(AUTO_BED_LEVELING_UBL)
|
||||||
typedef struct { double A, B, D; } linear_fit;
|
typedef struct { double A, B, D; } linear_fit;
|
||||||
linear_fit* lsf_linear_fit(double x[], double y[], double z[], const int);
|
linear_fit* lsf_linear_fit(double x[], double y[], double z[], const int);
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#if HAS_LEVELING
|
|
||||||
bool leveling_is_valid();
|
|
||||||
bool leveling_is_active();
|
|
||||||
void set_bed_leveling_enabled(const bool enable=true);
|
|
||||||
void reset_bed_level();
|
|
||||||
#endif
|
|
||||||
|
|
||||||
#if ENABLED(ENABLE_LEVELING_FADE_HEIGHT)
|
|
||||||
void set_z_fade_height(const float zfh);
|
|
||||||
#endif
|
|
||||||
|
|
||||||
#if ENABLED(Z_DUAL_ENDSTOPS)
|
#if ENABLED(Z_DUAL_ENDSTOPS)
|
||||||
extern float z_endstop_adj;
|
extern float z_endstop_adj;
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#if HAS_BED_PROBE
|
#if HAS_SERVOS
|
||||||
extern float zprobe_zoffset;
|
#include "HAL/servo.h"
|
||||||
void refresh_zprobe_zoffset(const bool no_babystep=false);
|
extern HAL_SERVO_LIB servo[NUM_SERVOS];
|
||||||
#define DEPLOY_PROBE() set_probe_deployed(true)
|
#define MOVE_SERVO(I, P) servo[I].move(P)
|
||||||
#define STOW_PROBE() set_probe_deployed(false)
|
#if HAS_Z_SERVO_ENDSTOP
|
||||||
#else
|
#define DEPLOY_Z_SERVO() MOVE_SERVO(Z_ENDSTOP_SERVO_NR, z_servo_angle[0])
|
||||||
#define DEPLOY_PROBE()
|
#define STOW_Z_SERVO() MOVE_SERVO(Z_ENDSTOP_SERVO_NR, z_servo_angle[1])
|
||||||
#define STOW_PROBE()
|
#endif
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#if FAN_COUNT > 0
|
#if FAN_COUNT > 0
|
||||||
|
@ -309,16 +250,4 @@ extern float soft_endstop_min[XYZ], soft_endstop_max[XYZ];
|
||||||
|
|
||||||
void calculate_volumetric_multipliers();
|
void calculate_volumetric_multipliers();
|
||||||
|
|
||||||
/**
|
|
||||||
* Blocking movement and shorthand functions
|
|
||||||
*/
|
|
||||||
void do_blocking_move_to(const float &x, const float &y, const float &z, const float &fr_mm_s=0.0);
|
|
||||||
void do_blocking_move_to_x(const float &x, const float &fr_mm_s=0.0);
|
|
||||||
void do_blocking_move_to_z(const float &z, const float &fr_mm_s=0.0);
|
|
||||||
void do_blocking_move_to_xy(const float &x, const float &y, const float &fr_mm_s=0.0);
|
|
||||||
|
|
||||||
#if ENABLED(Z_PROBE_ALLEN_KEY) || ENABLED(Z_PROBE_SLED) || HAS_PROBING_PROCEDURE || HOTENDS > 1 || ENABLED(NOZZLE_CLEAN_FEATURE) || ENABLED(NOZZLE_PARK_FEATURE)
|
|
||||||
bool axis_unhomed_error(const bool x=true, const bool y=true, const bool z=true);
|
|
||||||
#endif
|
|
||||||
|
|
||||||
#endif // __MARLIN_H__
|
#endif // __MARLIN_H__
|
||||||
|
|
425
Marlin/src/feature/bedlevel/abl/abl.cpp
Normal file
425
Marlin/src/feature/bedlevel/abl/abl.cpp
Normal file
|
@ -0,0 +1,425 @@
|
||||||
|
/**
|
||||||
|
* Marlin 3D Printer Firmware
|
||||||
|
* Copyright (C) 2016 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
|
||||||
|
*
|
||||||
|
* Based on Sprinter and grbl.
|
||||||
|
* Copyright (C) 2011 Camiel Gubbels / Erik van der Zalm
|
||||||
|
*
|
||||||
|
* This program is free software: you can redistribute it and/or modify
|
||||||
|
* it under the terms of the GNU General Public License as published by
|
||||||
|
* the Free Software Foundation, either version 3 of the License, or
|
||||||
|
* (at your option) any later version.
|
||||||
|
*
|
||||||
|
* This program is distributed in the hope that it will be useful,
|
||||||
|
* but WITHOUT ANY WARRANTY; without even the implied warranty of
|
||||||
|
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
|
||||||
|
* GNU General Public License for more details.
|
||||||
|
*
|
||||||
|
* You should have received a copy of the GNU General Public License
|
||||||
|
* along with this program. If not, see <http://www.gnu.org/licenses/>.
|
||||||
|
*
|
||||||
|
*/
|
||||||
|
|
||||||
|
#include "../../../inc/MarlinConfig.h"
|
||||||
|
|
||||||
|
#if ENABLED(AUTO_BED_LEVELING_BILINEAR)
|
||||||
|
|
||||||
|
#include "abl.h"
|
||||||
|
|
||||||
|
#include "../../../module/motion.h"
|
||||||
|
|
||||||
|
int bilinear_grid_spacing[2], bilinear_start[2];
|
||||||
|
float bilinear_grid_factor[2],
|
||||||
|
z_values[GRID_MAX_POINTS_X][GRID_MAX_POINTS_Y];
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Extrapolate a single point from its neighbors
|
||||||
|
*/
|
||||||
|
static void extrapolate_one_point(const uint8_t x, const uint8_t y, const int8_t xdir, const int8_t ydir) {
|
||||||
|
#if ENABLED(DEBUG_LEVELING_FEATURE)
|
||||||
|
if (DEBUGGING(LEVELING)) {
|
||||||
|
SERIAL_ECHOPGM("Extrapolate [");
|
||||||
|
if (x < 10) SERIAL_CHAR(' ');
|
||||||
|
SERIAL_ECHO((int)x);
|
||||||
|
SERIAL_CHAR(xdir ? (xdir > 0 ? '+' : '-') : ' ');
|
||||||
|
SERIAL_CHAR(' ');
|
||||||
|
if (y < 10) SERIAL_CHAR(' ');
|
||||||
|
SERIAL_ECHO((int)y);
|
||||||
|
SERIAL_CHAR(ydir ? (ydir > 0 ? '+' : '-') : ' ');
|
||||||
|
SERIAL_CHAR(']');
|
||||||
|
}
|
||||||
|
#endif
|
||||||
|
if (!isnan(z_values[x][y])) {
|
||||||
|
#if ENABLED(DEBUG_LEVELING_FEATURE)
|
||||||
|
if (DEBUGGING(LEVELING)) SERIAL_ECHOLNPGM(" (done)");
|
||||||
|
#endif
|
||||||
|
return; // Don't overwrite good values.
|
||||||
|
}
|
||||||
|
SERIAL_EOL();
|
||||||
|
|
||||||
|
// Get X neighbors, Y neighbors, and XY neighbors
|
||||||
|
const uint8_t x1 = x + xdir, y1 = y + ydir, x2 = x1 + xdir, y2 = y1 + ydir;
|
||||||
|
float a1 = z_values[x1][y ], a2 = z_values[x2][y ],
|
||||||
|
b1 = z_values[x ][y1], b2 = z_values[x ][y2],
|
||||||
|
c1 = z_values[x1][y1], c2 = z_values[x2][y2];
|
||||||
|
|
||||||
|
// Treat far unprobed points as zero, near as equal to far
|
||||||
|
if (isnan(a2)) a2 = 0.0; if (isnan(a1)) a1 = a2;
|
||||||
|
if (isnan(b2)) b2 = 0.0; if (isnan(b1)) b1 = b2;
|
||||||
|
if (isnan(c2)) c2 = 0.0; if (isnan(c1)) c1 = c2;
|
||||||
|
|
||||||
|
const float a = 2 * a1 - a2, b = 2 * b1 - b2, c = 2 * c1 - c2;
|
||||||
|
|
||||||
|
// Take the average instead of the median
|
||||||
|
z_values[x][y] = (a + b + c) / 3.0;
|
||||||
|
|
||||||
|
// Median is robust (ignores outliers).
|
||||||
|
// z_values[x][y] = (a < b) ? ((b < c) ? b : (c < a) ? a : c)
|
||||||
|
// : ((c < b) ? b : (a < c) ? a : c);
|
||||||
|
}
|
||||||
|
|
||||||
|
//Enable this if your SCARA uses 180° of total area
|
||||||
|
//#define EXTRAPOLATE_FROM_EDGE
|
||||||
|
|
||||||
|
#if ENABLED(EXTRAPOLATE_FROM_EDGE)
|
||||||
|
#if GRID_MAX_POINTS_X < GRID_MAX_POINTS_Y
|
||||||
|
#define HALF_IN_X
|
||||||
|
#elif GRID_MAX_POINTS_Y < GRID_MAX_POINTS_X
|
||||||
|
#define HALF_IN_Y
|
||||||
|
#endif
|
||||||
|
#endif
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Fill in the unprobed points (corners of circular print surface)
|
||||||
|
* using linear extrapolation, away from the center.
|
||||||
|
*/
|
||||||
|
void extrapolate_unprobed_bed_level() {
|
||||||
|
#ifdef HALF_IN_X
|
||||||
|
constexpr uint8_t ctrx2 = 0, xlen = GRID_MAX_POINTS_X - 1;
|
||||||
|
#else
|
||||||
|
constexpr uint8_t ctrx1 = (GRID_MAX_POINTS_X - 1) / 2, // left-of-center
|
||||||
|
ctrx2 = (GRID_MAX_POINTS_X) / 2, // right-of-center
|
||||||
|
xlen = ctrx1;
|
||||||
|
#endif
|
||||||
|
|
||||||
|
#ifdef HALF_IN_Y
|
||||||
|
constexpr uint8_t ctry2 = 0, ylen = GRID_MAX_POINTS_Y - 1;
|
||||||
|
#else
|
||||||
|
constexpr uint8_t ctry1 = (GRID_MAX_POINTS_Y - 1) / 2, // top-of-center
|
||||||
|
ctry2 = (GRID_MAX_POINTS_Y) / 2, // bottom-of-center
|
||||||
|
ylen = ctry1;
|
||||||
|
#endif
|
||||||
|
|
||||||
|
for (uint8_t xo = 0; xo <= xlen; xo++)
|
||||||
|
for (uint8_t yo = 0; yo <= ylen; yo++) {
|
||||||
|
uint8_t x2 = ctrx2 + xo, y2 = ctry2 + yo;
|
||||||
|
#ifndef HALF_IN_X
|
||||||
|
const uint8_t x1 = ctrx1 - xo;
|
||||||
|
#endif
|
||||||
|
#ifndef HALF_IN_Y
|
||||||
|
const uint8_t y1 = ctry1 - yo;
|
||||||
|
#ifndef HALF_IN_X
|
||||||
|
extrapolate_one_point(x1, y1, +1, +1); // left-below + +
|
||||||
|
#endif
|
||||||
|
extrapolate_one_point(x2, y1, -1, +1); // right-below - +
|
||||||
|
#endif
|
||||||
|
#ifndef HALF_IN_X
|
||||||
|
extrapolate_one_point(x1, y2, +1, -1); // left-above + -
|
||||||
|
#endif
|
||||||
|
extrapolate_one_point(x2, y2, -1, -1); // right-above - -
|
||||||
|
}
|
||||||
|
|
||||||
|
}
|
||||||
|
|
||||||
|
void print_bilinear_leveling_grid() {
|
||||||
|
SERIAL_ECHOLNPGM("Bilinear Leveling Grid:");
|
||||||
|
print_2d_array(GRID_MAX_POINTS_X, GRID_MAX_POINTS_Y, 3,
|
||||||
|
[](const uint8_t ix, const uint8_t iy) { return z_values[ix][iy]; }
|
||||||
|
);
|
||||||
|
}
|
||||||
|
|
||||||
|
#if ENABLED(ABL_BILINEAR_SUBDIVISION)
|
||||||
|
|
||||||
|
#define ABL_GRID_POINTS_VIRT_X (GRID_MAX_POINTS_X - 1) * (BILINEAR_SUBDIVISIONS) + 1
|
||||||
|
#define ABL_GRID_POINTS_VIRT_Y (GRID_MAX_POINTS_Y - 1) * (BILINEAR_SUBDIVISIONS) + 1
|
||||||
|
#define ABL_TEMP_POINTS_X (GRID_MAX_POINTS_X + 2)
|
||||||
|
#define ABL_TEMP_POINTS_Y (GRID_MAX_POINTS_Y + 2)
|
||||||
|
float z_values_virt[ABL_GRID_POINTS_VIRT_X][ABL_GRID_POINTS_VIRT_Y];
|
||||||
|
int bilinear_grid_spacing_virt[2] = { 0 };
|
||||||
|
float bilinear_grid_factor_virt[2] = { 0 };
|
||||||
|
|
||||||
|
void print_bilinear_leveling_grid_virt() {
|
||||||
|
SERIAL_ECHOLNPGM("Subdivided with CATMULL ROM Leveling Grid:");
|
||||||
|
print_2d_array(ABL_GRID_POINTS_VIRT_X, ABL_GRID_POINTS_VIRT_Y, 5,
|
||||||
|
[](const uint8_t ix, const uint8_t iy) { return z_values_virt[ix][iy]; }
|
||||||
|
);
|
||||||
|
}
|
||||||
|
|
||||||
|
#define LINEAR_EXTRAPOLATION(E, I) ((E) * 2 - (I))
|
||||||
|
float bed_level_virt_coord(const uint8_t x, const uint8_t y) {
|
||||||
|
uint8_t ep = 0, ip = 1;
|
||||||
|
if (!x || x == ABL_TEMP_POINTS_X - 1) {
|
||||||
|
if (x) {
|
||||||
|
ep = GRID_MAX_POINTS_X - 1;
|
||||||
|
ip = GRID_MAX_POINTS_X - 2;
|
||||||
|
}
|
||||||
|
if (WITHIN(y, 1, ABL_TEMP_POINTS_Y - 2))
|
||||||
|
return LINEAR_EXTRAPOLATION(
|
||||||
|
z_values[ep][y - 1],
|
||||||
|
z_values[ip][y - 1]
|
||||||
|
);
|
||||||
|
else
|
||||||
|
return LINEAR_EXTRAPOLATION(
|
||||||
|
bed_level_virt_coord(ep + 1, y),
|
||||||
|
bed_level_virt_coord(ip + 1, y)
|
||||||
|
);
|
||||||
|
}
|
||||||
|
if (!y || y == ABL_TEMP_POINTS_Y - 1) {
|
||||||
|
if (y) {
|
||||||
|
ep = GRID_MAX_POINTS_Y - 1;
|
||||||
|
ip = GRID_MAX_POINTS_Y - 2;
|
||||||
|
}
|
||||||
|
if (WITHIN(x, 1, ABL_TEMP_POINTS_X - 2))
|
||||||
|
return LINEAR_EXTRAPOLATION(
|
||||||
|
z_values[x - 1][ep],
|
||||||
|
z_values[x - 1][ip]
|
||||||
|
);
|
||||||
|
else
|
||||||
|
return LINEAR_EXTRAPOLATION(
|
||||||
|
bed_level_virt_coord(x, ep + 1),
|
||||||
|
bed_level_virt_coord(x, ip + 1)
|
||||||
|
);
|
||||||
|
}
|
||||||
|
return z_values[x - 1][y - 1];
|
||||||
|
}
|
||||||
|
|
||||||
|
static float bed_level_virt_cmr(const float p[4], const uint8_t i, const float t) {
|
||||||
|
return (
|
||||||
|
p[i-1] * -t * sq(1 - t)
|
||||||
|
+ p[i] * (2 - 5 * sq(t) + 3 * t * sq(t))
|
||||||
|
+ p[i+1] * t * (1 + 4 * t - 3 * sq(t))
|
||||||
|
- p[i+2] * sq(t) * (1 - t)
|
||||||
|
) * 0.5;
|
||||||
|
}
|
||||||
|
|
||||||
|
static float bed_level_virt_2cmr(const uint8_t x, const uint8_t y, const float &tx, const float &ty) {
|
||||||
|
float row[4], column[4];
|
||||||
|
for (uint8_t i = 0; i < 4; i++) {
|
||||||
|
for (uint8_t j = 0; j < 4; j++) {
|
||||||
|
column[j] = bed_level_virt_coord(i + x - 1, j + y - 1);
|
||||||
|
}
|
||||||
|
row[i] = bed_level_virt_cmr(column, 1, ty);
|
||||||
|
}
|
||||||
|
return bed_level_virt_cmr(row, 1, tx);
|
||||||
|
}
|
||||||
|
|
||||||
|
void bed_level_virt_interpolate() {
|
||||||
|
bilinear_grid_spacing_virt[X_AXIS] = bilinear_grid_spacing[X_AXIS] / (BILINEAR_SUBDIVISIONS);
|
||||||
|
bilinear_grid_spacing_virt[Y_AXIS] = bilinear_grid_spacing[Y_AXIS] / (BILINEAR_SUBDIVISIONS);
|
||||||
|
bilinear_grid_factor_virt[X_AXIS] = RECIPROCAL(bilinear_grid_spacing_virt[X_AXIS]);
|
||||||
|
bilinear_grid_factor_virt[Y_AXIS] = RECIPROCAL(bilinear_grid_spacing_virt[Y_AXIS]);
|
||||||
|
for (uint8_t y = 0; y < GRID_MAX_POINTS_Y; y++)
|
||||||
|
for (uint8_t x = 0; x < GRID_MAX_POINTS_X; x++)
|
||||||
|
for (uint8_t ty = 0; ty < BILINEAR_SUBDIVISIONS; ty++)
|
||||||
|
for (uint8_t tx = 0; tx < BILINEAR_SUBDIVISIONS; tx++) {
|
||||||
|
if ((ty && y == GRID_MAX_POINTS_Y - 1) || (tx && x == GRID_MAX_POINTS_X - 1))
|
||||||
|
continue;
|
||||||
|
z_values_virt[x * (BILINEAR_SUBDIVISIONS) + tx][y * (BILINEAR_SUBDIVISIONS) + ty] =
|
||||||
|
bed_level_virt_2cmr(
|
||||||
|
x + 1,
|
||||||
|
y + 1,
|
||||||
|
(float)tx / (BILINEAR_SUBDIVISIONS),
|
||||||
|
(float)ty / (BILINEAR_SUBDIVISIONS)
|
||||||
|
);
|
||||||
|
}
|
||||||
|
}
|
||||||
|
#endif // ABL_BILINEAR_SUBDIVISION
|
||||||
|
|
||||||
|
// Refresh after other values have been updated
|
||||||
|
void refresh_bed_level() {
|
||||||
|
bilinear_grid_factor[X_AXIS] = RECIPROCAL(bilinear_grid_spacing[X_AXIS]);
|
||||||
|
bilinear_grid_factor[Y_AXIS] = RECIPROCAL(bilinear_grid_spacing[Y_AXIS]);
|
||||||
|
#if ENABLED(ABL_BILINEAR_SUBDIVISION)
|
||||||
|
bed_level_virt_interpolate();
|
||||||
|
#endif
|
||||||
|
}
|
||||||
|
|
||||||
|
#if ENABLED(ABL_BILINEAR_SUBDIVISION)
|
||||||
|
#define ABL_BG_SPACING(A) bilinear_grid_spacing_virt[A]
|
||||||
|
#define ABL_BG_FACTOR(A) bilinear_grid_factor_virt[A]
|
||||||
|
#define ABL_BG_POINTS_X ABL_GRID_POINTS_VIRT_X
|
||||||
|
#define ABL_BG_POINTS_Y ABL_GRID_POINTS_VIRT_Y
|
||||||
|
#define ABL_BG_GRID(X,Y) z_values_virt[X][Y]
|
||||||
|
#else
|
||||||
|
#define ABL_BG_SPACING(A) bilinear_grid_spacing[A]
|
||||||
|
#define ABL_BG_FACTOR(A) bilinear_grid_factor[A]
|
||||||
|
#define ABL_BG_POINTS_X GRID_MAX_POINTS_X
|
||||||
|
#define ABL_BG_POINTS_Y GRID_MAX_POINTS_Y
|
||||||
|
#define ABL_BG_GRID(X,Y) z_values[X][Y]
|
||||||
|
#endif
|
||||||
|
|
||||||
|
// Get the Z adjustment for non-linear bed leveling
|
||||||
|
float bilinear_z_offset(const float logical[XYZ]) {
|
||||||
|
|
||||||
|
static float z1, d2, z3, d4, L, D, ratio_x, ratio_y,
|
||||||
|
last_x = -999.999, last_y = -999.999;
|
||||||
|
|
||||||
|
// Whole units for the grid line indices. Constrained within bounds.
|
||||||
|
static int8_t gridx, gridy, nextx, nexty,
|
||||||
|
last_gridx = -99, last_gridy = -99;
|
||||||
|
|
||||||
|
// XY relative to the probed area
|
||||||
|
const float x = RAW_X_POSITION(logical[X_AXIS]) - bilinear_start[X_AXIS],
|
||||||
|
y = RAW_Y_POSITION(logical[Y_AXIS]) - bilinear_start[Y_AXIS];
|
||||||
|
|
||||||
|
#if ENABLED(EXTRAPOLATE_BEYOND_GRID)
|
||||||
|
// Keep using the last grid box
|
||||||
|
#define FAR_EDGE_OR_BOX 2
|
||||||
|
#else
|
||||||
|
// Just use the grid far edge
|
||||||
|
#define FAR_EDGE_OR_BOX 1
|
||||||
|
#endif
|
||||||
|
|
||||||
|
if (last_x != x) {
|
||||||
|
last_x = x;
|
||||||
|
ratio_x = x * ABL_BG_FACTOR(X_AXIS);
|
||||||
|
const float gx = constrain(FLOOR(ratio_x), 0, ABL_BG_POINTS_X - FAR_EDGE_OR_BOX);
|
||||||
|
ratio_x -= gx; // Subtract whole to get the ratio within the grid box
|
||||||
|
|
||||||
|
#if DISABLED(EXTRAPOLATE_BEYOND_GRID)
|
||||||
|
// Beyond the grid maintain height at grid edges
|
||||||
|
NOLESS(ratio_x, 0); // Never < 0.0. (> 1.0 is ok when nextx==gridx.)
|
||||||
|
#endif
|
||||||
|
|
||||||
|
gridx = gx;
|
||||||
|
nextx = min(gridx + 1, ABL_BG_POINTS_X - 1);
|
||||||
|
}
|
||||||
|
|
||||||
|
if (last_y != y || last_gridx != gridx) {
|
||||||
|
|
||||||
|
if (last_y != y) {
|
||||||
|
last_y = y;
|
||||||
|
ratio_y = y * ABL_BG_FACTOR(Y_AXIS);
|
||||||
|
const float gy = constrain(FLOOR(ratio_y), 0, ABL_BG_POINTS_Y - FAR_EDGE_OR_BOX);
|
||||||
|
ratio_y -= gy;
|
||||||
|
|
||||||
|
#if DISABLED(EXTRAPOLATE_BEYOND_GRID)
|
||||||
|
// Beyond the grid maintain height at grid edges
|
||||||
|
NOLESS(ratio_y, 0); // Never < 0.0. (> 1.0 is ok when nexty==gridy.)
|
||||||
|
#endif
|
||||||
|
|
||||||
|
gridy = gy;
|
||||||
|
nexty = min(gridy + 1, ABL_BG_POINTS_Y - 1);
|
||||||
|
}
|
||||||
|
|
||||||
|
if (last_gridx != gridx || last_gridy != gridy) {
|
||||||
|
last_gridx = gridx;
|
||||||
|
last_gridy = gridy;
|
||||||
|
// Z at the box corners
|
||||||
|
z1 = ABL_BG_GRID(gridx, gridy); // left-front
|
||||||
|
d2 = ABL_BG_GRID(gridx, nexty) - z1; // left-back (delta)
|
||||||
|
z3 = ABL_BG_GRID(nextx, gridy); // right-front
|
||||||
|
d4 = ABL_BG_GRID(nextx, nexty) - z3; // right-back (delta)
|
||||||
|
}
|
||||||
|
|
||||||
|
// Bilinear interpolate. Needed since y or gridx has changed.
|
||||||
|
L = z1 + d2 * ratio_y; // Linear interp. LF -> LB
|
||||||
|
const float R = z3 + d4 * ratio_y; // Linear interp. RF -> RB
|
||||||
|
|
||||||
|
D = R - L;
|
||||||
|
}
|
||||||
|
|
||||||
|
const float offset = L + ratio_x * D; // the offset almost always changes
|
||||||
|
|
||||||
|
/*
|
||||||
|
static float last_offset = 0;
|
||||||
|
if (FABS(last_offset - offset) > 0.2) {
|
||||||
|
SERIAL_ECHOPGM("Sudden Shift at ");
|
||||||
|
SERIAL_ECHOPAIR("x=", x);
|
||||||
|
SERIAL_ECHOPAIR(" / ", bilinear_grid_spacing[X_AXIS]);
|
||||||
|
SERIAL_ECHOLNPAIR(" -> gridx=", gridx);
|
||||||
|
SERIAL_ECHOPAIR(" y=", y);
|
||||||
|
SERIAL_ECHOPAIR(" / ", bilinear_grid_spacing[Y_AXIS]);
|
||||||
|
SERIAL_ECHOLNPAIR(" -> gridy=", gridy);
|
||||||
|
SERIAL_ECHOPAIR(" ratio_x=", ratio_x);
|
||||||
|
SERIAL_ECHOLNPAIR(" ratio_y=", ratio_y);
|
||||||
|
SERIAL_ECHOPAIR(" z1=", z1);
|
||||||
|
SERIAL_ECHOPAIR(" z2=", z2);
|
||||||
|
SERIAL_ECHOPAIR(" z3=", z3);
|
||||||
|
SERIAL_ECHOLNPAIR(" z4=", z4);
|
||||||
|
SERIAL_ECHOPAIR(" L=", L);
|
||||||
|
SERIAL_ECHOPAIR(" R=", R);
|
||||||
|
SERIAL_ECHOLNPAIR(" offset=", offset);
|
||||||
|
}
|
||||||
|
last_offset = offset;
|
||||||
|
//*/
|
||||||
|
|
||||||
|
return offset;
|
||||||
|
}
|
||||||
|
|
||||||
|
#if !IS_KINEMATIC
|
||||||
|
|
||||||
|
#define CELL_INDEX(A,V) ((RAW_##A##_POSITION(V) - bilinear_start[A##_AXIS]) * ABL_BG_FACTOR(A##_AXIS))
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Prepare a bilinear-leveled linear move on Cartesian,
|
||||||
|
* splitting the move where it crosses grid borders.
|
||||||
|
*/
|
||||||
|
void bilinear_line_to_destination(const float fr_mm_s, uint16_t x_splits, uint16_t y_splits) {
|
||||||
|
int cx1 = CELL_INDEX(X, current_position[X_AXIS]),
|
||||||
|
cy1 = CELL_INDEX(Y, current_position[Y_AXIS]),
|
||||||
|
cx2 = CELL_INDEX(X, destination[X_AXIS]),
|
||||||
|
cy2 = CELL_INDEX(Y, destination[Y_AXIS]);
|
||||||
|
cx1 = constrain(cx1, 0, ABL_BG_POINTS_X - 2);
|
||||||
|
cy1 = constrain(cy1, 0, ABL_BG_POINTS_Y - 2);
|
||||||
|
cx2 = constrain(cx2, 0, ABL_BG_POINTS_X - 2);
|
||||||
|
cy2 = constrain(cy2, 0, ABL_BG_POINTS_Y - 2);
|
||||||
|
|
||||||
|
if (cx1 == cx2 && cy1 == cy2) {
|
||||||
|
// Start and end on same mesh square
|
||||||
|
line_to_destination(fr_mm_s);
|
||||||
|
set_current_to_destination();
|
||||||
|
return;
|
||||||
|
}
|
||||||
|
|
||||||
|
#define LINE_SEGMENT_END(A) (current_position[A ##_AXIS] + (destination[A ##_AXIS] - current_position[A ##_AXIS]) * normalized_dist)
|
||||||
|
|
||||||
|
float normalized_dist, end[XYZE];
|
||||||
|
|
||||||
|
// Split at the left/front border of the right/top square
|
||||||
|
const int8_t gcx = max(cx1, cx2), gcy = max(cy1, cy2);
|
||||||
|
if (cx2 != cx1 && TEST(x_splits, gcx)) {
|
||||||
|
COPY(end, destination);
|
||||||
|
destination[X_AXIS] = LOGICAL_X_POSITION(bilinear_start[X_AXIS] + ABL_BG_SPACING(X_AXIS) * gcx);
|
||||||
|
normalized_dist = (destination[X_AXIS] - current_position[X_AXIS]) / (end[X_AXIS] - current_position[X_AXIS]);
|
||||||
|
destination[Y_AXIS] = LINE_SEGMENT_END(Y);
|
||||||
|
CBI(x_splits, gcx);
|
||||||
|
}
|
||||||
|
else if (cy2 != cy1 && TEST(y_splits, gcy)) {
|
||||||
|
COPY(end, destination);
|
||||||
|
destination[Y_AXIS] = LOGICAL_Y_POSITION(bilinear_start[Y_AXIS] + ABL_BG_SPACING(Y_AXIS) * gcy);
|
||||||
|
normalized_dist = (destination[Y_AXIS] - current_position[Y_AXIS]) / (end[Y_AXIS] - current_position[Y_AXIS]);
|
||||||
|
destination[X_AXIS] = LINE_SEGMENT_END(X);
|
||||||
|
CBI(y_splits, gcy);
|
||||||
|
}
|
||||||
|
else {
|
||||||
|
// Already split on a border
|
||||||
|
line_to_destination(fr_mm_s);
|
||||||
|
set_current_to_destination();
|
||||||
|
return;
|
||||||
|
}
|
||||||
|
|
||||||
|
destination[Z_AXIS] = LINE_SEGMENT_END(Z);
|
||||||
|
destination[E_AXIS] = LINE_SEGMENT_END(E);
|
||||||
|
|
||||||
|
// Do the split and look for more borders
|
||||||
|
bilinear_line_to_destination(fr_mm_s, x_splits, y_splits);
|
||||||
|
|
||||||
|
// Restore destination from stack
|
||||||
|
COPY(destination, end);
|
||||||
|
bilinear_line_to_destination(fr_mm_s, x_splits, y_splits);
|
||||||
|
}
|
||||||
|
|
||||||
|
#endif // !IS_KINEMATIC
|
||||||
|
|
||||||
|
#endif // AUTO_BED_LEVELING_BILINEAR
|
51
Marlin/src/feature/bedlevel/abl/abl.h
Normal file
51
Marlin/src/feature/bedlevel/abl/abl.h
Normal file
|
@ -0,0 +1,51 @@
|
||||||
|
/**
|
||||||
|
* Marlin 3D Printer Firmware
|
||||||
|
* Copyright (C) 2016, 2017 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
|
||||||
|
*
|
||||||
|
* Based on Sprinter and grbl.
|
||||||
|
* Copyright (C) 2011 Camiel Gubbels / Erik van der Zalm
|
||||||
|
*
|
||||||
|
* This program is free software: you can redistribute it and/or modify
|
||||||
|
* it under the terms of the GNU General Public License as published by
|
||||||
|
* the Free Software Foundation, either version 3 of the License, or
|
||||||
|
* (at your option) any later version.
|
||||||
|
*
|
||||||
|
* This program is distributed in the hope that it will be useful,
|
||||||
|
* but WITHOUT ANY WARRANTY; without even the implied warranty of
|
||||||
|
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
|
||||||
|
* GNU General Public License for more details.
|
||||||
|
*
|
||||||
|
* You should have received a copy of the GNU General Public License
|
||||||
|
* along with this program. If not, see <http://www.gnu.org/licenses/>.
|
||||||
|
*
|
||||||
|
*/
|
||||||
|
|
||||||
|
#ifndef __ABL_H__
|
||||||
|
#define __ABL_H__
|
||||||
|
|
||||||
|
#include "../../../inc/MarlinConfig.h"
|
||||||
|
|
||||||
|
#if ENABLED(AUTO_BED_LEVELING_BILINEAR)
|
||||||
|
|
||||||
|
#include "../bedlevel.h"
|
||||||
|
|
||||||
|
extern int bilinear_grid_spacing[2], bilinear_start[2];
|
||||||
|
extern float bilinear_grid_factor[2],
|
||||||
|
z_values[GRID_MAX_POINTS_X][GRID_MAX_POINTS_Y];
|
||||||
|
float bilinear_z_offset(const float logical[XYZ]);
|
||||||
|
|
||||||
|
void extrapolate_unprobed_bed_level();
|
||||||
|
void print_bilinear_leveling_grid();
|
||||||
|
void refresh_bed_level();
|
||||||
|
#if ENABLED(ABL_BILINEAR_SUBDIVISION)
|
||||||
|
void print_bilinear_leveling_grid_virt();
|
||||||
|
void bed_level_virt_interpolate();
|
||||||
|
#endif
|
||||||
|
|
||||||
|
#if !IS_KINEMATIC
|
||||||
|
void bilinear_line_to_destination(const float fr_mm_s, uint16_t x_splits=0xFFFF, uint16_t y_splits=0xFFFF);
|
||||||
|
#endif
|
||||||
|
|
||||||
|
#endif // AUTO_BED_LEVELING_BILINEAR
|
||||||
|
|
||||||
|
#endif // __ABL_H__
|
314
Marlin/src/feature/bedlevel/bedlevel.cpp
Normal file
314
Marlin/src/feature/bedlevel/bedlevel.cpp
Normal file
|
@ -0,0 +1,314 @@
|
||||||
|
/**
|
||||||
|
* Marlin 3D Printer Firmware
|
||||||
|
* Copyright (C) 2016 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
|
||||||
|
*
|
||||||
|
* Based on Sprinter and grbl.
|
||||||
|
* Copyright (C) 2011 Camiel Gubbels / Erik van der Zalm
|
||||||
|
*
|
||||||
|
* This program is free software: you can redistribute it and/or modify
|
||||||
|
* it under the terms of the GNU General Public License as published by
|
||||||
|
* the Free Software Foundation, either version 3 of the License, or
|
||||||
|
* (at your option) any later version.
|
||||||
|
*
|
||||||
|
* This program is distributed in the hope that it will be useful,
|
||||||
|
* but WITHOUT ANY WARRANTY; without even the implied warranty of
|
||||||
|
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
|
||||||
|
* GNU General Public License for more details.
|
||||||
|
*
|
||||||
|
* You should have received a copy of the GNU General Public License
|
||||||
|
* along with this program. If not, see <http://www.gnu.org/licenses/>.
|
||||||
|
*
|
||||||
|
*/
|
||||||
|
|
||||||
|
#include "../../inc/MarlinConfig.h"
|
||||||
|
|
||||||
|
#if HAS_LEVELING
|
||||||
|
|
||||||
|
#include "bedlevel.h"
|
||||||
|
|
||||||
|
#if ENABLED(MESH_BED_LEVELING) || ENABLED(PROBE_MANUALLY)
|
||||||
|
#include "../../module/stepper.h"
|
||||||
|
#endif
|
||||||
|
|
||||||
|
#if PLANNER_LEVELING
|
||||||
|
#include "../../module/planner.h"
|
||||||
|
#endif
|
||||||
|
|
||||||
|
#if ENABLED(PROBE_MANUALLY)
|
||||||
|
bool g29_in_progress = false;
|
||||||
|
#if ENABLED(LCD_BED_LEVELING)
|
||||||
|
#include "../../lcd/ultralcd.h"
|
||||||
|
#endif
|
||||||
|
#endif
|
||||||
|
|
||||||
|
bool leveling_is_valid() {
|
||||||
|
return
|
||||||
|
#if ENABLED(MESH_BED_LEVELING)
|
||||||
|
mbl.has_mesh()
|
||||||
|
#elif ENABLED(AUTO_BED_LEVELING_BILINEAR)
|
||||||
|
!!bilinear_grid_spacing[X_AXIS]
|
||||||
|
#elif ENABLED(AUTO_BED_LEVELING_UBL)
|
||||||
|
true
|
||||||
|
#else // 3POINT, LINEAR
|
||||||
|
true
|
||||||
|
#endif
|
||||||
|
;
|
||||||
|
}
|
||||||
|
|
||||||
|
bool leveling_is_active() {
|
||||||
|
return
|
||||||
|
#if ENABLED(MESH_BED_LEVELING)
|
||||||
|
mbl.active()
|
||||||
|
#elif ENABLED(AUTO_BED_LEVELING_UBL)
|
||||||
|
ubl.state.active
|
||||||
|
#else // OLDSCHOOL_ABL
|
||||||
|
planner.abl_enabled
|
||||||
|
#endif
|
||||||
|
;
|
||||||
|
}
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Turn bed leveling on or off, fixing the current
|
||||||
|
* position as-needed.
|
||||||
|
*
|
||||||
|
* Disable: Current position = physical position
|
||||||
|
* Enable: Current position = "unleveled" physical position
|
||||||
|
*/
|
||||||
|
void set_bed_leveling_enabled(const bool enable/*=true*/) {
|
||||||
|
|
||||||
|
#if ENABLED(AUTO_BED_LEVELING_BILINEAR)
|
||||||
|
const bool can_change = (!enable || leveling_is_valid());
|
||||||
|
#else
|
||||||
|
constexpr bool can_change = true;
|
||||||
|
#endif
|
||||||
|
|
||||||
|
if (can_change && enable != leveling_is_active()) {
|
||||||
|
|
||||||
|
#if ENABLED(MESH_BED_LEVELING)
|
||||||
|
|
||||||
|
if (!enable)
|
||||||
|
planner.apply_leveling(current_position[X_AXIS], current_position[Y_AXIS], current_position[Z_AXIS]);
|
||||||
|
|
||||||
|
const bool enabling = enable && leveling_is_valid();
|
||||||
|
mbl.set_active(enabling);
|
||||||
|
if (enabling) planner.unapply_leveling(current_position);
|
||||||
|
|
||||||
|
#elif ENABLED(AUTO_BED_LEVELING_UBL)
|
||||||
|
#if PLANNER_LEVELING
|
||||||
|
if (ubl.state.active) { // leveling from on to off
|
||||||
|
// change unleveled current_position to physical current_position without moving steppers.
|
||||||
|
planner.apply_leveling(current_position[X_AXIS], current_position[Y_AXIS], current_position[Z_AXIS]);
|
||||||
|
ubl.state.active = false; // disable only AFTER calling apply_leveling
|
||||||
|
}
|
||||||
|
else { // leveling from off to on
|
||||||
|
ubl.state.active = true; // enable BEFORE calling unapply_leveling, otherwise ignored
|
||||||
|
// change physical current_position to unleveled current_position without moving steppers.
|
||||||
|
planner.unapply_leveling(current_position);
|
||||||
|
}
|
||||||
|
#else
|
||||||
|
ubl.state.active = enable; // just flip the bit, current_position will be wrong until next move.
|
||||||
|
#endif
|
||||||
|
|
||||||
|
#else // OLDSCHOOL_ABL
|
||||||
|
|
||||||
|
#if ENABLED(AUTO_BED_LEVELING_BILINEAR)
|
||||||
|
// Force bilinear_z_offset to re-calculate next time
|
||||||
|
const float reset[XYZ] = { -9999.999, -9999.999, 0 };
|
||||||
|
(void)bilinear_z_offset(reset);
|
||||||
|
#endif
|
||||||
|
|
||||||
|
// Enable or disable leveling compensation in the planner
|
||||||
|
planner.abl_enabled = enable;
|
||||||
|
|
||||||
|
if (!enable)
|
||||||
|
// When disabling just get the current position from the steppers.
|
||||||
|
// This will yield the smallest error when first converted back to steps.
|
||||||
|
set_current_from_steppers_for_axis(
|
||||||
|
#if ABL_PLANAR
|
||||||
|
ALL_AXES
|
||||||
|
#else
|
||||||
|
Z_AXIS
|
||||||
|
#endif
|
||||||
|
);
|
||||||
|
else
|
||||||
|
// When enabling, remove compensation from the current position,
|
||||||
|
// so compensation will give the right stepper counts.
|
||||||
|
planner.unapply_leveling(current_position);
|
||||||
|
|
||||||
|
#endif // OLDSCHOOL_ABL
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
#if ENABLED(ENABLE_LEVELING_FADE_HEIGHT)
|
||||||
|
|
||||||
|
void set_z_fade_height(const float zfh) {
|
||||||
|
|
||||||
|
const bool level_active = leveling_is_active();
|
||||||
|
|
||||||
|
#if ENABLED(AUTO_BED_LEVELING_UBL)
|
||||||
|
|
||||||
|
if (level_active)
|
||||||
|
set_bed_leveling_enabled(false); // turn off before changing fade height for proper apply/unapply leveling to maintain current_position
|
||||||
|
planner.z_fade_height = zfh;
|
||||||
|
planner.inverse_z_fade_height = RECIPROCAL(zfh);
|
||||||
|
if (level_active)
|
||||||
|
set_bed_leveling_enabled(true); // turn back on after changing fade height
|
||||||
|
|
||||||
|
#else
|
||||||
|
|
||||||
|
planner.z_fade_height = zfh;
|
||||||
|
planner.inverse_z_fade_height = RECIPROCAL(zfh);
|
||||||
|
|
||||||
|
if (level_active) {
|
||||||
|
set_current_from_steppers_for_axis(
|
||||||
|
#if ABL_PLANAR
|
||||||
|
ALL_AXES
|
||||||
|
#else
|
||||||
|
Z_AXIS
|
||||||
|
#endif
|
||||||
|
);
|
||||||
|
}
|
||||||
|
#endif
|
||||||
|
}
|
||||||
|
|
||||||
|
#endif // ENABLE_LEVELING_FADE_HEIGHT
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Reset calibration results to zero.
|
||||||
|
*/
|
||||||
|
void reset_bed_level() {
|
||||||
|
set_bed_leveling_enabled(false);
|
||||||
|
#if ENABLED(MESH_BED_LEVELING)
|
||||||
|
if (leveling_is_valid()) {
|
||||||
|
mbl.reset();
|
||||||
|
mbl.set_has_mesh(false);
|
||||||
|
}
|
||||||
|
#else
|
||||||
|
#if ENABLED(DEBUG_LEVELING_FEATURE)
|
||||||
|
if (DEBUGGING(LEVELING)) SERIAL_ECHOLNPGM("reset_bed_level");
|
||||||
|
#endif
|
||||||
|
#if ABL_PLANAR
|
||||||
|
planner.bed_level_matrix.set_to_identity();
|
||||||
|
#elif ENABLED(AUTO_BED_LEVELING_BILINEAR)
|
||||||
|
bilinear_start[X_AXIS] = bilinear_start[Y_AXIS] =
|
||||||
|
bilinear_grid_spacing[X_AXIS] = bilinear_grid_spacing[Y_AXIS] = 0;
|
||||||
|
for (uint8_t x = 0; x < GRID_MAX_POINTS_X; x++)
|
||||||
|
for (uint8_t y = 0; y < GRID_MAX_POINTS_Y; y++)
|
||||||
|
z_values[x][y] = NAN;
|
||||||
|
#elif ENABLED(AUTO_BED_LEVELING_UBL)
|
||||||
|
ubl.reset();
|
||||||
|
#endif
|
||||||
|
#endif
|
||||||
|
}
|
||||||
|
|
||||||
|
#if ENABLED(AUTO_BED_LEVELING_BILINEAR) || ENABLED(MESH_BED_LEVELING)
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Enable to produce output in JSON format suitable
|
||||||
|
* for SCAD or JavaScript mesh visualizers.
|
||||||
|
*
|
||||||
|
* Visualize meshes in OpenSCAD using the included script.
|
||||||
|
*
|
||||||
|
* buildroot/shared/scripts/MarlinMesh.scad
|
||||||
|
*/
|
||||||
|
//#define SCAD_MESH_OUTPUT
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Print calibration results for plotting or manual frame adjustment.
|
||||||
|
*/
|
||||||
|
void print_2d_array(const uint8_t sx, const uint8_t sy, const uint8_t precision, element_2d_fn fn) {
|
||||||
|
#ifndef SCAD_MESH_OUTPUT
|
||||||
|
for (uint8_t x = 0; x < sx; x++) {
|
||||||
|
for (uint8_t i = 0; i < precision + 2 + (x < 10 ? 1 : 0); i++)
|
||||||
|
SERIAL_PROTOCOLCHAR(' ');
|
||||||
|
SERIAL_PROTOCOL((int)x);
|
||||||
|
}
|
||||||
|
SERIAL_EOL();
|
||||||
|
#endif
|
||||||
|
#ifdef SCAD_MESH_OUTPUT
|
||||||
|
SERIAL_PROTOCOLLNPGM("measured_z = ["); // open 2D array
|
||||||
|
#endif
|
||||||
|
for (uint8_t y = 0; y < sy; y++) {
|
||||||
|
#ifdef SCAD_MESH_OUTPUT
|
||||||
|
SERIAL_PROTOCOLPGM(" ["); // open sub-array
|
||||||
|
#else
|
||||||
|
if (y < 10) SERIAL_PROTOCOLCHAR(' ');
|
||||||
|
SERIAL_PROTOCOL((int)y);
|
||||||
|
#endif
|
||||||
|
for (uint8_t x = 0; x < sx; x++) {
|
||||||
|
SERIAL_PROTOCOLCHAR(' ');
|
||||||
|
const float offset = fn(x, y);
|
||||||
|
if (!isnan(offset)) {
|
||||||
|
if (offset >= 0) SERIAL_PROTOCOLCHAR('+');
|
||||||
|
SERIAL_PROTOCOL_F(offset, precision);
|
||||||
|
}
|
||||||
|
else {
|
||||||
|
#ifdef SCAD_MESH_OUTPUT
|
||||||
|
for (uint8_t i = 3; i < precision + 3; i++)
|
||||||
|
SERIAL_PROTOCOLCHAR(' ');
|
||||||
|
SERIAL_PROTOCOLPGM("NAN");
|
||||||
|
#else
|
||||||
|
for (uint8_t i = 0; i < precision + 3; i++)
|
||||||
|
SERIAL_PROTOCOLCHAR(i ? '=' : ' ');
|
||||||
|
#endif
|
||||||
|
}
|
||||||
|
#ifdef SCAD_MESH_OUTPUT
|
||||||
|
if (x < sx - 1) SERIAL_PROTOCOLCHAR(',');
|
||||||
|
#endif
|
||||||
|
}
|
||||||
|
#ifdef SCAD_MESH_OUTPUT
|
||||||
|
SERIAL_PROTOCOLCHAR(' ');
|
||||||
|
SERIAL_PROTOCOLCHAR(']'); // close sub-array
|
||||||
|
if (y < sy - 1) SERIAL_PROTOCOLCHAR(',');
|
||||||
|
#endif
|
||||||
|
SERIAL_EOL();
|
||||||
|
}
|
||||||
|
#ifdef SCAD_MESH_OUTPUT
|
||||||
|
SERIAL_PROTOCOLPGM("];"); // close 2D array
|
||||||
|
#endif
|
||||||
|
SERIAL_EOL();
|
||||||
|
}
|
||||||
|
|
||||||
|
#endif // AUTO_BED_LEVELING_BILINEAR || MESH_BED_LEVELING
|
||||||
|
|
||||||
|
#if ENABLED(MESH_BED_LEVELING) || ENABLED(PROBE_MANUALLY)
|
||||||
|
|
||||||
|
void _manual_goto_xy(const float &x, const float &y) {
|
||||||
|
const float old_feedrate_mm_s = feedrate_mm_s;
|
||||||
|
#if MANUAL_PROBE_HEIGHT > 0
|
||||||
|
const float prev_z = current_position[Z_AXIS];
|
||||||
|
feedrate_mm_s = homing_feedrate(Z_AXIS);
|
||||||
|
current_position[Z_AXIS] = LOGICAL_Z_POSITION(MANUAL_PROBE_HEIGHT);
|
||||||
|
line_to_current_position();
|
||||||
|
#endif
|
||||||
|
|
||||||
|
feedrate_mm_s = MMM_TO_MMS(XY_PROBE_SPEED);
|
||||||
|
current_position[X_AXIS] = LOGICAL_X_POSITION(x);
|
||||||
|
current_position[Y_AXIS] = LOGICAL_Y_POSITION(y);
|
||||||
|
line_to_current_position();
|
||||||
|
|
||||||
|
#if MANUAL_PROBE_HEIGHT > 0
|
||||||
|
feedrate_mm_s = homing_feedrate(Z_AXIS);
|
||||||
|
current_position[Z_AXIS] = prev_z; // move back to the previous Z.
|
||||||
|
line_to_current_position();
|
||||||
|
#endif
|
||||||
|
|
||||||
|
feedrate_mm_s = old_feedrate_mm_s;
|
||||||
|
stepper.synchronize();
|
||||||
|
|
||||||
|
#if ENABLED(PROBE_MANUALLY) && ENABLED(LCD_BED_LEVELING)
|
||||||
|
lcd_wait_for_move = false;
|
||||||
|
#endif
|
||||||
|
}
|
||||||
|
|
||||||
|
#endif
|
||||||
|
|
||||||
|
#if HAS_PROBING_PROCEDURE
|
||||||
|
void out_of_range_error(const char* p_edge) {
|
||||||
|
SERIAL_PROTOCOLPGM("?Probe ");
|
||||||
|
serialprintPGM(p_edge);
|
||||||
|
SERIAL_PROTOCOLLNPGM(" position out of range.");
|
||||||
|
}
|
||||||
|
#endif
|
||||||
|
|
||||||
|
#endif // HAS_LEVELING
|
72
Marlin/src/feature/bedlevel/bedlevel.h
Normal file
72
Marlin/src/feature/bedlevel/bedlevel.h
Normal file
|
@ -0,0 +1,72 @@
|
||||||
|
/**
|
||||||
|
* Marlin 3D Printer Firmware
|
||||||
|
* Copyright (C) 2016 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
|
||||||
|
*
|
||||||
|
* Based on Sprinter and grbl.
|
||||||
|
* Copyright (C) 2011 Camiel Gubbels / Erik van der Zalm
|
||||||
|
*
|
||||||
|
* This program is free software: you can redistribute it and/or modify
|
||||||
|
* it under the terms of the GNU General Public License as published by
|
||||||
|
* the Free Software Foundation, either version 3 of the License, or
|
||||||
|
* (at your option) any later version.
|
||||||
|
*
|
||||||
|
* This program is distributed in the hope that it will be useful,
|
||||||
|
* but WITHOUT ANY WARRANTY; without even the implied warranty of
|
||||||
|
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
|
||||||
|
* GNU General Public License for more details.
|
||||||
|
*
|
||||||
|
* You should have received a copy of the GNU General Public License
|
||||||
|
* along with this program. If not, see <http://www.gnu.org/licenses/>.
|
||||||
|
*
|
||||||
|
*/
|
||||||
|
|
||||||
|
#ifndef __BEDLEVEL_H__
|
||||||
|
#define __BEDLEVEL_H__
|
||||||
|
|
||||||
|
#include "../../inc/MarlinConfig.h"
|
||||||
|
|
||||||
|
#if ENABLED(MESH_BED_LEVELING)
|
||||||
|
#include "mbl/mesh_bed_leveling.h"
|
||||||
|
#elif ENABLED(AUTO_BED_LEVELING_UBL)
|
||||||
|
#include "ubl/ubl.h"
|
||||||
|
#elif HAS_ABL
|
||||||
|
#include "abl/abl.h"
|
||||||
|
#endif
|
||||||
|
|
||||||
|
#if ENABLED(PROBE_MANUALLY)
|
||||||
|
extern bool g29_in_progress;
|
||||||
|
#else
|
||||||
|
constexpr bool g29_in_progress = false;
|
||||||
|
#endif
|
||||||
|
|
||||||
|
bool leveling_is_valid();
|
||||||
|
bool leveling_is_active();
|
||||||
|
void set_bed_leveling_enabled(const bool enable=true);
|
||||||
|
void reset_bed_level();
|
||||||
|
|
||||||
|
#if ENABLED(ENABLE_LEVELING_FADE_HEIGHT)
|
||||||
|
void set_z_fade_height(const float zfh);
|
||||||
|
#endif
|
||||||
|
|
||||||
|
#if ENABLED(AUTO_BED_LEVELING_BILINEAR) || ENABLED(MESH_BED_LEVELING)
|
||||||
|
|
||||||
|
#include <stdint.h>
|
||||||
|
|
||||||
|
typedef float (*element_2d_fn)(const uint8_t, const uint8_t);
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Print calibration results for plotting or manual frame adjustment.
|
||||||
|
*/
|
||||||
|
void print_2d_array(const uint8_t sx, const uint8_t sy, const uint8_t precision, element_2d_fn fn);
|
||||||
|
|
||||||
|
#endif
|
||||||
|
|
||||||
|
#if ENABLED(MESH_BED_LEVELING) || ENABLED(PROBE_MANUALLY)
|
||||||
|
void _manual_goto_xy(const float &x, const float &y);
|
||||||
|
#endif
|
||||||
|
|
||||||
|
#if HAS_PROBING_PROCEDURE
|
||||||
|
void out_of_range_error(const char* p_edge);
|
||||||
|
#endif
|
||||||
|
|
||||||
|
#endif // __BEDLEVEL_H__
|
|
@ -20,13 +20,14 @@
|
||||||
*
|
*
|
||||||
*/
|
*/
|
||||||
|
|
||||||
#include "../../inc/MarlinConfig.h"
|
#include "../../../inc/MarlinConfig.h"
|
||||||
|
|
||||||
#if ENABLED(MESH_BED_LEVELING)
|
#if ENABLED(MESH_BED_LEVELING)
|
||||||
|
|
||||||
#include "mesh_bed_leveling.h"
|
#include "mesh_bed_leveling.h"
|
||||||
|
|
||||||
#include "../../module/motion.h"
|
#include "../../../module/motion.h"
|
||||||
|
#include "../../../feature/bedlevel/bedlevel.h"
|
||||||
|
|
||||||
mesh_bed_leveling mbl;
|
mesh_bed_leveling mbl;
|
||||||
|
|
||||||
|
@ -110,4 +111,13 @@
|
||||||
mesh_line_to_destination(fr_mm_s, x_splits, y_splits);
|
mesh_line_to_destination(fr_mm_s, x_splits, y_splits);
|
||||||
}
|
}
|
||||||
|
|
||||||
|
void mbl_mesh_report() {
|
||||||
|
SERIAL_PROTOCOLLNPGM("Num X,Y: " STRINGIFY(GRID_MAX_POINTS_X) "," STRINGIFY(GRID_MAX_POINTS_Y));
|
||||||
|
SERIAL_PROTOCOLPGM("Z offset: "); SERIAL_PROTOCOL_F(mbl.z_offset, 5);
|
||||||
|
SERIAL_PROTOCOLLNPGM("\nMeasured points:");
|
||||||
|
print_2d_array(GRID_MAX_POINTS_X, GRID_MAX_POINTS_Y, 5,
|
||||||
|
[](const uint8_t ix, const uint8_t iy) { return mbl.z_values[ix][iy]; }
|
||||||
|
);
|
||||||
|
}
|
||||||
|
|
||||||
#endif // MESH_BED_LEVELING
|
#endif // MESH_BED_LEVELING
|
|
@ -23,7 +23,7 @@
|
||||||
#ifndef _MESH_BED_LEVELING_H_
|
#ifndef _MESH_BED_LEVELING_H_
|
||||||
#define _MESH_BED_LEVELING_H_
|
#define _MESH_BED_LEVELING_H_
|
||||||
|
|
||||||
#include "../../Marlin.h"
|
#include "../../../inc/MarlinConfig.h"
|
||||||
|
|
||||||
enum MeshLevelingState {
|
enum MeshLevelingState {
|
||||||
MeshReport,
|
MeshReport,
|
||||||
|
@ -120,6 +120,10 @@ public:
|
||||||
|
|
||||||
extern mesh_bed_leveling mbl;
|
extern mesh_bed_leveling mbl;
|
||||||
|
|
||||||
|
// Support functions, which may be embedded in the class later
|
||||||
|
|
||||||
void mesh_line_to_destination(const float fr_mm_s, uint8_t x_splits=0xFF, uint8_t y_splits=0xFF);
|
void mesh_line_to_destination(const float fr_mm_s, uint8_t x_splits=0xFF, uint8_t y_splits=0xFF);
|
||||||
|
|
||||||
|
void mbl_mesh_report();
|
||||||
|
|
||||||
#endif // _MESH_BED_LEVELING_H_
|
#endif // _MESH_BED_LEVELING_H_
|
|
@ -20,17 +20,17 @@
|
||||||
*
|
*
|
||||||
*/
|
*/
|
||||||
|
|
||||||
#include "../../inc/MarlinConfig.h"
|
#include "../../../inc/MarlinConfig.h"
|
||||||
|
|
||||||
#if ENABLED(AUTO_BED_LEVELING_UBL)
|
#if ENABLED(AUTO_BED_LEVELING_UBL)
|
||||||
|
|
||||||
#include "ubl.h"
|
#include "ubl.h"
|
||||||
unified_bed_leveling ubl;
|
unified_bed_leveling ubl;
|
||||||
|
|
||||||
#include "../../module/configuration_store.h"
|
#include "../../../module/configuration_store.h"
|
||||||
#include "../../core/serial.h"
|
#include "../../../module/planner.h"
|
||||||
#include "../../module/planner.h"
|
#include "../../../module/motion.h"
|
||||||
#include "../../module/motion.h"
|
#include "../../bedlevel/bedlevel.h"
|
||||||
|
|
||||||
#include "math.h"
|
#include "math.h"
|
||||||
|
|
||||||
|
@ -78,6 +78,10 @@
|
||||||
bool unified_bed_leveling::g26_debug_flag = false,
|
bool unified_bed_leveling::g26_debug_flag = false,
|
||||||
unified_bed_leveling::has_control_of_lcd_panel = false;
|
unified_bed_leveling::has_control_of_lcd_panel = false;
|
||||||
|
|
||||||
|
#if ENABLED(ULTRA_LCD)
|
||||||
|
bool unified_bed_leveling::lcd_map_control = false;
|
||||||
|
#endif
|
||||||
|
|
||||||
volatile int unified_bed_leveling::encoder_diff;
|
volatile int unified_bed_leveling::encoder_diff;
|
||||||
|
|
||||||
unified_bed_leveling::unified_bed_leveling() {
|
unified_bed_leveling::unified_bed_leveling() {
|
|
@ -23,9 +23,9 @@
|
||||||
#ifndef UNIFIED_BED_LEVELING_H
|
#ifndef UNIFIED_BED_LEVELING_H
|
||||||
#define UNIFIED_BED_LEVELING_H
|
#define UNIFIED_BED_LEVELING_H
|
||||||
|
|
||||||
#include "../../Marlin.h"
|
#include "../../../Marlin.h"
|
||||||
#include "../../core/serial.h"
|
#include "../../../module/planner.h"
|
||||||
#include "../../module/planner.h"
|
#include "../../../module/motion.h"
|
||||||
|
|
||||||
#define UBL_VERSION "1.01"
|
#define UBL_VERSION "1.01"
|
||||||
#define UBL_OK false
|
#define UBL_OK false
|
||||||
|
@ -57,7 +57,6 @@ enum MeshPointType { INVALID, REAL, SET_IN_BITMAP };
|
||||||
|
|
||||||
char *ftostr43sign(const float&, char);
|
char *ftostr43sign(const float&, char);
|
||||||
bool ubl_lcd_clicked();
|
bool ubl_lcd_clicked();
|
||||||
void home_all_axes();
|
|
||||||
|
|
||||||
extern uint8_t ubl_cnt;
|
extern uint8_t ubl_cnt;
|
||||||
|
|
||||||
|
@ -190,6 +189,10 @@ class unified_bed_leveling {
|
||||||
|
|
||||||
static bool g26_debug_flag, has_control_of_lcd_panel;
|
static bool g26_debug_flag, has_control_of_lcd_panel;
|
||||||
|
|
||||||
|
#if ENABLED(ULTRA_LCD)
|
||||||
|
static bool lcd_map_control;
|
||||||
|
#endif
|
||||||
|
|
||||||
static volatile int encoder_diff; // Volatile because it's changed at interrupt time.
|
static volatile int encoder_diff; // Volatile because it's changed at interrupt time.
|
||||||
|
|
||||||
unified_bed_leveling();
|
unified_bed_leveling();
|
||||||
|
@ -246,12 +249,16 @@ class unified_bed_leveling {
|
||||||
*/
|
*/
|
||||||
inline static float z_correction_for_x_on_horizontal_mesh_line(const float &lx0, const int x1_i, const int yi) {
|
inline static float z_correction_for_x_on_horizontal_mesh_line(const float &lx0, const int x1_i, const int yi) {
|
||||||
if (!WITHIN(x1_i, 0, GRID_MAX_POINTS_X - 2) || !WITHIN(yi, 0, GRID_MAX_POINTS_Y - 1)) {
|
if (!WITHIN(x1_i, 0, GRID_MAX_POINTS_X - 2) || !WITHIN(yi, 0, GRID_MAX_POINTS_Y - 1)) {
|
||||||
serialprintPGM( !WITHIN(x1_i, 0, GRID_MAX_POINTS_X - 1) ? PSTR("x1l_i") : PSTR("yi") );
|
#if ENABLED(DEBUG_LEVELING_FEATURE)
|
||||||
SERIAL_ECHOPAIR(" out of bounds in z_correction_for_x_on_horizontal_mesh_line(lx0=", lx0);
|
if (DEBUGGING(LEVELING)) {
|
||||||
SERIAL_ECHOPAIR(",x1_i=", x1_i);
|
serialprintPGM( !WITHIN(x1_i, 0, GRID_MAX_POINTS_X - 1) ? PSTR("x1l_i") : PSTR("yi") );
|
||||||
SERIAL_ECHOPAIR(",yi=", yi);
|
SERIAL_ECHOPAIR(" out of bounds in z_correction_for_x_on_horizontal_mesh_line(lx0=", lx0);
|
||||||
SERIAL_CHAR(')');
|
SERIAL_ECHOPAIR(",x1_i=", x1_i);
|
||||||
SERIAL_EOL();
|
SERIAL_ECHOPAIR(",yi=", yi);
|
||||||
|
SERIAL_CHAR(')');
|
||||||
|
SERIAL_EOL();
|
||||||
|
}
|
||||||
|
#endif
|
||||||
return NAN;
|
return NAN;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
@ -266,12 +273,16 @@ class unified_bed_leveling {
|
||||||
//
|
//
|
||||||
inline static float z_correction_for_y_on_vertical_mesh_line(const float &ly0, const int xi, const int y1_i) {
|
inline static float z_correction_for_y_on_vertical_mesh_line(const float &ly0, const int xi, const int y1_i) {
|
||||||
if (!WITHIN(xi, 0, GRID_MAX_POINTS_X - 1) || !WITHIN(y1_i, 0, GRID_MAX_POINTS_Y - 2)) {
|
if (!WITHIN(xi, 0, GRID_MAX_POINTS_X - 1) || !WITHIN(y1_i, 0, GRID_MAX_POINTS_Y - 2)) {
|
||||||
serialprintPGM( !WITHIN(xi, 0, GRID_MAX_POINTS_X - 1) ? PSTR("xi") : PSTR("yl_i") );
|
#if ENABLED(DEBUG_LEVELING_FEATURE)
|
||||||
SERIAL_ECHOPAIR(" out of bounds in z_correction_for_y_on_vertical_mesh_line(ly0=", ly0);
|
if (DEBUGGING(LEVELING)) {
|
||||||
SERIAL_ECHOPAIR(", xi=", xi);
|
serialprintPGM( !WITHIN(xi, 0, GRID_MAX_POINTS_X - 1) ? PSTR("xi") : PSTR("yl_i") );
|
||||||
SERIAL_ECHOPAIR(", y1_i=", y1_i);
|
SERIAL_ECHOPAIR(" out of bounds in z_correction_for_y_on_vertical_mesh_line(ly0=", ly0);
|
||||||
SERIAL_CHAR(')');
|
SERIAL_ECHOPAIR(", xi=", xi);
|
||||||
SERIAL_EOL();
|
SERIAL_ECHOPAIR(", y1_i=", y1_i);
|
||||||
|
SERIAL_CHAR(')');
|
||||||
|
SERIAL_EOL();
|
||||||
|
}
|
||||||
|
#endif
|
||||||
return NAN;
|
return NAN;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
@ -390,6 +401,19 @@ class unified_bed_leveling {
|
||||||
static bool prepare_segmented_line_to(const float ltarget[XYZE], const float &feedrate);
|
static bool prepare_segmented_line_to(const float ltarget[XYZE], const float &feedrate);
|
||||||
static void line_to_destination_cartesian(const float &fr, uint8_t e);
|
static void line_to_destination_cartesian(const float &fr, uint8_t e);
|
||||||
|
|
||||||
|
#define _CMPZ(a,b) (z_values[a][b] == z_values[a][b+1])
|
||||||
|
#define CMPZ(a) (_CMPZ(a, 0) && _CMPZ(a, 1))
|
||||||
|
#define ZZER(a) (z_values[a][0] == 0)
|
||||||
|
|
||||||
|
FORCE_INLINE bool mesh_is_valid() {
|
||||||
|
return !(
|
||||||
|
( CMPZ(0) && CMPZ(1) && CMPZ(2) // adjacent z values all equal?
|
||||||
|
&& ZZER(0) && ZZER(1) && ZZER(2) // all zero at the edge?
|
||||||
|
)
|
||||||
|
|| isnan(z_values[0][0])
|
||||||
|
);
|
||||||
|
}
|
||||||
|
|
||||||
}; // class unified_bed_leveling
|
}; // class unified_bed_leveling
|
||||||
|
|
||||||
extern unified_bed_leveling ubl;
|
extern unified_bed_leveling ubl;
|
|
@ -20,20 +20,23 @@
|
||||||
*
|
*
|
||||||
*/
|
*/
|
||||||
|
|
||||||
#include "../../inc/MarlinConfig.h"
|
#include "../../../inc/MarlinConfig.h"
|
||||||
|
|
||||||
#if ENABLED(AUTO_BED_LEVELING_UBL)
|
#if ENABLED(AUTO_BED_LEVELING_UBL)
|
||||||
|
|
||||||
#include "ubl.h"
|
#include "ubl.h"
|
||||||
|
|
||||||
#include "../../Marlin.h"
|
#include "../../../Marlin.h"
|
||||||
#include "../../libs/hex_print_routines.h"
|
#include "../../../libs/hex_print_routines.h"
|
||||||
#include "../../module/configuration_store.h"
|
#include "../../../module/configuration_store.h"
|
||||||
#include "../../lcd/ultralcd.h"
|
#include "../../../lcd/ultralcd.h"
|
||||||
#include "../../module/stepper.h"
|
#include "../../../module/stepper.h"
|
||||||
#include "../../module/planner.h"
|
#include "../../../module/planner.h"
|
||||||
#include "../../gcode/parser.h"
|
#include "../../../module/probe.h"
|
||||||
#include "../../libs/least_squares_fit.h"
|
#include "../../../gcode/gcode.h"
|
||||||
|
#include "../../../gcode/parser.h"
|
||||||
|
#include "../../../feature/bedlevel/bedlevel.h"
|
||||||
|
#include "../../../libs/least_squares_fit.h"
|
||||||
|
|
||||||
#include <math.h>
|
#include <math.h>
|
||||||
|
|
||||||
|
@ -52,11 +55,8 @@
|
||||||
|
|
||||||
extern float meshedit_done;
|
extern float meshedit_done;
|
||||||
extern long babysteps_done;
|
extern long babysteps_done;
|
||||||
extern float probe_pt(const float &lx, const float &ly, const bool, const uint8_t, const bool=true);
|
//extern bool set_probe_deployed(bool);
|
||||||
extern bool set_probe_deployed(bool);
|
//extern void set_bed_leveling_enabled(bool);
|
||||||
extern void set_bed_leveling_enabled(bool);
|
|
||||||
typedef void (*screenFunc_t)();
|
|
||||||
extern void lcd_goto_screen(screenFunc_t screen, const uint32_t encoder = 0);
|
|
||||||
|
|
||||||
#define SIZE_OF_LITTLE_RAISE 1
|
#define SIZE_OF_LITTLE_RAISE 1
|
||||||
#define BIG_RAISE_NOT_NEEDED 0
|
#define BIG_RAISE_NOT_NEEDED 0
|
||||||
|
@ -314,7 +314,7 @@
|
||||||
if (axis_unhomed_error()) {
|
if (axis_unhomed_error()) {
|
||||||
const int8_t p_val = parser.intval('P', -1);
|
const int8_t p_val = parser.intval('P', -1);
|
||||||
if (p_val == 1 || p_val == 2 || p_val == 4 || parser.seen('J'))
|
if (p_val == 1 || p_val == 2 || p_val == 4 || parser.seen('J'))
|
||||||
home_all_axes();
|
gcode.home_all_axes();
|
||||||
}
|
}
|
||||||
|
|
||||||
if (g29_parameter_parsing()) return; // abort if parsing the simple parameters causes a problem,
|
if (g29_parameter_parsing()) return; // abort if parsing the simple parameters causes a problem,
|
||||||
|
@ -1515,7 +1515,7 @@
|
||||||
idle();
|
idle();
|
||||||
} while (!ubl_lcd_clicked());
|
} while (!ubl_lcd_clicked());
|
||||||
|
|
||||||
if (!ubl_lcd_map_control) lcd_return_to_status();
|
if (!lcd_map_control) lcd_return_to_status();
|
||||||
|
|
||||||
// The technique used here generates a race condition for the encoder click.
|
// The technique used here generates a race condition for the encoder click.
|
||||||
// It could get detected in lcd_mesh_edit (actually _lcd_mesh_fine_tune) or here.
|
// It could get detected in lcd_mesh_edit (actually _lcd_mesh_fine_tune) or here.
|
||||||
|
@ -1561,7 +1561,7 @@
|
||||||
LCD_MESSAGEPGM(MSG_UBL_DONE_EDITING_MESH);
|
LCD_MESSAGEPGM(MSG_UBL_DONE_EDITING_MESH);
|
||||||
SERIAL_ECHOLNPGM("Done Editing Mesh");
|
SERIAL_ECHOLNPGM("Done Editing Mesh");
|
||||||
|
|
||||||
if (ubl_lcd_map_control)
|
if (lcd_map_control)
|
||||||
lcd_goto_screen(_lcd_ubl_output_map_lcd);
|
lcd_goto_screen(_lcd_ubl_output_map_lcd);
|
||||||
else
|
else
|
||||||
lcd_return_to_status();
|
lcd_return_to_status();
|
||||||
|
@ -1606,7 +1606,7 @@
|
||||||
// { GRID_MAX_POINTS_X - 1, 0, 0, GRID_MAX_POINTS_Y, true } PROGMEM // Right side of the mesh looking left
|
// { GRID_MAX_POINTS_X - 1, 0, 0, GRID_MAX_POINTS_Y, true } PROGMEM // Right side of the mesh looking left
|
||||||
// };
|
// };
|
||||||
for (uint8_t i = 0; i < COUNT(info); ++i) {
|
for (uint8_t i = 0; i < COUNT(info); ++i) {
|
||||||
const smart_fill_info *f = (smart_fill_info*)pgm_read_word(&info[i]);
|
const smart_fill_info *f = (smart_fill_info*)pgm_read_ptr(&info[i]);
|
||||||
const int8_t sx = pgm_read_word(&f->sx), sy = pgm_read_word(&f->sy),
|
const int8_t sx = pgm_read_word(&f->sx), sy = pgm_read_word(&f->sy),
|
||||||
ex = pgm_read_word(&f->ex), ey = pgm_read_word(&f->ey);
|
ex = pgm_read_word(&f->ex), ey = pgm_read_word(&f->ey);
|
||||||
if (pgm_read_byte(&f->yfirst)) {
|
if (pgm_read_byte(&f->yfirst)) {
|
|
@ -19,16 +19,20 @@
|
||||||
* along with this program. If not, see <http://www.gnu.org/licenses/>.
|
* along with this program. If not, see <http://www.gnu.org/licenses/>.
|
||||||
*
|
*
|
||||||
*/
|
*/
|
||||||
#include "../../inc/MarlinConfig.h"
|
#include "../../../inc/MarlinConfig.h"
|
||||||
|
|
||||||
#if ENABLED(AUTO_BED_LEVELING_UBL)
|
#if ENABLED(AUTO_BED_LEVELING_UBL)
|
||||||
|
|
||||||
#include "ubl.h"
|
#include "ubl.h"
|
||||||
|
|
||||||
#include "../../Marlin.h"
|
#include "../../../Marlin.h"
|
||||||
#include "../../module/planner.h"
|
#include "../../../module/planner.h"
|
||||||
#include "../../module/stepper.h"
|
#include "../../../module/stepper.h"
|
||||||
#include "../../module/motion.h"
|
#include "../../../module/motion.h"
|
||||||
|
|
||||||
|
#if ENABLED(DELTA)
|
||||||
|
#include "../../../module/delta.h"
|
||||||
|
#endif
|
||||||
|
|
||||||
#include <math.h>
|
#include <math.h>
|
||||||
|
|
||||||
|
@ -40,25 +44,6 @@
|
||||||
extern void set_current_to_destination();
|
extern void set_current_to_destination();
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#if ENABLED(DELTA)
|
|
||||||
|
|
||||||
extern float delta[ABC],
|
|
||||||
endstop_adj[ABC];
|
|
||||||
|
|
||||||
extern float delta_radius,
|
|
||||||
delta_tower_angle_trim[2],
|
|
||||||
delta_tower[ABC][2],
|
|
||||||
delta_diagonal_rod,
|
|
||||||
delta_calibration_radius,
|
|
||||||
delta_diagonal_rod_2_tower[ABC],
|
|
||||||
delta_segments_per_second,
|
|
||||||
delta_clip_start_height;
|
|
||||||
|
|
||||||
extern float delta_safe_distance_from_top();
|
|
||||||
|
|
||||||
#endif
|
|
||||||
|
|
||||||
|
|
||||||
static void debug_echo_axis(const AxisEnum axis) {
|
static void debug_echo_axis(const AxisEnum axis) {
|
||||||
if (current_position[axis] == destination[axis])
|
if (current_position[axis] == destination[axis])
|
||||||
SERIAL_ECHOPGM("-------------");
|
SERIAL_ECHOPGM("-------------");
|
|
@ -1,893 +0,0 @@
|
||||||
/**
|
|
||||||
* Marlin 3D Printer Firmware
|
|
||||||
* Copyright (C) 2016 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
|
|
||||||
*
|
|
||||||
* Based on Sprinter and grbl.
|
|
||||||
* Copyright (C) 2011 Camiel Gubbels / Erik van der Zalm
|
|
||||||
*
|
|
||||||
* This program is free software: you can redistribute it and/or modify
|
|
||||||
* it under the terms of the GNU General Public License as published by
|
|
||||||
* the Free Software Foundation, either version 3 of the License, or
|
|
||||||
* (at your option) any later version.
|
|
||||||
*
|
|
||||||
* This program is distributed in the hope that it will be useful,
|
|
||||||
* but WITHOUT ANY WARRANTY; without even the implied warranty of
|
|
||||||
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
|
|
||||||
* GNU General Public License for more details.
|
|
||||||
*
|
|
||||||
* You should have received a copy of the GNU General Public License
|
|
||||||
* along with this program. If not, see <http://www.gnu.org/licenses/>.
|
|
||||||
*
|
|
||||||
*/
|
|
||||||
|
|
||||||
/**
|
|
||||||
* Marlin Firmware -- G26 - Mesh Validation Tool
|
|
||||||
*/
|
|
||||||
|
|
||||||
#include "../../inc/MarlinConfig.h"
|
|
||||||
|
|
||||||
#if ENABLED(AUTO_BED_LEVELING_UBL) && ENABLED(UBL_G26_MESH_VALIDATION)
|
|
||||||
|
|
||||||
#include "ubl.h"
|
|
||||||
|
|
||||||
#include "../../Marlin.h"
|
|
||||||
#include "../../module/planner.h"
|
|
||||||
#include "../../module/stepper.h"
|
|
||||||
#include "../../module/motion.h"
|
|
||||||
#include "../../module/temperature.h"
|
|
||||||
#include "../../lcd/ultralcd.h"
|
|
||||||
#include "../../gcode/parser.h"
|
|
||||||
|
|
||||||
#define EXTRUSION_MULTIPLIER 1.0
|
|
||||||
#define RETRACTION_MULTIPLIER 1.0
|
|
||||||
#define NOZZLE 0.4
|
|
||||||
#define FILAMENT 1.75
|
|
||||||
#define LAYER_HEIGHT 0.2
|
|
||||||
#define PRIME_LENGTH 10.0
|
|
||||||
#define BED_TEMP 60.0
|
|
||||||
#define HOTEND_TEMP 205.0
|
|
||||||
#define OOZE_AMOUNT 0.3
|
|
||||||
|
|
||||||
#define SIZE_OF_INTERSECTION_CIRCLES 5
|
|
||||||
#define SIZE_OF_CROSSHAIRS 3
|
|
||||||
|
|
||||||
#if SIZE_OF_CROSSHAIRS >= SIZE_OF_INTERSECTION_CIRCLES
|
|
||||||
#error "SIZE_OF_CROSSHAIRS must be less than SIZE_OF_INTERSECTION_CIRCLES."
|
|
||||||
#endif
|
|
||||||
|
|
||||||
/**
|
|
||||||
* G26 Mesh Validation Tool
|
|
||||||
*
|
|
||||||
* G26 is a Mesh Validation Tool intended to provide support for the Marlin Unified Bed Leveling System.
|
|
||||||
* In order to fully utilize and benefit from the Marlin Unified Bed Leveling System an accurate Mesh must
|
|
||||||
* be defined. G29 is designed to allow the user to quickly validate the correctness of her Mesh. It will
|
|
||||||
* first heat the bed and nozzle. It will then print lines and circles along the Mesh Cell boundaries and
|
|
||||||
* the intersections of those lines (respectively).
|
|
||||||
*
|
|
||||||
* This action allows the user to immediately see where the Mesh is properly defined and where it needs to
|
|
||||||
* be edited. The command will generate the Mesh lines closest to the nozzle's starting position. Alternatively
|
|
||||||
* the user can specify the X and Y position of interest with command parameters. This allows the user to
|
|
||||||
* focus on a particular area of the Mesh where attention is needed.
|
|
||||||
*
|
|
||||||
* B # Bed Set the Bed Temperature. If not specified, a default of 60 C. will be assumed.
|
|
||||||
*
|
|
||||||
* C Current When searching for Mesh Intersection points to draw, use the current nozzle location
|
|
||||||
* as the base for any distance comparison.
|
|
||||||
*
|
|
||||||
* D Disable Disable the Unified Bed Leveling System. In the normal case the user is invoking this
|
|
||||||
* command to see how well a Mesh as been adjusted to match a print surface. In order to do
|
|
||||||
* this the Unified Bed Leveling System is turned on by the G26 command. The D parameter
|
|
||||||
* alters the command's normal behaviour and disables the Unified Bed Leveling System even if
|
|
||||||
* it is on.
|
|
||||||
*
|
|
||||||
* H # Hotend Set the Nozzle Temperature. If not specified, a default of 205 C. will be assumed.
|
|
||||||
*
|
|
||||||
* F # Filament Used to specify the diameter of the filament being used. If not specified
|
|
||||||
* 1.75mm filament is assumed. If you are not getting acceptable results by using the
|
|
||||||
* 'correct' numbers, you can scale this number up or down a little bit to change the amount
|
|
||||||
* of filament that is being extruded during the printing of the various lines on the bed.
|
|
||||||
*
|
|
||||||
* K Keep-On Keep the heaters turned on at the end of the command.
|
|
||||||
*
|
|
||||||
* L # Layer Layer height. (Height of nozzle above bed) If not specified .20mm will be used.
|
|
||||||
*
|
|
||||||
* O # Ooooze How much your nozzle will Ooooze filament while getting in position to print. This
|
|
||||||
* is over kill, but using this parameter will let you get the very first 'circle' perfect
|
|
||||||
* so you have a trophy to peel off of the bed and hang up to show how perfectly you have your
|
|
||||||
* Mesh calibrated. If not specified, a filament length of .3mm is assumed.
|
|
||||||
*
|
|
||||||
* P # Prime Prime the nozzle with specified length of filament. If this parameter is not
|
|
||||||
* given, no prime action will take place. If the parameter specifies an amount, that much
|
|
||||||
* will be purged before continuing. If no amount is specified the command will start
|
|
||||||
* purging filament until the user provides an LCD Click and then it will continue with
|
|
||||||
* printing the Mesh. You can carefully remove the spent filament with a needle nose
|
|
||||||
* pliers while holding the LCD Click wheel in a depressed state. If you do not have
|
|
||||||
* an LCD, you must specify a value if you use P.
|
|
||||||
*
|
|
||||||
* Q # Multiplier Retraction Multiplier. Normally not needed. Retraction defaults to 1.0mm and
|
|
||||||
* un-retraction is at 1.2mm These numbers will be scaled by the specified amount
|
|
||||||
*
|
|
||||||
* R # Repeat Prints the number of patterns given as a parameter, starting at the current location.
|
|
||||||
* If a parameter isn't given, every point will be printed unless G26 is interrupted.
|
|
||||||
* This works the same way that the UBL G29 P4 R parameter works.
|
|
||||||
*
|
|
||||||
* NOTE: If you do not have an LCD, you -must- specify R. This is to ensure that you are
|
|
||||||
* aware that there's some risk associated with printing without the ability to abort in
|
|
||||||
* cases where mesh point Z value may be inaccurate. As above, if you do not include a
|
|
||||||
* parameter, every point will be printed.
|
|
||||||
*
|
|
||||||
* S # Nozzle Used to control the size of nozzle diameter. If not specified, a .4mm nozzle is assumed.
|
|
||||||
*
|
|
||||||
* U # Random Randomize the order that the circles are drawn on the bed. The search for the closest
|
|
||||||
* undrawn cicle is still done. But the distance to the location for each circle has a
|
|
||||||
* random number of the size specified added to it. Specifying S50 will give an interesting
|
|
||||||
* deviation from the normal behaviour on a 10 x 10 Mesh.
|
|
||||||
*
|
|
||||||
* X # X Coord. Specify the starting location of the drawing activity.
|
|
||||||
*
|
|
||||||
* Y # Y Coord. Specify the starting location of the drawing activity.
|
|
||||||
*/
|
|
||||||
|
|
||||||
// External references
|
|
||||||
|
|
||||||
extern Planner planner;
|
|
||||||
#if ENABLED(ULTRA_LCD)
|
|
||||||
extern char lcd_status_message[];
|
|
||||||
#endif
|
|
||||||
extern float destination[XYZE];
|
|
||||||
extern void set_destination_to_current() { COPY(destination, current_position); }
|
|
||||||
void prepare_move_to_destination();
|
|
||||||
#if AVR_AT90USB1286_FAMILY // Teensyduino & Printrboard IDE extensions have compile errors without this
|
|
||||||
inline void sync_plan_position_e() { planner.set_e_position_mm(current_position[E_AXIS]); }
|
|
||||||
inline void set_current_to_destination() { COPY(current_position, destination); }
|
|
||||||
#else
|
|
||||||
extern void sync_plan_position_e();
|
|
||||||
extern void set_current_to_destination();
|
|
||||||
#endif
|
|
||||||
#if ENABLED(NEWPANEL)
|
|
||||||
void lcd_setstatusPGM(const char* const message, const int8_t level);
|
|
||||||
void chirp_at_user();
|
|
||||||
#endif
|
|
||||||
|
|
||||||
// Private functions
|
|
||||||
|
|
||||||
static uint16_t circle_flags[16], horizontal_mesh_line_flags[16], vertical_mesh_line_flags[16];
|
|
||||||
float g26_e_axis_feedrate = 0.020,
|
|
||||||
random_deviation = 0.0;
|
|
||||||
|
|
||||||
static bool g26_retracted = false; // Track the retracted state of the nozzle so mismatched
|
|
||||||
// retracts/recovers won't result in a bad state.
|
|
||||||
|
|
||||||
float valid_trig_angle(float);
|
|
||||||
|
|
||||||
float unified_bed_leveling::g26_extrusion_multiplier,
|
|
||||||
unified_bed_leveling::g26_retraction_multiplier,
|
|
||||||
unified_bed_leveling::g26_nozzle,
|
|
||||||
unified_bed_leveling::g26_filament_diameter,
|
|
||||||
unified_bed_leveling::g26_layer_height,
|
|
||||||
unified_bed_leveling::g26_prime_length,
|
|
||||||
unified_bed_leveling::g26_x_pos,
|
|
||||||
unified_bed_leveling::g26_y_pos,
|
|
||||||
unified_bed_leveling::g26_ooze_amount;
|
|
||||||
|
|
||||||
int16_t unified_bed_leveling::g26_bed_temp,
|
|
||||||
unified_bed_leveling::g26_hotend_temp;
|
|
||||||
|
|
||||||
int8_t unified_bed_leveling::g26_prime_flag;
|
|
||||||
|
|
||||||
bool unified_bed_leveling::g26_continue_with_closest,
|
|
||||||
unified_bed_leveling::g26_keep_heaters_on;
|
|
||||||
|
|
||||||
int16_t unified_bed_leveling::g26_repeats;
|
|
||||||
|
|
||||||
void unified_bed_leveling::G26_line_to_destination(const float &feed_rate) {
|
|
||||||
const float save_feedrate = feedrate_mm_s;
|
|
||||||
feedrate_mm_s = feed_rate; // use specified feed rate
|
|
||||||
prepare_move_to_destination(); // will ultimately call ubl.line_to_destination_cartesian or ubl.prepare_linear_move_to for UBL_DELTA
|
|
||||||
feedrate_mm_s = save_feedrate; // restore global feed rate
|
|
||||||
}
|
|
||||||
|
|
||||||
#if ENABLED(NEWPANEL)
|
|
||||||
/**
|
|
||||||
* Detect ubl_lcd_clicked, debounce it, and return true for cancel
|
|
||||||
*/
|
|
||||||
bool user_canceled() {
|
|
||||||
if (!ubl_lcd_clicked()) return false;
|
|
||||||
safe_delay(10); // Wait for click to settle
|
|
||||||
|
|
||||||
#if ENABLED(ULTRA_LCD)
|
|
||||||
lcd_setstatusPGM(PSTR("Mesh Validation Stopped."), 99);
|
|
||||||
lcd_quick_feedback();
|
|
||||||
#endif
|
|
||||||
|
|
||||||
while (!ubl_lcd_clicked()) idle(); // Wait for button release
|
|
||||||
|
|
||||||
// If the button is suddenly pressed again,
|
|
||||||
// ask the user to resolve the issue
|
|
||||||
lcd_setstatusPGM(PSTR("Release button"), 99); // will never appear...
|
|
||||||
while (ubl_lcd_clicked()) idle(); // unless this loop happens
|
|
||||||
lcd_reset_status();
|
|
||||||
|
|
||||||
return true;
|
|
||||||
}
|
|
||||||
#endif
|
|
||||||
|
|
||||||
/**
|
|
||||||
* G26: Mesh Validation Pattern generation.
|
|
||||||
*
|
|
||||||
* Used to interactively edit UBL's Mesh by placing the
|
|
||||||
* nozzle in a problem area and doing a G29 P4 R command.
|
|
||||||
*/
|
|
||||||
void unified_bed_leveling::G26() {
|
|
||||||
SERIAL_ECHOLNPGM("G26 command started. Waiting for heater(s).");
|
|
||||||
float tmp, start_angle, end_angle;
|
|
||||||
int i, xi, yi;
|
|
||||||
mesh_index_pair location;
|
|
||||||
|
|
||||||
// Don't allow Mesh Validation without homing first,
|
|
||||||
// or if the parameter parsing did not go OK, abort
|
|
||||||
if (axis_unhomed_error() || parse_G26_parameters()) return;
|
|
||||||
|
|
||||||
if (current_position[Z_AXIS] < Z_CLEARANCE_BETWEEN_PROBES) {
|
|
||||||
do_blocking_move_to_z(Z_CLEARANCE_BETWEEN_PROBES);
|
|
||||||
stepper.synchronize();
|
|
||||||
set_current_to_destination();
|
|
||||||
}
|
|
||||||
|
|
||||||
if (turn_on_heaters()) goto LEAVE;
|
|
||||||
|
|
||||||
current_position[E_AXIS] = 0.0;
|
|
||||||
sync_plan_position_e();
|
|
||||||
|
|
||||||
if (g26_prime_flag && prime_nozzle()) goto LEAVE;
|
|
||||||
|
|
||||||
/**
|
|
||||||
* Bed is preheated
|
|
||||||
*
|
|
||||||
* Nozzle is at temperature
|
|
||||||
*
|
|
||||||
* Filament is primed!
|
|
||||||
*
|
|
||||||
* It's "Show Time" !!!
|
|
||||||
*/
|
|
||||||
|
|
||||||
ZERO(circle_flags);
|
|
||||||
ZERO(horizontal_mesh_line_flags);
|
|
||||||
ZERO(vertical_mesh_line_flags);
|
|
||||||
|
|
||||||
// Move nozzle to the specified height for the first layer
|
|
||||||
set_destination_to_current();
|
|
||||||
destination[Z_AXIS] = g26_layer_height;
|
|
||||||
move_to(destination, 0.0);
|
|
||||||
move_to(destination, g26_ooze_amount);
|
|
||||||
|
|
||||||
has_control_of_lcd_panel = true;
|
|
||||||
//debug_current_and_destination(PSTR("Starting G26 Mesh Validation Pattern."));
|
|
||||||
|
|
||||||
/**
|
|
||||||
* Declare and generate a sin() & cos() table to be used during the circle drawing. This will lighten
|
|
||||||
* the CPU load and make the arc drawing faster and more smooth
|
|
||||||
*/
|
|
||||||
float sin_table[360 / 30 + 1], cos_table[360 / 30 + 1];
|
|
||||||
for (i = 0; i <= 360 / 30; i++) {
|
|
||||||
cos_table[i] = SIZE_OF_INTERSECTION_CIRCLES * cos(RADIANS(valid_trig_angle(i * 30.0)));
|
|
||||||
sin_table[i] = SIZE_OF_INTERSECTION_CIRCLES * sin(RADIANS(valid_trig_angle(i * 30.0)));
|
|
||||||
}
|
|
||||||
|
|
||||||
do {
|
|
||||||
location = g26_continue_with_closest
|
|
||||||
? find_closest_circle_to_print(current_position[X_AXIS], current_position[Y_AXIS])
|
|
||||||
: find_closest_circle_to_print(g26_x_pos, g26_y_pos); // Find the closest Mesh Intersection to where we are now.
|
|
||||||
|
|
||||||
if (location.x_index >= 0 && location.y_index >= 0) {
|
|
||||||
const float circle_x = mesh_index_to_xpos(location.x_index),
|
|
||||||
circle_y = mesh_index_to_ypos(location.y_index);
|
|
||||||
|
|
||||||
// If this mesh location is outside the printable_radius, skip it.
|
|
||||||
|
|
||||||
if (!position_is_reachable_raw_xy(circle_x, circle_y)) continue;
|
|
||||||
|
|
||||||
xi = location.x_index; // Just to shrink the next few lines and make them easier to understand
|
|
||||||
yi = location.y_index;
|
|
||||||
|
|
||||||
if (g26_debug_flag) {
|
|
||||||
SERIAL_ECHOPAIR(" Doing circle at: (xi=", xi);
|
|
||||||
SERIAL_ECHOPAIR(", yi=", yi);
|
|
||||||
SERIAL_CHAR(')');
|
|
||||||
SERIAL_EOL();
|
|
||||||
}
|
|
||||||
|
|
||||||
start_angle = 0.0; // assume it is going to be a full circle
|
|
||||||
end_angle = 360.0;
|
|
||||||
if (xi == 0) { // Check for bottom edge
|
|
||||||
start_angle = -90.0;
|
|
||||||
end_angle = 90.0;
|
|
||||||
if (yi == 0) // it is an edge, check for the two left corners
|
|
||||||
start_angle = 0.0;
|
|
||||||
else if (yi == GRID_MAX_POINTS_Y - 1)
|
|
||||||
end_angle = 0.0;
|
|
||||||
}
|
|
||||||
else if (xi == GRID_MAX_POINTS_X - 1) { // Check for top edge
|
|
||||||
start_angle = 90.0;
|
|
||||||
end_angle = 270.0;
|
|
||||||
if (yi == 0) // it is an edge, check for the two right corners
|
|
||||||
end_angle = 180.0;
|
|
||||||
else if (yi == GRID_MAX_POINTS_Y - 1)
|
|
||||||
start_angle = 180.0;
|
|
||||||
}
|
|
||||||
else if (yi == 0) {
|
|
||||||
start_angle = 0.0; // only do the top side of the cirlce
|
|
||||||
end_angle = 180.0;
|
|
||||||
}
|
|
||||||
else if (yi == GRID_MAX_POINTS_Y - 1) {
|
|
||||||
start_angle = 180.0; // only do the bottom side of the cirlce
|
|
||||||
end_angle = 360.0;
|
|
||||||
}
|
|
||||||
|
|
||||||
for (tmp = start_angle; tmp < end_angle - 0.1; tmp += 30.0) {
|
|
||||||
|
|
||||||
#if ENABLED(NEWPANEL)
|
|
||||||
if (user_canceled()) goto LEAVE; // Check if the user wants to stop the Mesh Validation
|
|
||||||
#endif
|
|
||||||
|
|
||||||
int tmp_div_30 = tmp / 30.0;
|
|
||||||
if (tmp_div_30 < 0) tmp_div_30 += 360 / 30;
|
|
||||||
if (tmp_div_30 > 11) tmp_div_30 -= 360 / 30;
|
|
||||||
|
|
||||||
float x = circle_x + cos_table[tmp_div_30], // for speed, these are now a lookup table entry
|
|
||||||
y = circle_y + sin_table[tmp_div_30],
|
|
||||||
xe = circle_x + cos_table[tmp_div_30 + 1],
|
|
||||||
ye = circle_y + sin_table[tmp_div_30 + 1];
|
|
||||||
#if IS_KINEMATIC
|
|
||||||
// Check to make sure this segment is entirely on the bed, skip if not.
|
|
||||||
if (!position_is_reachable_raw_xy(x, y) || !position_is_reachable_raw_xy(xe, ye)) continue;
|
|
||||||
#else // not, we need to skip
|
|
||||||
x = constrain(x, X_MIN_POS + 1, X_MAX_POS - 1); // This keeps us from bumping the endstops
|
|
||||||
y = constrain(y, Y_MIN_POS + 1, Y_MAX_POS - 1);
|
|
||||||
xe = constrain(xe, X_MIN_POS + 1, X_MAX_POS - 1);
|
|
||||||
ye = constrain(ye, Y_MIN_POS + 1, Y_MAX_POS - 1);
|
|
||||||
#endif
|
|
||||||
|
|
||||||
//if (g26_debug_flag) {
|
|
||||||
// char ccc, *cptr, seg_msg[50], seg_num[10];
|
|
||||||
// strcpy(seg_msg, " segment: ");
|
|
||||||
// strcpy(seg_num, " \n");
|
|
||||||
// cptr = (char*) "01234567890ABCDEF????????";
|
|
||||||
// ccc = cptr[tmp_div_30];
|
|
||||||
// seg_num[1] = ccc;
|
|
||||||
// strcat(seg_msg, seg_num);
|
|
||||||
// debug_current_and_destination(seg_msg);
|
|
||||||
//}
|
|
||||||
|
|
||||||
print_line_from_here_to_there(LOGICAL_X_POSITION(x), LOGICAL_Y_POSITION(y), g26_layer_height, LOGICAL_X_POSITION(xe), LOGICAL_Y_POSITION(ye), g26_layer_height);
|
|
||||||
|
|
||||||
}
|
|
||||||
if (look_for_lines_to_connect())
|
|
||||||
goto LEAVE;
|
|
||||||
}
|
|
||||||
} while (--g26_repeats && location.x_index >= 0 && location.y_index >= 0);
|
|
||||||
|
|
||||||
LEAVE:
|
|
||||||
lcd_setstatusPGM(PSTR("Leaving G26"), -1);
|
|
||||||
|
|
||||||
retract_filament(destination);
|
|
||||||
destination[Z_AXIS] = Z_CLEARANCE_BETWEEN_PROBES;
|
|
||||||
|
|
||||||
//debug_current_and_destination(PSTR("ready to do Z-Raise."));
|
|
||||||
move_to(destination, 0); // Raise the nozzle
|
|
||||||
//debug_current_and_destination(PSTR("done doing Z-Raise."));
|
|
||||||
|
|
||||||
destination[X_AXIS] = g26_x_pos; // Move back to the starting position
|
|
||||||
destination[Y_AXIS] = g26_y_pos;
|
|
||||||
//destination[Z_AXIS] = Z_CLEARANCE_BETWEEN_PROBES; // Keep the nozzle where it is
|
|
||||||
|
|
||||||
move_to(destination, 0); // Move back to the starting position
|
|
||||||
//debug_current_and_destination(PSTR("done doing X/Y move."));
|
|
||||||
|
|
||||||
has_control_of_lcd_panel = false; // Give back control of the LCD Panel!
|
|
||||||
|
|
||||||
if (!g26_keep_heaters_on) {
|
|
||||||
#if HAS_TEMP_BED
|
|
||||||
thermalManager.setTargetBed(0);
|
|
||||||
#endif
|
|
||||||
thermalManager.setTargetHotend(0, 0);
|
|
||||||
}
|
|
||||||
}
|
|
||||||
|
|
||||||
float valid_trig_angle(float d) {
|
|
||||||
while (d > 360.0) d -= 360.0;
|
|
||||||
while (d < 0.0) d += 360.0;
|
|
||||||
return d;
|
|
||||||
}
|
|
||||||
|
|
||||||
mesh_index_pair unified_bed_leveling::find_closest_circle_to_print(const float &X, const float &Y) {
|
|
||||||
float closest = 99999.99;
|
|
||||||
mesh_index_pair return_val;
|
|
||||||
|
|
||||||
return_val.x_index = return_val.y_index = -1;
|
|
||||||
|
|
||||||
for (uint8_t i = 0; i < GRID_MAX_POINTS_X; i++) {
|
|
||||||
for (uint8_t j = 0; j < GRID_MAX_POINTS_Y; j++) {
|
|
||||||
if (!is_bit_set(circle_flags, i, j)) {
|
|
||||||
const float mx = mesh_index_to_xpos(i), // We found a circle that needs to be printed
|
|
||||||
my = mesh_index_to_ypos(j);
|
|
||||||
|
|
||||||
// Get the distance to this intersection
|
|
||||||
float f = HYPOT(X - mx, Y - my);
|
|
||||||
|
|
||||||
// It is possible that we are being called with the values
|
|
||||||
// to let us find the closest circle to the start position.
|
|
||||||
// But if this is not the case, add a small weighting to the
|
|
||||||
// distance calculation to help it choose a better place to continue.
|
|
||||||
f += HYPOT(g26_x_pos - mx, g26_y_pos - my) / 15.0;
|
|
||||||
|
|
||||||
// Add in the specified amount of Random Noise to our search
|
|
||||||
if (random_deviation > 1.0)
|
|
||||||
f += random(0.0, random_deviation);
|
|
||||||
|
|
||||||
if (f < closest) {
|
|
||||||
closest = f; // We found a closer location that is still
|
|
||||||
return_val.x_index = i; // un-printed --- save the data for it
|
|
||||||
return_val.y_index = j;
|
|
||||||
return_val.distance = closest;
|
|
||||||
}
|
|
||||||
}
|
|
||||||
}
|
|
||||||
}
|
|
||||||
bit_set(circle_flags, return_val.x_index, return_val.y_index); // Mark this location as done.
|
|
||||||
return return_val;
|
|
||||||
}
|
|
||||||
|
|
||||||
bool unified_bed_leveling::look_for_lines_to_connect() {
|
|
||||||
float sx, sy, ex, ey;
|
|
||||||
|
|
||||||
for (uint8_t i = 0; i < GRID_MAX_POINTS_X; i++) {
|
|
||||||
for (uint8_t j = 0; j < GRID_MAX_POINTS_Y; j++) {
|
|
||||||
|
|
||||||
#if ENABLED(NEWPANEL)
|
|
||||||
if (user_canceled()) return true; // Check if the user wants to stop the Mesh Validation
|
|
||||||
#endif
|
|
||||||
|
|
||||||
if (i < GRID_MAX_POINTS_X) { // We can't connect to anything to the right than GRID_MAX_POINTS_X.
|
|
||||||
// This is already a half circle because we are at the edge of the bed.
|
|
||||||
|
|
||||||
if (is_bit_set(circle_flags, i, j) && is_bit_set(circle_flags, i + 1, j)) { // check if we can do a line to the left
|
|
||||||
if (!is_bit_set(horizontal_mesh_line_flags, i, j)) {
|
|
||||||
|
|
||||||
//
|
|
||||||
// We found two circles that need a horizontal line to connect them
|
|
||||||
// Print it!
|
|
||||||
//
|
|
||||||
sx = mesh_index_to_xpos( i ) + (SIZE_OF_INTERSECTION_CIRCLES - (SIZE_OF_CROSSHAIRS)); // right edge
|
|
||||||
ex = mesh_index_to_xpos(i + 1) - (SIZE_OF_INTERSECTION_CIRCLES - (SIZE_OF_CROSSHAIRS)); // left edge
|
|
||||||
|
|
||||||
sx = constrain(sx, X_MIN_POS + 1, X_MAX_POS - 1);
|
|
||||||
sy = ey = constrain(mesh_index_to_ypos(j), Y_MIN_POS + 1, Y_MAX_POS - 1);
|
|
||||||
ex = constrain(ex, X_MIN_POS + 1, X_MAX_POS - 1);
|
|
||||||
|
|
||||||
if (position_is_reachable_raw_xy(sx, sy) && position_is_reachable_raw_xy(ex, ey)) {
|
|
||||||
|
|
||||||
if (g26_debug_flag) {
|
|
||||||
SERIAL_ECHOPAIR(" Connecting with horizontal line (sx=", sx);
|
|
||||||
SERIAL_ECHOPAIR(", sy=", sy);
|
|
||||||
SERIAL_ECHOPAIR(") -> (ex=", ex);
|
|
||||||
SERIAL_ECHOPAIR(", ey=", ey);
|
|
||||||
SERIAL_CHAR(')');
|
|
||||||
SERIAL_EOL();
|
|
||||||
//debug_current_and_destination(PSTR("Connecting horizontal line."));
|
|
||||||
}
|
|
||||||
|
|
||||||
print_line_from_here_to_there(LOGICAL_X_POSITION(sx), LOGICAL_Y_POSITION(sy), g26_layer_height, LOGICAL_X_POSITION(ex), LOGICAL_Y_POSITION(ey), g26_layer_height);
|
|
||||||
}
|
|
||||||
bit_set(horizontal_mesh_line_flags, i, j); // Mark it as done so we don't do it again, even if we skipped it
|
|
||||||
}
|
|
||||||
}
|
|
||||||
|
|
||||||
if (j < GRID_MAX_POINTS_Y) { // We can't connect to anything further back than GRID_MAX_POINTS_Y.
|
|
||||||
// This is already a half circle because we are at the edge of the bed.
|
|
||||||
|
|
||||||
if (is_bit_set(circle_flags, i, j) && is_bit_set(circle_flags, i, j + 1)) { // check if we can do a line straight down
|
|
||||||
if (!is_bit_set( vertical_mesh_line_flags, i, j)) {
|
|
||||||
//
|
|
||||||
// We found two circles that need a vertical line to connect them
|
|
||||||
// Print it!
|
|
||||||
//
|
|
||||||
sy = mesh_index_to_ypos( j ) + (SIZE_OF_INTERSECTION_CIRCLES - (SIZE_OF_CROSSHAIRS)); // top edge
|
|
||||||
ey = mesh_index_to_ypos(j + 1) - (SIZE_OF_INTERSECTION_CIRCLES - (SIZE_OF_CROSSHAIRS)); // bottom edge
|
|
||||||
|
|
||||||
sx = ex = constrain(mesh_index_to_xpos(i), X_MIN_POS + 1, X_MAX_POS - 1);
|
|
||||||
sy = constrain(sy, Y_MIN_POS + 1, Y_MAX_POS - 1);
|
|
||||||
ey = constrain(ey, Y_MIN_POS + 1, Y_MAX_POS - 1);
|
|
||||||
|
|
||||||
if (position_is_reachable_raw_xy(sx, sy) && position_is_reachable_raw_xy(ex, ey)) {
|
|
||||||
|
|
||||||
if (g26_debug_flag) {
|
|
||||||
SERIAL_ECHOPAIR(" Connecting with vertical line (sx=", sx);
|
|
||||||
SERIAL_ECHOPAIR(", sy=", sy);
|
|
||||||
SERIAL_ECHOPAIR(") -> (ex=", ex);
|
|
||||||
SERIAL_ECHOPAIR(", ey=", ey);
|
|
||||||
SERIAL_CHAR(')');
|
|
||||||
SERIAL_EOL();
|
|
||||||
debug_current_and_destination(PSTR("Connecting vertical line."));
|
|
||||||
}
|
|
||||||
print_line_from_here_to_there(LOGICAL_X_POSITION(sx), LOGICAL_Y_POSITION(sy), g26_layer_height, LOGICAL_X_POSITION(ex), LOGICAL_Y_POSITION(ey), g26_layer_height);
|
|
||||||
}
|
|
||||||
bit_set(vertical_mesh_line_flags, i, j); // Mark it as done so we don't do it again, even if skipped
|
|
||||||
}
|
|
||||||
}
|
|
||||||
}
|
|
||||||
}
|
|
||||||
}
|
|
||||||
}
|
|
||||||
return false;
|
|
||||||
}
|
|
||||||
|
|
||||||
void unified_bed_leveling::move_to(const float &x, const float &y, const float &z, const float &e_delta) {
|
|
||||||
float feed_value;
|
|
||||||
static float last_z = -999.99;
|
|
||||||
|
|
||||||
bool has_xy_component = (x != current_position[X_AXIS] || y != current_position[Y_AXIS]); // Check if X or Y is involved in the movement.
|
|
||||||
|
|
||||||
if (z != last_z) {
|
|
||||||
last_z = z;
|
|
||||||
feed_value = planner.max_feedrate_mm_s[Z_AXIS]/(3.0); // Base the feed rate off of the configured Z_AXIS feed rate
|
|
||||||
|
|
||||||
destination[X_AXIS] = current_position[X_AXIS];
|
|
||||||
destination[Y_AXIS] = current_position[Y_AXIS];
|
|
||||||
destination[Z_AXIS] = z; // We know the last_z==z or we wouldn't be in this block of code.
|
|
||||||
destination[E_AXIS] = current_position[E_AXIS];
|
|
||||||
|
|
||||||
G26_line_to_destination(feed_value);
|
|
||||||
|
|
||||||
stepper.synchronize();
|
|
||||||
set_destination_to_current();
|
|
||||||
}
|
|
||||||
|
|
||||||
// Check if X or Y is involved in the movement.
|
|
||||||
// Yes: a 'normal' movement. No: a retract() or recover()
|
|
||||||
feed_value = has_xy_component ? PLANNER_XY_FEEDRATE() / 10.0 : planner.max_feedrate_mm_s[E_AXIS] / 1.5;
|
|
||||||
|
|
||||||
if (g26_debug_flag) SERIAL_ECHOLNPAIR("in move_to() feed_value for XY:", feed_value);
|
|
||||||
|
|
||||||
destination[X_AXIS] = x;
|
|
||||||
destination[Y_AXIS] = y;
|
|
||||||
destination[E_AXIS] += e_delta;
|
|
||||||
|
|
||||||
G26_line_to_destination(feed_value);
|
|
||||||
|
|
||||||
stepper.synchronize();
|
|
||||||
set_destination_to_current();
|
|
||||||
|
|
||||||
}
|
|
||||||
|
|
||||||
void unified_bed_leveling::retract_filament(const float where[XYZE]) {
|
|
||||||
if (!g26_retracted) { // Only retract if we are not already retracted!
|
|
||||||
g26_retracted = true;
|
|
||||||
move_to(where, -1.0 * g26_retraction_multiplier);
|
|
||||||
}
|
|
||||||
}
|
|
||||||
|
|
||||||
void unified_bed_leveling::recover_filament(const float where[XYZE]) {
|
|
||||||
if (g26_retracted) { // Only un-retract if we are retracted.
|
|
||||||
move_to(where, 1.2 * g26_retraction_multiplier);
|
|
||||||
g26_retracted = false;
|
|
||||||
}
|
|
||||||
}
|
|
||||||
|
|
||||||
/**
|
|
||||||
* print_line_from_here_to_there() takes two cartesian coordinates and draws a line from one
|
|
||||||
* to the other. But there are really three sets of coordinates involved. The first coordinate
|
|
||||||
* is the present location of the nozzle. We don't necessarily want to print from this location.
|
|
||||||
* We first need to move the nozzle to the start of line segment where we want to print. Once
|
|
||||||
* there, we can use the two coordinates supplied to draw the line.
|
|
||||||
*
|
|
||||||
* Note: Although we assume the first set of coordinates is the start of the line and the second
|
|
||||||
* set of coordinates is the end of the line, it does not always work out that way. This function
|
|
||||||
* optimizes the movement to minimize the travel distance before it can start printing. This saves
|
|
||||||
* a lot of time and eliminates a lot of nonsensical movement of the nozzle. However, it does
|
|
||||||
* cause a lot of very little short retracement of th nozzle when it draws the very first line
|
|
||||||
* segment of a 'circle'. The time this requires is very short and is easily saved by the other
|
|
||||||
* cases where the optimization comes into play.
|
|
||||||
*/
|
|
||||||
void unified_bed_leveling::print_line_from_here_to_there(const float &sx, const float &sy, const float &sz, const float &ex, const float &ey, const float &ez) {
|
|
||||||
const float dx_s = current_position[X_AXIS] - sx, // find our distance from the start of the actual line segment
|
|
||||||
dy_s = current_position[Y_AXIS] - sy,
|
|
||||||
dist_start = HYPOT2(dx_s, dy_s), // We don't need to do a sqrt(), we can compare the distance^2
|
|
||||||
// to save computation time
|
|
||||||
dx_e = current_position[X_AXIS] - ex, // find our distance from the end of the actual line segment
|
|
||||||
dy_e = current_position[Y_AXIS] - ey,
|
|
||||||
dist_end = HYPOT2(dx_e, dy_e),
|
|
||||||
|
|
||||||
line_length = HYPOT(ex - sx, ey - sy);
|
|
||||||
|
|
||||||
// If the end point of the line is closer to the nozzle, flip the direction,
|
|
||||||
// moving from the end to the start. On very small lines the optimization isn't worth it.
|
|
||||||
if (dist_end < dist_start && (SIZE_OF_INTERSECTION_CIRCLES) < FABS(line_length)) {
|
|
||||||
return print_line_from_here_to_there(ex, ey, ez, sx, sy, sz);
|
|
||||||
}
|
|
||||||
|
|
||||||
// Decide whether to retract & bump
|
|
||||||
|
|
||||||
if (dist_start > 2.0) {
|
|
||||||
retract_filament(destination);
|
|
||||||
//todo: parameterize the bump height with a define
|
|
||||||
move_to(current_position[X_AXIS], current_position[Y_AXIS], current_position[Z_AXIS] + 0.500, 0.0); // Z bump to minimize scraping
|
|
||||||
move_to(sx, sy, sz + 0.500, 0.0); // Get to the starting point with no extrusion while bumped
|
|
||||||
}
|
|
||||||
|
|
||||||
move_to(sx, sy, sz, 0.0); // Get to the starting point with no extrusion / un-Z bump
|
|
||||||
|
|
||||||
const float e_pos_delta = line_length * g26_e_axis_feedrate * g26_extrusion_multiplier;
|
|
||||||
|
|
||||||
recover_filament(destination);
|
|
||||||
move_to(ex, ey, ez, e_pos_delta); // Get to the ending point with an appropriate amount of extrusion
|
|
||||||
}
|
|
||||||
|
|
||||||
/**
|
|
||||||
* This function used to be inline code in G26. But there are so many
|
|
||||||
* parameters it made sense to turn them into static globals and get
|
|
||||||
* this code out of sight of the main routine.
|
|
||||||
*/
|
|
||||||
bool unified_bed_leveling::parse_G26_parameters() {
|
|
||||||
|
|
||||||
g26_extrusion_multiplier = EXTRUSION_MULTIPLIER;
|
|
||||||
g26_retraction_multiplier = RETRACTION_MULTIPLIER;
|
|
||||||
g26_nozzle = NOZZLE;
|
|
||||||
g26_filament_diameter = FILAMENT;
|
|
||||||
g26_layer_height = LAYER_HEIGHT;
|
|
||||||
g26_prime_length = PRIME_LENGTH;
|
|
||||||
g26_bed_temp = BED_TEMP;
|
|
||||||
g26_hotend_temp = HOTEND_TEMP;
|
|
||||||
g26_prime_flag = 0;
|
|
||||||
|
|
||||||
g26_ooze_amount = parser.linearval('O', OOZE_AMOUNT);
|
|
||||||
g26_keep_heaters_on = parser.boolval('K');
|
|
||||||
g26_continue_with_closest = parser.boolval('C');
|
|
||||||
|
|
||||||
if (parser.seenval('B')) {
|
|
||||||
g26_bed_temp = parser.value_celsius();
|
|
||||||
if (!WITHIN(g26_bed_temp, 15, 140)) {
|
|
||||||
SERIAL_PROTOCOLLNPGM("?Specified bed temperature not plausible.");
|
|
||||||
return UBL_ERR;
|
|
||||||
}
|
|
||||||
}
|
|
||||||
|
|
||||||
if (parser.seenval('L')) {
|
|
||||||
g26_layer_height = parser.value_linear_units();
|
|
||||||
if (!WITHIN(g26_layer_height, 0.0, 2.0)) {
|
|
||||||
SERIAL_PROTOCOLLNPGM("?Specified layer height not plausible.");
|
|
||||||
return UBL_ERR;
|
|
||||||
}
|
|
||||||
}
|
|
||||||
|
|
||||||
if (parser.seen('Q')) {
|
|
||||||
if (parser.has_value()) {
|
|
||||||
g26_retraction_multiplier = parser.value_float();
|
|
||||||
if (!WITHIN(g26_retraction_multiplier, 0.05, 15.0)) {
|
|
||||||
SERIAL_PROTOCOLLNPGM("?Specified Retraction Multiplier not plausible.");
|
|
||||||
return UBL_ERR;
|
|
||||||
}
|
|
||||||
}
|
|
||||||
else {
|
|
||||||
SERIAL_PROTOCOLLNPGM("?Retraction Multiplier must be specified.");
|
|
||||||
return UBL_ERR;
|
|
||||||
}
|
|
||||||
}
|
|
||||||
|
|
||||||
if (parser.seenval('S')) {
|
|
||||||
g26_nozzle = parser.value_float();
|
|
||||||
if (!WITHIN(g26_nozzle, 0.1, 1.0)) {
|
|
||||||
SERIAL_PROTOCOLLNPGM("?Specified nozzle size not plausible.");
|
|
||||||
return UBL_ERR;
|
|
||||||
}
|
|
||||||
}
|
|
||||||
|
|
||||||
if (parser.seen('P')) {
|
|
||||||
if (!parser.has_value()) {
|
|
||||||
#if ENABLED(NEWPANEL)
|
|
||||||
g26_prime_flag = -1;
|
|
||||||
#else
|
|
||||||
SERIAL_PROTOCOLLNPGM("?Prime length must be specified when not using an LCD.");
|
|
||||||
return UBL_ERR;
|
|
||||||
#endif
|
|
||||||
}
|
|
||||||
else {
|
|
||||||
g26_prime_flag++;
|
|
||||||
g26_prime_length = parser.value_linear_units();
|
|
||||||
if (!WITHIN(g26_prime_length, 0.0, 25.0)) {
|
|
||||||
SERIAL_PROTOCOLLNPGM("?Specified prime length not plausible.");
|
|
||||||
return UBL_ERR;
|
|
||||||
}
|
|
||||||
}
|
|
||||||
}
|
|
||||||
|
|
||||||
if (parser.seenval('F')) {
|
|
||||||
g26_filament_diameter = parser.value_linear_units();
|
|
||||||
if (!WITHIN(g26_filament_diameter, 1.0, 4.0)) {
|
|
||||||
SERIAL_PROTOCOLLNPGM("?Specified filament size not plausible.");
|
|
||||||
return UBL_ERR;
|
|
||||||
}
|
|
||||||
}
|
|
||||||
g26_extrusion_multiplier *= sq(1.75) / sq(g26_filament_diameter); // If we aren't using 1.75mm filament, we need to
|
|
||||||
// scale up or down the length needed to get the
|
|
||||||
// same volume of filament
|
|
||||||
|
|
||||||
g26_extrusion_multiplier *= g26_filament_diameter * sq(g26_nozzle) / sq(0.3); // Scale up by nozzle size
|
|
||||||
|
|
||||||
if (parser.seenval('H')) {
|
|
||||||
g26_hotend_temp = parser.value_celsius();
|
|
||||||
if (!WITHIN(g26_hotend_temp, 165, 280)) {
|
|
||||||
SERIAL_PROTOCOLLNPGM("?Specified nozzle temperature not plausible.");
|
|
||||||
return UBL_ERR;
|
|
||||||
}
|
|
||||||
}
|
|
||||||
|
|
||||||
if (parser.seen('U')) {
|
|
||||||
randomSeed(millis());
|
|
||||||
// This setting will persist for the next G26
|
|
||||||
random_deviation = parser.has_value() ? parser.value_float() : 50.0;
|
|
||||||
}
|
|
||||||
|
|
||||||
#if ENABLED(NEWPANEL)
|
|
||||||
g26_repeats = parser.intval('R', GRID_MAX_POINTS + 1);
|
|
||||||
#else
|
|
||||||
if (!parser.seen('R')) {
|
|
||||||
SERIAL_PROTOCOLLNPGM("?(R)epeat must be specified when not using an LCD.");
|
|
||||||
return UBL_ERR;
|
|
||||||
}
|
|
||||||
else
|
|
||||||
g26_repeats = parser.has_value() ? parser.value_int() : GRID_MAX_POINTS + 1;
|
|
||||||
#endif
|
|
||||||
if (g26_repeats < 1) {
|
|
||||||
SERIAL_PROTOCOLLNPGM("?(R)epeat value not plausible; must be at least 1.");
|
|
||||||
return UBL_ERR;
|
|
||||||
}
|
|
||||||
|
|
||||||
g26_x_pos = parser.linearval('X', current_position[X_AXIS]);
|
|
||||||
g26_y_pos = parser.linearval('Y', current_position[Y_AXIS]);
|
|
||||||
if (!position_is_reachable_xy(g26_x_pos, g26_y_pos)) {
|
|
||||||
SERIAL_PROTOCOLLNPGM("?Specified X,Y coordinate out of bounds.");
|
|
||||||
return UBL_ERR;
|
|
||||||
}
|
|
||||||
|
|
||||||
/**
|
|
||||||
* Wait until all parameters are verified before altering the state!
|
|
||||||
*/
|
|
||||||
set_bed_leveling_enabled(!parser.seen('D'));
|
|
||||||
|
|
||||||
return UBL_OK;
|
|
||||||
}
|
|
||||||
|
|
||||||
#if ENABLED(NEWPANEL)
|
|
||||||
bool unified_bed_leveling::exit_from_g26() {
|
|
||||||
lcd_setstatusPGM(PSTR("Leaving G26"), -1);
|
|
||||||
while (ubl_lcd_clicked()) idle();
|
|
||||||
return UBL_ERR;
|
|
||||||
}
|
|
||||||
#endif
|
|
||||||
|
|
||||||
/**
|
|
||||||
* Turn on the bed and nozzle heat and
|
|
||||||
* wait for them to get up to temperature.
|
|
||||||
*/
|
|
||||||
bool unified_bed_leveling::turn_on_heaters() {
|
|
||||||
millis_t next = millis() + 5000UL;
|
|
||||||
#if HAS_TEMP_BED
|
|
||||||
#if ENABLED(ULTRA_LCD)
|
|
||||||
if (g26_bed_temp > 25) {
|
|
||||||
lcd_setstatusPGM(PSTR("G26 Heating Bed."), 99);
|
|
||||||
lcd_quick_feedback();
|
|
||||||
#endif
|
|
||||||
has_control_of_lcd_panel = true;
|
|
||||||
thermalManager.setTargetBed(g26_bed_temp);
|
|
||||||
while (abs(thermalManager.degBed() - g26_bed_temp) > 3) {
|
|
||||||
|
|
||||||
#if ENABLED(NEWPANEL)
|
|
||||||
if (ubl_lcd_clicked()) return exit_from_g26();
|
|
||||||
#endif
|
|
||||||
|
|
||||||
if (ELAPSED(millis(), next)) {
|
|
||||||
next = millis() + 5000UL;
|
|
||||||
print_heaterstates();
|
|
||||||
SERIAL_EOL();
|
|
||||||
}
|
|
||||||
idle();
|
|
||||||
}
|
|
||||||
#if ENABLED(ULTRA_LCD)
|
|
||||||
}
|
|
||||||
lcd_setstatusPGM(PSTR("G26 Heating Nozzle."), 99);
|
|
||||||
lcd_quick_feedback();
|
|
||||||
#endif
|
|
||||||
#endif
|
|
||||||
|
|
||||||
// Start heating the nozzle and wait for it to reach temperature.
|
|
||||||
thermalManager.setTargetHotend(g26_hotend_temp, 0);
|
|
||||||
while (abs(thermalManager.degHotend(0) - g26_hotend_temp) > 3) {
|
|
||||||
|
|
||||||
#if ENABLED(NEWPANEL)
|
|
||||||
if (ubl_lcd_clicked()) return exit_from_g26();
|
|
||||||
#endif
|
|
||||||
|
|
||||||
if (ELAPSED(millis(), next)) {
|
|
||||||
next = millis() + 5000UL;
|
|
||||||
print_heaterstates();
|
|
||||||
SERIAL_EOL();
|
|
||||||
}
|
|
||||||
idle();
|
|
||||||
}
|
|
||||||
|
|
||||||
#if ENABLED(ULTRA_LCD)
|
|
||||||
lcd_reset_status();
|
|
||||||
lcd_quick_feedback();
|
|
||||||
#endif
|
|
||||||
|
|
||||||
return UBL_OK;
|
|
||||||
}
|
|
||||||
|
|
||||||
/**
|
|
||||||
* Prime the nozzle if needed. Return true on error.
|
|
||||||
*/
|
|
||||||
bool unified_bed_leveling::prime_nozzle() {
|
|
||||||
|
|
||||||
#if ENABLED(NEWPANEL)
|
|
||||||
float Total_Prime = 0.0;
|
|
||||||
|
|
||||||
if (g26_prime_flag == -1) { // The user wants to control how much filament gets purged
|
|
||||||
|
|
||||||
has_control_of_lcd_panel = true;
|
|
||||||
lcd_setstatusPGM(PSTR("User-Controlled Prime"), 99);
|
|
||||||
chirp_at_user();
|
|
||||||
|
|
||||||
set_destination_to_current();
|
|
||||||
|
|
||||||
recover_filament(destination); // Make sure G26 doesn't think the filament is retracted().
|
|
||||||
|
|
||||||
while (!ubl_lcd_clicked()) {
|
|
||||||
chirp_at_user();
|
|
||||||
destination[E_AXIS] += 0.25;
|
|
||||||
#ifdef PREVENT_LENGTHY_EXTRUDE
|
|
||||||
Total_Prime += 0.25;
|
|
||||||
if (Total_Prime >= EXTRUDE_MAXLENGTH) return UBL_ERR;
|
|
||||||
#endif
|
|
||||||
G26_line_to_destination(planner.max_feedrate_mm_s[E_AXIS] / 15.0);
|
|
||||||
|
|
||||||
stepper.synchronize(); // Without this synchronize, the purge is more consistent,
|
|
||||||
// but because the planner has a buffer, we won't be able
|
|
||||||
// to stop as quickly. So we put up with the less smooth
|
|
||||||
// action to give the user a more responsive 'Stop'.
|
|
||||||
set_destination_to_current();
|
|
||||||
idle();
|
|
||||||
}
|
|
||||||
|
|
||||||
while (ubl_lcd_clicked()) idle(); // Debounce Encoder Wheel
|
|
||||||
|
|
||||||
#if ENABLED(ULTRA_LCD)
|
|
||||||
strcpy_P(lcd_status_message, PSTR("Done Priming")); // We can't do lcd_setstatusPGM() without having it continue;
|
|
||||||
// So... We cheat to get a message up.
|
|
||||||
lcd_setstatusPGM(PSTR("Done Priming"), 99);
|
|
||||||
lcd_quick_feedback();
|
|
||||||
#endif
|
|
||||||
|
|
||||||
has_control_of_lcd_panel = false;
|
|
||||||
|
|
||||||
}
|
|
||||||
else {
|
|
||||||
#else
|
|
||||||
{
|
|
||||||
#endif
|
|
||||||
#if ENABLED(ULTRA_LCD)
|
|
||||||
lcd_setstatusPGM(PSTR("Fixed Length Prime."), 99);
|
|
||||||
lcd_quick_feedback();
|
|
||||||
#endif
|
|
||||||
set_destination_to_current();
|
|
||||||
destination[E_AXIS] += g26_prime_length;
|
|
||||||
G26_line_to_destination(planner.max_feedrate_mm_s[E_AXIS] / 15.0);
|
|
||||||
stepper.synchronize();
|
|
||||||
set_destination_to_current();
|
|
||||||
retract_filament(destination);
|
|
||||||
}
|
|
||||||
|
|
||||||
return UBL_OK;
|
|
||||||
}
|
|
||||||
|
|
||||||
#endif // AUTO_BED_LEVELING_UBL && UBL_G26_MESH_VALIDATION
|
|
|
@ -20,6 +20,18 @@
|
||||||
*
|
*
|
||||||
*/
|
*/
|
||||||
|
|
||||||
|
#include "../../inc/MarlinConfig.h"
|
||||||
|
|
||||||
|
#if HAS_LEVELING
|
||||||
|
|
||||||
|
#include "../gcode.h"
|
||||||
|
#include "../../feature/bedlevel/bedlevel.h"
|
||||||
|
#include "../../module/planner.h"
|
||||||
|
|
||||||
|
#if ENABLED(EEPROM_SETTINGS)
|
||||||
|
#include "../../module/configuration_store.h"
|
||||||
|
#endif
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* M420: Enable/Disable Bed Leveling and/or set the Z fade height.
|
* M420: Enable/Disable Bed Leveling and/or set the Z fade height.
|
||||||
*
|
*
|
||||||
|
@ -31,7 +43,7 @@
|
||||||
*
|
*
|
||||||
* L[index] Load UBL mesh from index (0 is default)
|
* L[index] Load UBL mesh from index (0 is default)
|
||||||
*/
|
*/
|
||||||
void gcode_M420() {
|
void GcodeSuite::M420() {
|
||||||
|
|
||||||
#if ENABLED(AUTO_BED_LEVELING_UBL)
|
#if ENABLED(AUTO_BED_LEVELING_UBL)
|
||||||
|
|
||||||
|
@ -64,10 +76,10 @@ void gcode_M420() {
|
||||||
#endif
|
#endif
|
||||||
}
|
}
|
||||||
|
|
||||||
// L to load a mesh from the EEPROM
|
// L or V display the map info
|
||||||
if (parser.seen('L') || parser.seen('V')) {
|
if (parser.seen('L') || parser.seen('V')) {
|
||||||
ubl.display_map(0); // Currently only supports one map type
|
ubl.display_map(0); // Currently only supports one map type
|
||||||
SERIAL_ECHOLNPAIR("UBL_MESH_VALID = ", UBL_MESH_VALID);
|
SERIAL_ECHOLNPAIR("ubl.mesh_is_valid = ", ubl.mesh_is_valid());
|
||||||
SERIAL_ECHOLNPAIR("ubl.state.storage_slot = ", ubl.state.storage_slot);
|
SERIAL_ECHOLNPAIR("ubl.state.storage_slot = ", ubl.state.storage_slot);
|
||||||
}
|
}
|
||||||
|
|
||||||
|
@ -119,3 +131,5 @@ void gcode_M420() {
|
||||||
SERIAL_ECHOLNPGM(MSG_OFF);
|
SERIAL_ECHOLNPGM(MSG_OFF);
|
||||||
#endif
|
#endif
|
||||||
}
|
}
|
||||||
|
|
||||||
|
#endif // HAS_LEVELING
|
|
@ -20,6 +20,29 @@
|
||||||
*
|
*
|
||||||
*/
|
*/
|
||||||
|
|
||||||
|
/**
|
||||||
|
* G29.cpp - Auto Bed Leveling
|
||||||
|
*/
|
||||||
|
|
||||||
|
#include "../../../inc/MarlinConfig.h"
|
||||||
|
|
||||||
|
#if OLDSCHOOL_ABL
|
||||||
|
|
||||||
|
#include "../../gcode.h"
|
||||||
|
#include "../../../feature/bedlevel/bedlevel.h"
|
||||||
|
#include "../../../module/motion.h"
|
||||||
|
#include "../../../module/planner.h"
|
||||||
|
#include "../../../module/stepper.h"
|
||||||
|
#include "../../../module/probe.h"
|
||||||
|
|
||||||
|
#if ENABLED(LCD_BED_LEVELING) && ENABLED(PROBE_MANUALLY)
|
||||||
|
#include "../../../lcd/ultralcd.h"
|
||||||
|
#endif
|
||||||
|
|
||||||
|
#if ENABLED(AUTO_BED_LEVELING_LINEAR)
|
||||||
|
#include "../../../libs/least_squares_fit.h"
|
||||||
|
#endif
|
||||||
|
|
||||||
#if ABL_GRID
|
#if ABL_GRID
|
||||||
#if ENABLED(PROBE_Y_FIRST)
|
#if ENABLED(PROBE_Y_FIRST)
|
||||||
#define PR_OUTER_VAR xCount
|
#define PR_OUTER_VAR xCount
|
||||||
|
@ -106,7 +129,7 @@
|
||||||
* There's no extra effect if you have a fixed Z probe.
|
* There's no extra effect if you have a fixed Z probe.
|
||||||
*
|
*
|
||||||
*/
|
*/
|
||||||
void gcode_G29() {
|
void GcodeSuite::G29() {
|
||||||
|
|
||||||
// G29 Q is also available if debugging
|
// G29 Q is also available if debugging
|
||||||
#if ENABLED(DEBUG_LEVELING_FEATURE)
|
#if ENABLED(DEBUG_LEVELING_FEATURE)
|
||||||
|
@ -176,12 +199,10 @@ void gcode_G29() {
|
||||||
abl_grid_points_y = GRID_MAX_POINTS_Y;
|
abl_grid_points_y = GRID_MAX_POINTS_Y;
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#if ENABLED(AUTO_BED_LEVELING_LINEAR) || ENABLED(PROBE_MANUALLY)
|
#if ENABLED(AUTO_BED_LEVELING_LINEAR)
|
||||||
#if ENABLED(AUTO_BED_LEVELING_LINEAR)
|
ABL_VAR int abl2;
|
||||||
ABL_VAR int abl2;
|
#elif ENABLED(PROBE_MANUALLY) // Bilinear
|
||||||
#else // Bilinear
|
int constexpr abl2 = GRID_MAX_POINTS;
|
||||||
int constexpr abl2 = GRID_MAX_POINTS;
|
|
||||||
#endif
|
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#if ENABLED(AUTO_BED_LEVELING_BILINEAR)
|
#if ENABLED(AUTO_BED_LEVELING_BILINEAR)
|
||||||
|
@ -199,7 +220,9 @@ void gcode_G29() {
|
||||||
|
|
||||||
#elif ENABLED(AUTO_BED_LEVELING_3POINT)
|
#elif ENABLED(AUTO_BED_LEVELING_3POINT)
|
||||||
|
|
||||||
int constexpr abl2 = 3;
|
#if ENABLED(PROBE_MANUALLY)
|
||||||
|
int constexpr abl2 = 3; // used to show total points
|
||||||
|
#endif
|
||||||
|
|
||||||
// Probe at 3 arbitrary points
|
// Probe at 3 arbitrary points
|
||||||
ABL_VAR vector_3 points[3] = {
|
ABL_VAR vector_3 points[3] = {
|
||||||
|
@ -944,3 +967,5 @@ void gcode_G29() {
|
||||||
if (planner.abl_enabled)
|
if (planner.abl_enabled)
|
||||||
SYNC_PLAN_POSITION_KINEMATIC();
|
SYNC_PLAN_POSITION_KINEMATIC();
|
||||||
}
|
}
|
||||||
|
|
||||||
|
#endif // OLDSCHOOL_ABL
|
|
@ -20,6 +20,17 @@
|
||||||
*
|
*
|
||||||
*/
|
*/
|
||||||
|
|
||||||
|
/**
|
||||||
|
* M421.cpp - Auto Bed Leveling
|
||||||
|
*/
|
||||||
|
|
||||||
|
#include "../../../inc/MarlinConfig.h"
|
||||||
|
|
||||||
|
#if ENABLED(AUTO_BED_LEVELING_BILINEAR)
|
||||||
|
|
||||||
|
#include "../../gcode.h"
|
||||||
|
#include "../../../feature/bedlevel/abl/abl.h"
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* M421: Set a single Mesh Bed Leveling Z coordinate
|
* M421: Set a single Mesh Bed Leveling Z coordinate
|
||||||
*
|
*
|
||||||
|
@ -27,7 +38,7 @@
|
||||||
* M421 I<xindex> J<yindex> Z<linear>
|
* M421 I<xindex> J<yindex> Z<linear>
|
||||||
* M421 I<xindex> J<yindex> Q<offset>
|
* M421 I<xindex> J<yindex> Q<offset>
|
||||||
*/
|
*/
|
||||||
void gcode_M421() {
|
void GcodeSuite::M421() {
|
||||||
int8_t ix = parser.intval('I', -1), iy = parser.intval('J', -1);
|
int8_t ix = parser.intval('I', -1), iy = parser.intval('J', -1);
|
||||||
const bool hasI = ix >= 0,
|
const bool hasI = ix >= 0,
|
||||||
hasJ = iy >= 0,
|
hasJ = iy >= 0,
|
||||||
|
@ -49,3 +60,5 @@ void gcode_M421() {
|
||||||
#endif
|
#endif
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
|
#endif // AUTO_BED_LEVELING_BILINEAR
|
|
@ -20,26 +20,30 @@
|
||||||
*
|
*
|
||||||
*/
|
*/
|
||||||
|
|
||||||
#include "../queue.h"
|
/**
|
||||||
|
* G29.cpp - Mesh Bed Leveling
|
||||||
|
*/
|
||||||
|
|
||||||
#include "../../libs/buzzer.h"
|
#include "../../../inc/MarlinConfig.h"
|
||||||
#include "../../lcd/ultralcd.h"
|
|
||||||
|
#if ENABLED(MESH_BED_LEVELING)
|
||||||
|
|
||||||
|
#include "../../../feature/bedlevel/bedlevel.h"
|
||||||
|
|
||||||
|
#include "../../gcode.h"
|
||||||
|
#include "../../queue.h"
|
||||||
|
|
||||||
|
#include "../../../libs/buzzer.h"
|
||||||
|
#include "../../../lcd/ultralcd.h"
|
||||||
|
#include "../../../module/motion.h"
|
||||||
|
#include "../../../module/stepper.h"
|
||||||
|
|
||||||
// Save 130 bytes with non-duplication of PSTR
|
// Save 130 bytes with non-duplication of PSTR
|
||||||
void echo_not_entered() { SERIAL_PROTOCOLLNPGM(" not entered."); }
|
void echo_not_entered() { SERIAL_PROTOCOLLNPGM(" not entered."); }
|
||||||
|
|
||||||
void mbl_mesh_report() {
|
|
||||||
SERIAL_PROTOCOLLNPGM("Num X,Y: " STRINGIFY(GRID_MAX_POINTS_X) "," STRINGIFY(GRID_MAX_POINTS_Y));
|
|
||||||
SERIAL_PROTOCOLPGM("Z offset: "); SERIAL_PROTOCOL_F(mbl.z_offset, 5);
|
|
||||||
SERIAL_PROTOCOLLNPGM("\nMeasured points:");
|
|
||||||
print_2d_array(GRID_MAX_POINTS_X, GRID_MAX_POINTS_Y, 5,
|
|
||||||
[](const uint8_t ix, const uint8_t iy) { return mbl.z_values[ix][iy]; }
|
|
||||||
);
|
|
||||||
}
|
|
||||||
|
|
||||||
void mesh_probing_done() {
|
void mesh_probing_done() {
|
||||||
mbl.set_has_mesh(true);
|
mbl.set_has_mesh(true);
|
||||||
home_all_axes();
|
gcode.home_all_axes();
|
||||||
set_bed_leveling_enabled(true);
|
set_bed_leveling_enabled(true);
|
||||||
#if ENABLED(MESH_G28_REST_ORIGIN)
|
#if ENABLED(MESH_G28_REST_ORIGIN)
|
||||||
current_position[Z_AXIS] = LOGICAL_Z_POSITION(Z_MIN_POS);
|
current_position[Z_AXIS] = LOGICAL_Z_POSITION(Z_MIN_POS);
|
||||||
|
@ -70,7 +74,7 @@ void mesh_probing_done() {
|
||||||
* v Y-axis 1-n
|
* v Y-axis 1-n
|
||||||
*
|
*
|
||||||
*/
|
*/
|
||||||
void gcode_G29() {
|
void GcodeSuite::G29() {
|
||||||
|
|
||||||
static int mbl_probe_index = -1;
|
static int mbl_probe_index = -1;
|
||||||
#if HAS_SOFTWARE_ENDSTOPS
|
#if HAS_SOFTWARE_ENDSTOPS
|
||||||
|
@ -200,3 +204,5 @@ void gcode_G29() {
|
||||||
|
|
||||||
report_current_position();
|
report_current_position();
|
||||||
}
|
}
|
||||||
|
|
||||||
|
#endif // MESH_BED_LEVELING
|
|
@ -20,6 +20,18 @@
|
||||||
*
|
*
|
||||||
*/
|
*/
|
||||||
|
|
||||||
|
/**
|
||||||
|
* M421.cpp - Mesh Bed Leveling
|
||||||
|
*/
|
||||||
|
|
||||||
|
#include "../../../inc/MarlinConfig.h"
|
||||||
|
|
||||||
|
#if ENABLED(MESH_BED_LEVELING)
|
||||||
|
|
||||||
|
#include "../../gcode.h"
|
||||||
|
#include "../../../module/motion.h"
|
||||||
|
#include "../../../feature/bedlevel/mbl/mesh_bed_leveling.h"
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* M421: Set a single Mesh Bed Leveling Z coordinate
|
* M421: Set a single Mesh Bed Leveling Z coordinate
|
||||||
*
|
*
|
||||||
|
@ -29,7 +41,7 @@
|
||||||
* M421 I<xindex> J<yindex> Z<linear>
|
* M421 I<xindex> J<yindex> Z<linear>
|
||||||
* M421 I<xindex> J<yindex> Q<offset>
|
* M421 I<xindex> J<yindex> Q<offset>
|
||||||
*/
|
*/
|
||||||
void gcode_M421() {
|
void GcodeSuite::M421() {
|
||||||
const bool hasX = parser.seen('X'), hasI = parser.seen('I');
|
const bool hasX = parser.seen('X'), hasI = parser.seen('I');
|
||||||
const int8_t ix = hasI ? parser.value_int() : hasX ? mbl.probe_index_x(RAW_X_POSITION(parser.value_linear_units())) : -1;
|
const int8_t ix = hasI ? parser.value_int() : hasX ? mbl.probe_index_x(RAW_X_POSITION(parser.value_linear_units())) : -1;
|
||||||
const bool hasY = parser.seen('Y'), hasJ = parser.seen('J');
|
const bool hasY = parser.seen('Y'), hasJ = parser.seen('J');
|
||||||
|
@ -47,3 +59,5 @@ void gcode_M421() {
|
||||||
else
|
else
|
||||||
mbl.set_z(ix, iy, parser.value_linear_units() + (hasQ ? mbl.z_values[ix][iy] : 0));
|
mbl.set_z(ix, iy, parser.value_linear_units() + (hasQ ? mbl.z_values[ix][iy] : 0));
|
||||||
}
|
}
|
||||||
|
|
||||||
|
#endif // MESH_BED_LEVELING
|
|
@ -20,8 +20,17 @@
|
||||||
*
|
*
|
||||||
*/
|
*/
|
||||||
|
|
||||||
void gcode_G26() {
|
/**
|
||||||
|
* G26.cpp - Unified Bed Leveling
|
||||||
|
*/
|
||||||
|
|
||||||
ubl.G26();
|
#include "../../../inc/MarlinConfig.h"
|
||||||
|
|
||||||
}
|
#if ENABLED(UBL_G26_MESH_VALIDATION)
|
||||||
|
|
||||||
|
#include "../../gcode.h"
|
||||||
|
#include "../../../feature/bedlevel/ubl/ubl.h"
|
||||||
|
|
||||||
|
void GcodeSuite::G26() { ubl.G26(); }
|
||||||
|
|
||||||
|
#endif // UBL_G26_MESH_VALIDATION
|
|
@ -20,8 +20,17 @@
|
||||||
*
|
*
|
||||||
*/
|
*/
|
||||||
|
|
||||||
void gcode_G29() {
|
/**
|
||||||
|
* G29.cpp - Unified Bed Leveling
|
||||||
|
*/
|
||||||
|
|
||||||
ubl.G29();
|
#include "../../../inc/MarlinConfig.h"
|
||||||
|
|
||||||
}
|
#if ENABLED(AUTO_BED_LEVELING_UBL)
|
||||||
|
|
||||||
|
#include "../../gcode.h"
|
||||||
|
#include "../../../feature/bedlevel/ubl/ubl.h"
|
||||||
|
|
||||||
|
void GcodeSuite::G29() { ubl.G29(); }
|
||||||
|
|
||||||
|
#endif // AUTO_BED_LEVELING_UBL
|
|
@ -20,6 +20,17 @@
|
||||||
*
|
*
|
||||||
*/
|
*/
|
||||||
|
|
||||||
|
/**
|
||||||
|
* unified.cpp - Unified Bed Leveling
|
||||||
|
*/
|
||||||
|
|
||||||
|
#include "../../../inc/MarlinConfig.h"
|
||||||
|
|
||||||
|
#if ENABLED(AUTO_BED_LEVELING_UBL)
|
||||||
|
|
||||||
|
#include "../../gcode.h"
|
||||||
|
#include "../../../feature/bedlevel/ubl/ubl.h"
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* M421: Set a single Mesh Bed Leveling Z coordinate
|
* M421: Set a single Mesh Bed Leveling Z coordinate
|
||||||
*
|
*
|
||||||
|
@ -29,7 +40,7 @@
|
||||||
* M421 C Z<linear>
|
* M421 C Z<linear>
|
||||||
* M421 C Q<offset>
|
* M421 C Q<offset>
|
||||||
*/
|
*/
|
||||||
void gcode_M421() {
|
void GcodeSuite::M421() {
|
||||||
int8_t ix = parser.intval('I', -1), iy = parser.intval('J', -1);
|
int8_t ix = parser.intval('I', -1), iy = parser.intval('J', -1);
|
||||||
const bool hasI = ix >= 0,
|
const bool hasI = ix >= 0,
|
||||||
hasJ = iy >= 0,
|
hasJ = iy >= 0,
|
||||||
|
@ -54,3 +65,5 @@ void gcode_M421() {
|
||||||
else
|
else
|
||||||
ubl.z_values[ix][iy] = parser.value_linear_units() + (hasQ ? ubl.z_values[ix][iy] : 0);
|
ubl.z_values[ix][iy] = parser.value_linear_units() + (hasQ ? ubl.z_values[ix][iy] : 0);
|
||||||
}
|
}
|
||||||
|
|
||||||
|
#endif // AUTO_BED_LEVELING_UBL
|
|
@ -20,8 +20,21 @@
|
||||||
*
|
*
|
||||||
*/
|
*/
|
||||||
|
|
||||||
void gcode_M49() {
|
/**
|
||||||
|
* M49.cpp - Unified Bed Leveling
|
||||||
|
*/
|
||||||
|
|
||||||
|
#include "../../../inc/MarlinConfig.h"
|
||||||
|
|
||||||
|
#if ENABLED(UBL_G26_MESH_VALIDATION)
|
||||||
|
|
||||||
|
#include "../../gcode.h"
|
||||||
|
#include "../../../feature/bedlevel/bedlevel.h"
|
||||||
|
|
||||||
|
void GcodeSuite::M49() {
|
||||||
ubl.g26_debug_flag ^= true;
|
ubl.g26_debug_flag ^= true;
|
||||||
SERIAL_PROTOCOLPGM("UBL Debug Flag turned ");
|
SERIAL_PROTOCOLPGM("UBL Debug Flag turned ");
|
||||||
serialprintPGM(ubl.g26_debug_flag ? PSTR("on.") : PSTR("off."));
|
serialprintPGM(ubl.g26_debug_flag ? PSTR("on.") : PSTR("off."));
|
||||||
}
|
}
|
||||||
|
|
||||||
|
#endif // UBL_G26_MESH_VALIDATION
|
|
@ -20,12 +20,23 @@
|
||||||
*
|
*
|
||||||
*/
|
*/
|
||||||
|
|
||||||
#include "common.h"
|
#include "../../inc/MarlinConfig.h"
|
||||||
|
|
||||||
|
#include "../gcode.h"
|
||||||
|
|
||||||
|
#include "../../module/stepper.h"
|
||||||
|
#include "../../module/endstops.h"
|
||||||
|
|
||||||
#if HOTENDS > 1
|
#if HOTENDS > 1
|
||||||
#include "../control/tool_change.h"
|
#include "../../module/tool_change.h"
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
#if HAS_LEVELING
|
||||||
|
#include "../../feature/bedlevel/bedlevel.h"
|
||||||
|
#endif
|
||||||
|
|
||||||
|
#include "../../lcd/ultralcd.h"
|
||||||
|
|
||||||
#if ENABLED(QUICK_HOME)
|
#if ENABLED(QUICK_HOME)
|
||||||
|
|
||||||
static void quick_home_xy() {
|
static void quick_home_xy() {
|
||||||
|
@ -126,11 +137,11 @@
|
||||||
* Z Home to the Z endstop
|
* Z Home to the Z endstop
|
||||||
*
|
*
|
||||||
*/
|
*/
|
||||||
void gcode_G28(const bool always_home_all) {
|
void GcodeSuite::G28(const bool always_home_all) {
|
||||||
|
|
||||||
#if ENABLED(DEBUG_LEVELING_FEATURE)
|
#if ENABLED(DEBUG_LEVELING_FEATURE)
|
||||||
if (DEBUGGING(LEVELING)) {
|
if (DEBUGGING(LEVELING)) {
|
||||||
SERIAL_ECHOLNPGM(">>> gcode_G28");
|
SERIAL_ECHOLNPGM(">>> G28");
|
||||||
log_machine_info();
|
log_machine_info();
|
||||||
}
|
}
|
||||||
#endif
|
#endif
|
||||||
|
@ -288,7 +299,7 @@ void gcode_G28(const bool always_home_all) {
|
||||||
|
|
||||||
SYNC_PLAN_POSITION_KINEMATIC();
|
SYNC_PLAN_POSITION_KINEMATIC();
|
||||||
|
|
||||||
#endif // !DELTA (gcode_G28)
|
#endif // !DELTA (G28)
|
||||||
|
|
||||||
endstops.not_homing();
|
endstops.not_homing();
|
||||||
|
|
||||||
|
@ -319,6 +330,6 @@ void gcode_G28(const bool always_home_all) {
|
||||||
report_current_position();
|
report_current_position();
|
||||||
|
|
||||||
#if ENABLED(DEBUG_LEVELING_FEATURE)
|
#if ENABLED(DEBUG_LEVELING_FEATURE)
|
||||||
if (DEBUGGING(LEVELING)) SERIAL_ECHOLNPGM("<<< gcode_G28");
|
if (DEBUGGING(LEVELING)) SERIAL_ECHOLNPGM("<<< G28");
|
||||||
#endif
|
#endif
|
||||||
}
|
}
|
|
@ -1,65 +0,0 @@
|
||||||
/**
|
|
||||||
* Marlin 3D Printer Firmware
|
|
||||||
* Copyright (C) 2016 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
|
|
||||||
*
|
|
||||||
* Based on Sprinter and grbl.
|
|
||||||
* Copyright (C) 2011 Camiel Gubbels / Erik van der Zalm
|
|
||||||
*
|
|
||||||
* This program is free software: you can redistribute it and/or modify
|
|
||||||
* it under the terms of the GNU General Public License as published by
|
|
||||||
* the Free Software Foundation, either version 3 of the License, or
|
|
||||||
* (at your option) any later version.
|
|
||||||
*
|
|
||||||
* This program is distributed in the hope that it will be useful,
|
|
||||||
* but WITHOUT ANY WARRANTY; without even the implied warranty of
|
|
||||||
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
|
|
||||||
* GNU General Public License for more details.
|
|
||||||
*
|
|
||||||
* You should have received a copy of the GNU General Public License
|
|
||||||
* along with this program. If not, see <http://www.gnu.org/licenses/>.
|
|
||||||
*
|
|
||||||
*/
|
|
||||||
|
|
||||||
#if ENABLED(MESH_BED_LEVELING) || ENABLED(PROBE_MANUALLY)
|
|
||||||
|
|
||||||
#if ENABLED(PROBE_MANUALLY) && ENABLED(LCD_BED_LEVELING)
|
|
||||||
extern bool lcd_wait_for_move;
|
|
||||||
#endif
|
|
||||||
|
|
||||||
inline void _manual_goto_xy(const float &x, const float &y) {
|
|
||||||
const float old_feedrate_mm_s = feedrate_mm_s;
|
|
||||||
#if MANUAL_PROBE_HEIGHT > 0
|
|
||||||
const float prev_z = current_position[Z_AXIS];
|
|
||||||
feedrate_mm_s = homing_feedrate(Z_AXIS);
|
|
||||||
current_position[Z_AXIS] = LOGICAL_Z_POSITION(MANUAL_PROBE_HEIGHT);
|
|
||||||
line_to_current_position();
|
|
||||||
#endif
|
|
||||||
|
|
||||||
feedrate_mm_s = MMM_TO_MMS(XY_PROBE_SPEED);
|
|
||||||
current_position[X_AXIS] = LOGICAL_X_POSITION(x);
|
|
||||||
current_position[Y_AXIS] = LOGICAL_Y_POSITION(y);
|
|
||||||
line_to_current_position();
|
|
||||||
|
|
||||||
#if MANUAL_PROBE_HEIGHT > 0
|
|
||||||
feedrate_mm_s = homing_feedrate(Z_AXIS);
|
|
||||||
current_position[Z_AXIS] = prev_z; // move back to the previous Z.
|
|
||||||
line_to_current_position();
|
|
||||||
#endif
|
|
||||||
|
|
||||||
feedrate_mm_s = old_feedrate_mm_s;
|
|
||||||
stepper.synchronize();
|
|
||||||
|
|
||||||
#if ENABLED(PROBE_MANUALLY) && ENABLED(LCD_BED_LEVELING)
|
|
||||||
lcd_wait_for_move = false;
|
|
||||||
#endif
|
|
||||||
}
|
|
||||||
|
|
||||||
#endif
|
|
||||||
|
|
||||||
#if ENABLED(MESH_BED_LEVELING)
|
|
||||||
#include "G29-mbl.h"
|
|
||||||
#elif ENABLED(AUTO_BED_LEVELING_UBL)
|
|
||||||
#include "G29-ubl.h"
|
|
||||||
#elif HAS_ABL
|
|
||||||
#include "G29-abl.h"
|
|
||||||
#endif
|
|
|
@ -20,10 +20,21 @@
|
||||||
*
|
*
|
||||||
*/
|
*/
|
||||||
|
|
||||||
#include "common.h"
|
#include "../../inc/MarlinConfig.h"
|
||||||
|
|
||||||
#if HOTENDS > 1
|
#if ENABLED(DELTA_AUTO_CALIBRATION)
|
||||||
#include "../control/tool_change.h"
|
|
||||||
|
#include "../gcode.h"
|
||||||
|
#include "../../module/delta.h"
|
||||||
|
#include "../../module/probe.h"
|
||||||
|
#include "../../module/motion.h"
|
||||||
|
#include "../../module/stepper.h"
|
||||||
|
#include "../../module/endstops.h"
|
||||||
|
#include "../../module/tool_change.h"
|
||||||
|
#include "../../lcd/ultralcd.h"
|
||||||
|
|
||||||
|
#if HAS_LEVELING
|
||||||
|
#include "../../feature/bedlevel/bedlevel.h"
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
/**
|
/**
|
||||||
|
@ -54,7 +65,7 @@
|
||||||
* E Engage the probe for each point
|
* E Engage the probe for each point
|
||||||
*/
|
*/
|
||||||
|
|
||||||
void print_signed_float(const char * const prefix, const float &f) {
|
static void print_signed_float(const char * const prefix, const float &f) {
|
||||||
SERIAL_PROTOCOLPGM(" ");
|
SERIAL_PROTOCOLPGM(" ");
|
||||||
serialprintPGM(prefix);
|
serialprintPGM(prefix);
|
||||||
SERIAL_PROTOCOLCHAR(':');
|
SERIAL_PROTOCOLCHAR(':');
|
||||||
|
@ -62,12 +73,12 @@ void print_signed_float(const char * const prefix, const float &f) {
|
||||||
SERIAL_PROTOCOL_F(f, 2);
|
SERIAL_PROTOCOL_F(f, 2);
|
||||||
}
|
}
|
||||||
|
|
||||||
inline void print_G33_settings(const bool end_stops, const bool tower_angles){ // TODO echo these to LCD ???
|
static void print_G33_settings(const bool end_stops, const bool tower_angles){ // TODO echo these to LCD ???
|
||||||
SERIAL_PROTOCOLPAIR(".Height:", DELTA_HEIGHT + home_offset[Z_AXIS]);
|
SERIAL_PROTOCOLPAIR(".Height:", DELTA_HEIGHT + home_offset[Z_AXIS]);
|
||||||
if (end_stops) {
|
if (end_stops) {
|
||||||
print_signed_float(PSTR(" Ex"), endstop_adj[A_AXIS]);
|
print_signed_float(PSTR(" Ex"), delta_endstop_adj[A_AXIS]);
|
||||||
print_signed_float(PSTR("Ey"), endstop_adj[B_AXIS]);
|
print_signed_float(PSTR("Ey"), delta_endstop_adj[B_AXIS]);
|
||||||
print_signed_float(PSTR("Ez"), endstop_adj[C_AXIS]);
|
print_signed_float(PSTR("Ez"), delta_endstop_adj[C_AXIS]);
|
||||||
SERIAL_PROTOCOLPAIR(" Radius:", delta_radius);
|
SERIAL_PROTOCOLPAIR(" Radius:", delta_radius);
|
||||||
}
|
}
|
||||||
SERIAL_EOL();
|
SERIAL_EOL();
|
||||||
|
@ -79,7 +90,7 @@ inline void print_G33_settings(const bool end_stops, const bool tower_angles){ /
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
void G33_cleanup(
|
static void G33_cleanup(
|
||||||
#if HOTENDS > 1
|
#if HOTENDS > 1
|
||||||
const uint8_t old_tool_index
|
const uint8_t old_tool_index
|
||||||
#endif
|
#endif
|
||||||
|
@ -94,7 +105,7 @@ void G33_cleanup(
|
||||||
#endif
|
#endif
|
||||||
}
|
}
|
||||||
|
|
||||||
void gcode_G33() {
|
void GcodeSuite::G33() {
|
||||||
|
|
||||||
const int8_t probe_points = parser.intval('P', DELTA_CALIBRATION_DEFAULT_POINTS);
|
const int8_t probe_points = parser.intval('P', DELTA_CALIBRATION_DEFAULT_POINTS);
|
||||||
if (!WITHIN(probe_points, 1, 7)) {
|
if (!WITHIN(probe_points, 1, 7)) {
|
||||||
|
@ -110,7 +121,7 @@ void gcode_G33() {
|
||||||
|
|
||||||
const float calibration_precision = parser.floatval('C');
|
const float calibration_precision = parser.floatval('C');
|
||||||
if (calibration_precision < 0) {
|
if (calibration_precision < 0) {
|
||||||
SERIAL_PROTOCOLLNPGM("?(C)alibration precision is implausible (>0).");
|
SERIAL_PROTOCOLLNPGM("?(C)alibration precision is implausible (>=0).");
|
||||||
return;
|
return;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
@ -121,7 +132,6 @@ void gcode_G33() {
|
||||||
}
|
}
|
||||||
|
|
||||||
const bool towers_set = parser.boolval('T', true),
|
const bool towers_set = parser.boolval('T', true),
|
||||||
stow_after_each = parser.boolval('E'),
|
|
||||||
_1p_calibration = probe_points == 1,
|
_1p_calibration = probe_points == 1,
|
||||||
_4p_calibration = probe_points == 2,
|
_4p_calibration = probe_points == 2,
|
||||||
_4p_towers_points = _4p_calibration && towers_set,
|
_4p_towers_points = _4p_calibration && towers_set,
|
||||||
|
@ -133,18 +143,24 @@ void gcode_G33() {
|
||||||
_7p_quadruple_circle = probe_points == 7,
|
_7p_quadruple_circle = probe_points == 7,
|
||||||
_7p_multi_circle = _7p_double_circle || _7p_triple_circle || _7p_quadruple_circle,
|
_7p_multi_circle = _7p_double_circle || _7p_triple_circle || _7p_quadruple_circle,
|
||||||
_7p_intermed_points = _7p_calibration && !_7p_half_circle;
|
_7p_intermed_points = _7p_calibration && !_7p_half_circle;
|
||||||
|
|
||||||
|
#if DISABLED(PROBE_MANUALLY)
|
||||||
|
const bool stow_after_each = parser.boolval('E');
|
||||||
|
const float dx = (X_PROBE_OFFSET_FROM_EXTRUDER),
|
||||||
|
dy = (Y_PROBE_OFFSET_FROM_EXTRUDER);
|
||||||
|
#endif
|
||||||
|
|
||||||
const static char save_message[] PROGMEM = "Save with M500 and/or copy to Configuration.h";
|
const static char save_message[] PROGMEM = "Save with M500 and/or copy to Configuration.h";
|
||||||
const float dx = (X_PROBE_OFFSET_FROM_EXTRUDER),
|
|
||||||
dy = (Y_PROBE_OFFSET_FROM_EXTRUDER);
|
|
||||||
int8_t iterations = 0;
|
int8_t iterations = 0;
|
||||||
float test_precision,
|
float test_precision,
|
||||||
zero_std_dev = (verbose_level ? 999.0 : 0.0), // 0.0 in dry-run mode : forced end
|
zero_std_dev = (verbose_level ? 999.0 : 0.0), // 0.0 in dry-run mode : forced end
|
||||||
zero_std_dev_old = zero_std_dev,
|
zero_std_dev_old = zero_std_dev,
|
||||||
zero_std_dev_min = zero_std_dev,
|
zero_std_dev_min = zero_std_dev,
|
||||||
e_old[XYZ] = {
|
e_old[XYZ] = {
|
||||||
endstop_adj[A_AXIS],
|
delta_endstop_adj[A_AXIS],
|
||||||
endstop_adj[B_AXIS],
|
delta_endstop_adj[B_AXIS],
|
||||||
endstop_adj[C_AXIS]
|
delta_endstop_adj[C_AXIS]
|
||||||
},
|
},
|
||||||
dr_old = delta_radius,
|
dr_old = delta_radius,
|
||||||
zh_old = home_offset[Z_AXIS],
|
zh_old = home_offset[Z_AXIS],
|
||||||
|
@ -167,6 +183,7 @@ void gcode_G33() {
|
||||||
SERIAL_PROTOCOLLNPGM("G33 Auto Calibrate");
|
SERIAL_PROTOCOLLNPGM("G33 Auto Calibrate");
|
||||||
|
|
||||||
stepper.synchronize();
|
stepper.synchronize();
|
||||||
|
|
||||||
#if HAS_LEVELING
|
#if HAS_LEVELING
|
||||||
reset_bed_level(); // After calibration bed-level data is no longer valid
|
reset_bed_level(); // After calibration bed-level data is no longer valid
|
||||||
#endif
|
#endif
|
||||||
|
@ -274,7 +291,7 @@ void gcode_G33() {
|
||||||
|
|
||||||
if ((zero_std_dev < test_precision && zero_std_dev > calibration_precision) || iterations <= force_iterations) {
|
if ((zero_std_dev < test_precision && zero_std_dev > calibration_precision) || iterations <= force_iterations) {
|
||||||
if (zero_std_dev < zero_std_dev_min) {
|
if (zero_std_dev < zero_std_dev_min) {
|
||||||
COPY(e_old, endstop_adj);
|
COPY(e_old, delta_endstop_adj);
|
||||||
dr_old = delta_radius;
|
dr_old = delta_radius;
|
||||||
zh_old = home_offset[Z_AXIS];
|
zh_old = home_offset[Z_AXIS];
|
||||||
alpha_old = delta_tower_angle_trim[A_AXIS];
|
alpha_old = delta_tower_angle_trim[A_AXIS];
|
||||||
|
@ -337,20 +354,20 @@ void gcode_G33() {
|
||||||
break;
|
break;
|
||||||
}
|
}
|
||||||
|
|
||||||
LOOP_XYZ(axis) endstop_adj[axis] += e_delta[axis];
|
LOOP_XYZ(axis) delta_endstop_adj[axis] += e_delta[axis];
|
||||||
delta_radius += r_delta;
|
delta_radius += r_delta;
|
||||||
delta_tower_angle_trim[A_AXIS] += t_alpha;
|
delta_tower_angle_trim[A_AXIS] += t_alpha;
|
||||||
delta_tower_angle_trim[B_AXIS] += t_beta;
|
delta_tower_angle_trim[B_AXIS] += t_beta;
|
||||||
|
|
||||||
// adjust delta_height and endstops by the max amount
|
// adjust delta_height and endstops by the max amount
|
||||||
const float z_temp = MAX3(endstop_adj[A_AXIS], endstop_adj[B_AXIS], endstop_adj[C_AXIS]);
|
const float z_temp = MAX3(delta_endstop_adj[A_AXIS], delta_endstop_adj[B_AXIS], delta_endstop_adj[C_AXIS]);
|
||||||
home_offset[Z_AXIS] -= z_temp;
|
home_offset[Z_AXIS] -= z_temp;
|
||||||
LOOP_XYZ(i) endstop_adj[i] -= z_temp;
|
LOOP_XYZ(i) delta_endstop_adj[i] -= z_temp;
|
||||||
|
|
||||||
recalc_delta_settings(delta_radius, delta_diagonal_rod);
|
recalc_delta_settings(delta_radius, delta_diagonal_rod);
|
||||||
}
|
}
|
||||||
else if (zero_std_dev >= test_precision) { // step one back
|
else if (zero_std_dev >= test_precision) { // step one back
|
||||||
COPY(endstop_adj, e_old);
|
COPY(delta_endstop_adj, e_old);
|
||||||
delta_radius = dr_old;
|
delta_radius = dr_old;
|
||||||
home_offset[Z_AXIS] = zh_old;
|
home_offset[Z_AXIS] = zh_old;
|
||||||
delta_tower_angle_trim[A_AXIS] = alpha_old;
|
delta_tower_angle_trim[A_AXIS] = alpha_old;
|
||||||
|
@ -449,3 +466,5 @@ void gcode_G33() {
|
||||||
|
|
||||||
G33_CLEANUP();
|
G33_CLEANUP();
|
||||||
}
|
}
|
||||||
|
|
||||||
|
#endif // DELTA_AUTO_CALIBRATION
|
|
@ -33,11 +33,11 @@
|
||||||
#endif
|
#endif
|
||||||
LOOP_XYZ(i) {
|
LOOP_XYZ(i) {
|
||||||
if (parser.seen(axis_codes[i])) {
|
if (parser.seen(axis_codes[i])) {
|
||||||
endstop_adj[i] = parser.value_linear_units();
|
delta_endstop_adj[i] = parser.value_linear_units();
|
||||||
#if ENABLED(DEBUG_LEVELING_FEATURE)
|
#if ENABLED(DEBUG_LEVELING_FEATURE)
|
||||||
if (DEBUGGING(LEVELING)) {
|
if (DEBUGGING(LEVELING)) {
|
||||||
SERIAL_ECHOPAIR("endstop_adj[", axis_codes[i]);
|
SERIAL_ECHOPAIR("delta_endstop_adj[", axis_codes[i]);
|
||||||
SERIAL_ECHOLNPAIR("] = ", endstop_adj[i]);
|
SERIAL_ECHOLNPAIR("] = ", delta_endstop_adj[i]);
|
||||||
}
|
}
|
||||||
#endif
|
#endif
|
||||||
}
|
}
|
||||||
|
@ -48,9 +48,9 @@
|
||||||
}
|
}
|
||||||
#endif
|
#endif
|
||||||
// normalize endstops so all are <=0; set the residue to delta height
|
// normalize endstops so all are <=0; set the residue to delta height
|
||||||
const float z_temp = MAX3(endstop_adj[A_AXIS], endstop_adj[B_AXIS], endstop_adj[C_AXIS]);
|
const float z_temp = MAX3(delta_endstop_adj[A_AXIS], delta_endstop_adj[B_AXIS], delta_endstop_adj[C_AXIS]);
|
||||||
home_offset[Z_AXIS] -= z_temp;
|
home_offset[Z_AXIS] -= z_temp;
|
||||||
LOOP_XYZ(i) endstop_adj[i] -= z_temp;
|
LOOP_XYZ(i) delta_endstop_adj[i] -= z_temp;
|
||||||
}
|
}
|
||||||
|
|
||||||
#elif ENABLED(Z_DUAL_ENDSTOPS) // !DELTA && ENABLED(Z_DUAL_ENDSTOPS)
|
#elif ENABLED(Z_DUAL_ENDSTOPS) // !DELTA && ENABLED(Z_DUAL_ENDSTOPS)
|
||||||
|
|
|
@ -1,81 +0,0 @@
|
||||||
/**
|
|
||||||
* Marlin 3D Printer Firmware
|
|
||||||
* Copyright (C) 2016 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
|
|
||||||
*
|
|
||||||
* Based on Sprinter and grbl.
|
|
||||||
* Copyright (C) 2011 Camiel Gubbels / Erik van der Zalm
|
|
||||||
*
|
|
||||||
* This program is free software: you can redistribute it and/or modify
|
|
||||||
* it under the terms of the GNU General Public License as published by
|
|
||||||
* the Free Software Foundation, either version 3 of the License, or
|
|
||||||
* (at your option) any later version.
|
|
||||||
*
|
|
||||||
* This program is distributed in the hope that it will be useful,
|
|
||||||
* but WITHOUT ANY WARRANTY; without even the implied warranty of
|
|
||||||
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
|
|
||||||
* GNU General Public License for more details.
|
|
||||||
*
|
|
||||||
* You should have received a copy of the GNU General Public License
|
|
||||||
* along with this program. If not, see <http://www.gnu.org/licenses/>.
|
|
||||||
*
|
|
||||||
*/
|
|
||||||
|
|
||||||
#ifndef CALIBRATE_COMMON_H
|
|
||||||
#define CALIBRATE_COMMON_H
|
|
||||||
|
|
||||||
#if ENABLED(DELTA)
|
|
||||||
|
|
||||||
/**
|
|
||||||
* A delta can only safely home all axes at the same time
|
|
||||||
* This is like quick_home_xy() but for 3 towers.
|
|
||||||
*/
|
|
||||||
inline bool home_delta() {
|
|
||||||
#if ENABLED(DEBUG_LEVELING_FEATURE)
|
|
||||||
if (DEBUGGING(LEVELING)) DEBUG_POS(">>> home_delta", current_position);
|
|
||||||
#endif
|
|
||||||
// Init the current position of all carriages to 0,0,0
|
|
||||||
ZERO(current_position);
|
|
||||||
sync_plan_position();
|
|
||||||
|
|
||||||
// Move all carriages together linearly until an endstop is hit.
|
|
||||||
current_position[X_AXIS] = current_position[Y_AXIS] = current_position[Z_AXIS] = (DELTA_HEIGHT + home_offset[Z_AXIS] + 10);
|
|
||||||
feedrate_mm_s = homing_feedrate(X_AXIS);
|
|
||||||
line_to_current_position();
|
|
||||||
stepper.synchronize();
|
|
||||||
|
|
||||||
// If an endstop was not hit, then damage can occur if homing is continued.
|
|
||||||
// This can occur if the delta height (DELTA_HEIGHT + home_offset[Z_AXIS]) is
|
|
||||||
// not set correctly.
|
|
||||||
if (!(Endstops::endstop_hit_bits & (_BV(X_MAX) | _BV(Y_MAX) | _BV(Z_MAX)))) {
|
|
||||||
LCD_MESSAGEPGM(MSG_ERR_HOMING_FAILED);
|
|
||||||
SERIAL_ERROR_START();
|
|
||||||
SERIAL_ERRORLNPGM(MSG_ERR_HOMING_FAILED);
|
|
||||||
return false;
|
|
||||||
}
|
|
||||||
|
|
||||||
endstops.hit_on_purpose(); // clear endstop hit flags
|
|
||||||
|
|
||||||
// At least one carriage has reached the top.
|
|
||||||
// Now re-home each carriage separately.
|
|
||||||
HOMEAXIS(A);
|
|
||||||
HOMEAXIS(B);
|
|
||||||
HOMEAXIS(C);
|
|
||||||
|
|
||||||
// Set all carriages to their home positions
|
|
||||||
// Do this here all at once for Delta, because
|
|
||||||
// XYZ isn't ABC. Applying this per-tower would
|
|
||||||
// give the impression that they are the same.
|
|
||||||
LOOP_XYZ(i) set_axis_is_at_home((AxisEnum)i);
|
|
||||||
|
|
||||||
SYNC_PLAN_POSITION_KINEMATIC();
|
|
||||||
|
|
||||||
#if ENABLED(DEBUG_LEVELING_FEATURE)
|
|
||||||
if (DEBUGGING(LEVELING)) DEBUG_POS("<<< home_delta", current_position);
|
|
||||||
#endif
|
|
||||||
|
|
||||||
return true;
|
|
||||||
}
|
|
||||||
|
|
||||||
#endif // DELTA
|
|
||||||
|
|
||||||
#endif // CALIBRATE_COMMON_H
|
|
|
@ -47,7 +47,7 @@ void gcode_M18_M84() {
|
||||||
}
|
}
|
||||||
|
|
||||||
#if ENABLED(AUTO_BED_LEVELING_UBL) && ENABLED(ULTRA_LCD) // Only needed with an LCD
|
#if ENABLED(AUTO_BED_LEVELING_UBL) && ENABLED(ULTRA_LCD) // Only needed with an LCD
|
||||||
ubl_lcd_map_control = defer_return_to_status = false;
|
ubl.lcd_map_control = defer_return_to_status = false;
|
||||||
#endif
|
#endif
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
|
@ -115,14 +115,10 @@ extern void gcode_G18();
|
||||||
extern void gcode_G19();
|
extern void gcode_G19();
|
||||||
extern void gcode_G20();
|
extern void gcode_G20();
|
||||||
extern void gcode_G21();
|
extern void gcode_G21();
|
||||||
extern void gcode_G26();
|
|
||||||
extern void gcode_G27();
|
extern void gcode_G27();
|
||||||
extern void gcode_G28(const bool always_home_all);
|
|
||||||
extern void gcode_G29();
|
|
||||||
extern void gcode_G30();
|
extern void gcode_G30();
|
||||||
extern void gcode_G31();
|
extern void gcode_G31();
|
||||||
extern void gcode_G32();
|
extern void gcode_G32();
|
||||||
extern void gcode_G33();
|
|
||||||
extern void gcode_G38(bool is_38_2);
|
extern void gcode_G38(bool is_38_2);
|
||||||
extern void gcode_G42();
|
extern void gcode_G42();
|
||||||
extern void gcode_G92();
|
extern void gcode_G92();
|
||||||
|
@ -149,7 +145,6 @@ extern void gcode_M34();
|
||||||
extern void gcode_M42();
|
extern void gcode_M42();
|
||||||
extern void gcode_M43();
|
extern void gcode_M43();
|
||||||
extern void gcode_M48();
|
extern void gcode_M48();
|
||||||
extern void gcode_M49();
|
|
||||||
extern void gcode_M75();
|
extern void gcode_M75();
|
||||||
extern void gcode_M76();
|
extern void gcode_M76();
|
||||||
extern void gcode_M77();
|
extern void gcode_M77();
|
||||||
|
@ -225,8 +220,6 @@ extern void gcode_M405();
|
||||||
extern void gcode_M406();
|
extern void gcode_M406();
|
||||||
extern void gcode_M407();
|
extern void gcode_M407();
|
||||||
extern void gcode_M410();
|
extern void gcode_M410();
|
||||||
extern void gcode_M420();
|
|
||||||
extern void gcode_M421();
|
|
||||||
extern void gcode_M428();
|
extern void gcode_M428();
|
||||||
extern void gcode_M500();
|
extern void gcode_M500();
|
||||||
extern void gcode_M501();
|
extern void gcode_M501();
|
||||||
|
@ -238,7 +231,6 @@ extern void gcode_M605();
|
||||||
extern void gcode_M665();
|
extern void gcode_M665();
|
||||||
extern void gcode_M666();
|
extern void gcode_M666();
|
||||||
extern void gcode_M702();
|
extern void gcode_M702();
|
||||||
extern void gcode_M851();
|
|
||||||
extern void gcode_M900();
|
extern void gcode_M900();
|
||||||
extern void gcode_M906();
|
extern void gcode_M906();
|
||||||
extern void gcode_M911();
|
extern void gcode_M911();
|
||||||
|
@ -348,9 +340,9 @@ void GcodeSuite::process_next_command() {
|
||||||
break;
|
break;
|
||||||
#endif // INCH_MODE_SUPPORT
|
#endif // INCH_MODE_SUPPORT
|
||||||
|
|
||||||
#if ENABLED(AUTO_BED_LEVELING_UBL) && ENABLED(UBL_G26_MESH_VALIDATION)
|
#if ENABLED(UBL_G26_MESH_VALIDATION)
|
||||||
case 26: // G26: Mesh Validation Pattern generation
|
case 26: // G26: Mesh Validation Pattern generation
|
||||||
gcode_G26();
|
G26();
|
||||||
break;
|
break;
|
||||||
#endif // AUTO_BED_LEVELING_UBL
|
#endif // AUTO_BED_LEVELING_UBL
|
||||||
|
|
||||||
|
@ -361,13 +353,13 @@ void GcodeSuite::process_next_command() {
|
||||||
#endif // NOZZLE_PARK_FEATURE
|
#endif // NOZZLE_PARK_FEATURE
|
||||||
|
|
||||||
case 28: // G28: Home all axes, one at a time
|
case 28: // G28: Home all axes, one at a time
|
||||||
gcode_G28(false);
|
G28(false);
|
||||||
break;
|
break;
|
||||||
|
|
||||||
#if HAS_LEVELING
|
#if HAS_LEVELING
|
||||||
case 29: // G29 Detailed Z probe, probes the bed at 3 or more points,
|
case 29: // G29 Detailed Z probe, probes the bed at 3 or more points,
|
||||||
// or provides access to the UBL System if enabled.
|
// or provides access to the UBL System if enabled.
|
||||||
gcode_G29();
|
G29();
|
||||||
break;
|
break;
|
||||||
#endif // HAS_LEVELING
|
#endif // HAS_LEVELING
|
||||||
|
|
||||||
|
@ -391,17 +383,11 @@ void GcodeSuite::process_next_command() {
|
||||||
|
|
||||||
#endif // HAS_BED_PROBE
|
#endif // HAS_BED_PROBE
|
||||||
|
|
||||||
#if PROBE_SELECTED
|
#if ENABLED(DELTA_AUTO_CALIBRATION)
|
||||||
|
case 33: // G33: Delta Auto-Calibration
|
||||||
#if ENABLED(DELTA_AUTO_CALIBRATION)
|
G33();
|
||||||
|
break;
|
||||||
case 33: // G33: Delta Auto-Calibration
|
#endif // DELTA_AUTO_CALIBRATION
|
||||||
gcode_G33();
|
|
||||||
break;
|
|
||||||
|
|
||||||
#endif // DELTA_AUTO_CALIBRATION
|
|
||||||
|
|
||||||
#endif // PROBE_SELECTED
|
|
||||||
|
|
||||||
#if ENABLED(G38_PROBE_TARGET)
|
#if ENABLED(G38_PROBE_TARGET)
|
||||||
case 38: // G38.2 & G38.3
|
case 38: // G38.2 & G38.3
|
||||||
|
@ -516,11 +502,9 @@ void GcodeSuite::process_next_command() {
|
||||||
break;
|
break;
|
||||||
#endif // Z_MIN_PROBE_REPEATABILITY_TEST
|
#endif // Z_MIN_PROBE_REPEATABILITY_TEST
|
||||||
|
|
||||||
#if ENABLED(AUTO_BED_LEVELING_UBL) && ENABLED(UBL_G26_MESH_VALIDATION)
|
#if ENABLED(UBL_G26_MESH_VALIDATION)
|
||||||
case 49: // M49: Turn on or off G26 debug flag for verbose output
|
case 49: M49(); break; // M49: Turn on or off G26 debug flag for verbose output
|
||||||
gcode_M49();
|
#endif
|
||||||
break;
|
|
||||||
#endif // AUTO_BED_LEVELING_UBL && UBL_G26_MESH_VALIDATION
|
|
||||||
|
|
||||||
case 75: // M75: Start print timer
|
case 75: // M75: Start print timer
|
||||||
gcode_M75(); break;
|
gcode_M75(); break;
|
||||||
|
@ -901,13 +885,13 @@ void GcodeSuite::process_next_command() {
|
||||||
|
|
||||||
#if HAS_LEVELING
|
#if HAS_LEVELING
|
||||||
case 420: // M420: Enable/Disable Bed Leveling
|
case 420: // M420: Enable/Disable Bed Leveling
|
||||||
gcode_M420();
|
M420();
|
||||||
break;
|
break;
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#if ENABLED(MESH_BED_LEVELING) || ENABLED(AUTO_BED_LEVELING_UBL) || ENABLED(AUTO_BED_LEVELING_BILINEAR)
|
#if HAS_MESH
|
||||||
case 421: // M421: Set a Mesh Bed Leveling Z coordinate
|
case 421: // M421: Set a Mesh Bed Leveling Z coordinate
|
||||||
gcode_M421();
|
M421();
|
||||||
break;
|
break;
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
@ -941,7 +925,7 @@ void GcodeSuite::process_next_command() {
|
||||||
|
|
||||||
#if HAS_BED_PROBE
|
#if HAS_BED_PROBE
|
||||||
case 851: // M851: Set Z Probe Z Offset
|
case 851: // M851: Set Z Probe Z Offset
|
||||||
gcode_M851();
|
M851();
|
||||||
break;
|
break;
|
||||||
#endif // HAS_BED_PROBE
|
#endif // HAS_BED_PROBE
|
||||||
|
|
||||||
|
|
|
@ -20,43 +20,15 @@
|
||||||
*
|
*
|
||||||
*/
|
*/
|
||||||
|
|
||||||
void refresh_zprobe_zoffset(const bool no_babystep/*=false*/) {
|
#include "../../inc/MarlinConfig.h"
|
||||||
static float last_zoffset = NAN;
|
|
||||||
|
|
||||||
if (!isnan(last_zoffset)) {
|
#if HAS_BED_PROBE
|
||||||
|
|
||||||
#if ENABLED(AUTO_BED_LEVELING_BILINEAR) || ENABLED(BABYSTEP_ZPROBE_OFFSET) || ENABLED(DELTA)
|
#include "../gcode.h"
|
||||||
const float diff = zprobe_zoffset - last_zoffset;
|
#include "../../feature/bedlevel/bedlevel.h"
|
||||||
#endif
|
#include "../../module/probe.h"
|
||||||
|
|
||||||
#if ENABLED(AUTO_BED_LEVELING_BILINEAR)
|
void GcodeSuite::M851() {
|
||||||
// Correct bilinear grid for new probe offset
|
|
||||||
if (diff) {
|
|
||||||
for (uint8_t x = 0; x < GRID_MAX_POINTS_X; x++)
|
|
||||||
for (uint8_t y = 0; y < GRID_MAX_POINTS_Y; y++)
|
|
||||||
z_values[x][y] -= diff;
|
|
||||||
}
|
|
||||||
#if ENABLED(ABL_BILINEAR_SUBDIVISION)
|
|
||||||
bed_level_virt_interpolate();
|
|
||||||
#endif
|
|
||||||
#endif
|
|
||||||
|
|
||||||
#if ENABLED(BABYSTEP_ZPROBE_OFFSET)
|
|
||||||
if (!no_babystep && leveling_is_active())
|
|
||||||
thermalManager.babystep_axis(Z_AXIS, -LROUND(diff * planner.axis_steps_per_mm[Z_AXIS]));
|
|
||||||
#else
|
|
||||||
UNUSED(no_babystep);
|
|
||||||
#endif
|
|
||||||
|
|
||||||
#if ENABLED(DELTA) // correct the delta_height
|
|
||||||
home_offset[Z_AXIS] -= diff;
|
|
||||||
#endif
|
|
||||||
}
|
|
||||||
|
|
||||||
last_zoffset = zprobe_zoffset;
|
|
||||||
}
|
|
||||||
|
|
||||||
void gcode_M851() {
|
|
||||||
SERIAL_ECHO_START();
|
SERIAL_ECHO_START();
|
||||||
SERIAL_ECHOPGM(MSG_ZPROBE_ZOFFSET " ");
|
SERIAL_ECHOPGM(MSG_ZPROBE_ZOFFSET " ");
|
||||||
if (parser.seen('Z')) {
|
if (parser.seen('Z')) {
|
||||||
|
@ -74,3 +46,5 @@ void gcode_M851() {
|
||||||
|
|
||||||
SERIAL_EOL();
|
SERIAL_EOL();
|
||||||
}
|
}
|
||||||
|
|
||||||
|
#endif // HAS_BED_PROBE
|
|
@ -31,6 +31,7 @@
|
||||||
#include "../module/planner.h"
|
#include "../module/planner.h"
|
||||||
#include "../module/stepper.h"
|
#include "../module/stepper.h"
|
||||||
#include "../module/motion.h"
|
#include "../module/motion.h"
|
||||||
|
#include "../module/probe.h"
|
||||||
#include "../gcode/gcode.h"
|
#include "../gcode/gcode.h"
|
||||||
#include "../gcode/queue.h"
|
#include "../gcode/queue.h"
|
||||||
#include "../module/configuration_store.h"
|
#include "../module/configuration_store.h"
|
||||||
|
@ -173,7 +174,7 @@ uint16_t max_display_update_time = 0;
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#if ENABLED(MESH_BED_LEVELING) && ENABLED(LCD_BED_LEVELING)
|
#if ENABLED(MESH_BED_LEVELING) && ENABLED(LCD_BED_LEVELING)
|
||||||
#include "../feature/mbl/mesh_bed_leveling.h"
|
#include "../feature/bedlevel/mbl/mesh_bed_leveling.h"
|
||||||
extern void mesh_probing_done();
|
extern void mesh_probing_done();
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
@ -1021,7 +1022,7 @@ void kill_screen(const char* lcd_msg) {
|
||||||
const float new_zoffset = zprobe_zoffset + planner.steps_to_mm[Z_AXIS] * babystep_increment;
|
const float new_zoffset = zprobe_zoffset + planner.steps_to_mm[Z_AXIS] * babystep_increment;
|
||||||
if (WITHIN(new_zoffset, Z_PROBE_OFFSET_RANGE_MIN, Z_PROBE_OFFSET_RANGE_MAX)) {
|
if (WITHIN(new_zoffset, Z_PROBE_OFFSET_RANGE_MIN, Z_PROBE_OFFSET_RANGE_MAX)) {
|
||||||
|
|
||||||
if (planner.abl_enabled)
|
if (leveling_is_active())
|
||||||
thermalManager.babystep_axis(Z_AXIS, babystep_increment);
|
thermalManager.babystep_axis(Z_AXIS, babystep_increment);
|
||||||
|
|
||||||
zprobe_zoffset = new_zoffset;
|
zprobe_zoffset = new_zoffset;
|
||||||
|
@ -2635,9 +2636,9 @@ void kill_screen(const char* lcd_msg) {
|
||||||
MENU_ITEM_EDIT(float52, MSG_DELTA_DIAG_ROG, &delta_diagonal_rod, DELTA_DIAGONAL_ROD - 5.0, DELTA_DIAGONAL_ROD + 5.0);
|
MENU_ITEM_EDIT(float52, MSG_DELTA_DIAG_ROG, &delta_diagonal_rod, DELTA_DIAGONAL_ROD - 5.0, DELTA_DIAGONAL_ROD + 5.0);
|
||||||
_delta_height = DELTA_HEIGHT + home_offset[Z_AXIS];
|
_delta_height = DELTA_HEIGHT + home_offset[Z_AXIS];
|
||||||
MENU_MULTIPLIER_ITEM_EDIT_CALLBACK(float52, MSG_DELTA_HEIGHT, &_delta_height, _delta_height - 10.0, _delta_height + 10.0, _lcd_set_delta_height);
|
MENU_MULTIPLIER_ITEM_EDIT_CALLBACK(float52, MSG_DELTA_HEIGHT, &_delta_height, _delta_height - 10.0, _delta_height + 10.0, _lcd_set_delta_height);
|
||||||
MENU_ITEM_EDIT(float43, "Ex", &endstop_adj[A_AXIS], -5.0, 5.0);
|
MENU_ITEM_EDIT(float43, "Ex", &delta_endstop_adj[A_AXIS], -5.0, 5.0);
|
||||||
MENU_ITEM_EDIT(float43, "Ey", &endstop_adj[B_AXIS], -5.0, 5.0);
|
MENU_ITEM_EDIT(float43, "Ey", &delta_endstop_adj[B_AXIS], -5.0, 5.0);
|
||||||
MENU_ITEM_EDIT(float43, "Ez", &endstop_adj[C_AXIS], -5.0, 5.0);
|
MENU_ITEM_EDIT(float43, "Ez", &delta_endstop_adj[C_AXIS], -5.0, 5.0);
|
||||||
MENU_ITEM_EDIT(float52, MSG_DELTA_RADIUS, &delta_radius, DELTA_RADIUS - 5.0, DELTA_RADIUS + 5.0);
|
MENU_ITEM_EDIT(float52, MSG_DELTA_RADIUS, &delta_radius, DELTA_RADIUS - 5.0, DELTA_RADIUS + 5.0);
|
||||||
MENU_ITEM_EDIT(float43, "Tx", &delta_tower_angle_trim[A_AXIS], -5.0, 5.0);
|
MENU_ITEM_EDIT(float43, "Tx", &delta_tower_angle_trim[A_AXIS], -5.0, 5.0);
|
||||||
MENU_ITEM_EDIT(float43, "Ty", &delta_tower_angle_trim[B_AXIS], -5.0, 5.0);
|
MENU_ITEM_EDIT(float43, "Ty", &delta_tower_angle_trim[B_AXIS], -5.0, 5.0);
|
||||||
|
|
|
@ -52,7 +52,7 @@
|
||||||
#include <U8glib.h>
|
#include <U8glib.h>
|
||||||
|
|
||||||
#if ENABLED(AUTO_BED_LEVELING_UBL)
|
#if ENABLED(AUTO_BED_LEVELING_UBL)
|
||||||
#include "../feature/ubl/ubl.h"
|
#include "../feature/bedlevel/ubl/ubl.h"
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#if ENABLED(SHOW_BOOTSCREEN) && ENABLED(SHOW_CUSTOM_BOOTSCREEN)
|
#if ENABLED(SHOW_BOOTSCREEN) && ENABLED(SHOW_CUSTOM_BOOTSCREEN)
|
||||||
|
|
|
@ -35,7 +35,7 @@
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#if ENABLED(AUTO_BED_LEVELING_UBL)
|
#if ENABLED(AUTO_BED_LEVELING_UBL)
|
||||||
#include "../feature/ubl/ubl.h"
|
#include "../feature/bedlevel/ubl/ubl.h"
|
||||||
|
|
||||||
#if ENABLED(ULTIPANEL)
|
#if ENABLED(ULTIPANEL)
|
||||||
#define ULTRA_X_PIXELS_PER_CHAR 5
|
#define ULTRA_X_PIXELS_PER_CHAR 5
|
||||||
|
|
|
@ -93,7 +93,7 @@
|
||||||
* 329 G29 S ubl.state.storage_slot (int8_t)
|
* 329 G29 S ubl.state.storage_slot (int8_t)
|
||||||
*
|
*
|
||||||
* DELTA: 48 bytes
|
* DELTA: 48 bytes
|
||||||
* 348 M666 XYZ endstop_adj (float x3)
|
* 348 M666 XYZ delta_endstop_adj (float x3)
|
||||||
* 360 M665 R delta_radius (float)
|
* 360 M665 R delta_radius (float)
|
||||||
* 364 M665 L delta_diagonal_rod (float)
|
* 364 M665 L delta_diagonal_rod (float)
|
||||||
* 368 M665 S delta_segments_per_second (float)
|
* 368 M665 S delta_segments_per_second (float)
|
||||||
|
@ -187,6 +187,10 @@ MarlinSettings settings;
|
||||||
|
|
||||||
#include "../gcode/parser.h"
|
#include "../gcode/parser.h"
|
||||||
|
|
||||||
|
#if HAS_LEVELING
|
||||||
|
#include "../feature/bedlevel/bedlevel.h"
|
||||||
|
#endif
|
||||||
|
|
||||||
#if HAS_BED_PROBE
|
#if HAS_BED_PROBE
|
||||||
#include "../module/probe.h"
|
#include "../module/probe.h"
|
||||||
#endif
|
#endif
|
||||||
|
@ -199,14 +203,6 @@ MarlinSettings settings;
|
||||||
#include "../feature/fwretract.h"
|
#include "../feature/fwretract.h"
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#if ENABLED(AUTO_BED_LEVELING_BILINEAR)
|
|
||||||
extern void refresh_bed_level();
|
|
||||||
#endif
|
|
||||||
|
|
||||||
#if ENABLED(FWRETRACT)
|
|
||||||
#include "../gcode/feature/fwretract/fwretract.h"
|
|
||||||
#endif
|
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* Post-process after Retrieve or Reset
|
* Post-process after Retrieve or Reset
|
||||||
*/
|
*/
|
||||||
|
@ -421,7 +417,7 @@ void MarlinSettings::postprocess() {
|
||||||
|
|
||||||
// 9 floats for DELTA / Z_DUAL_ENDSTOPS
|
// 9 floats for DELTA / Z_DUAL_ENDSTOPS
|
||||||
#if ENABLED(DELTA)
|
#if ENABLED(DELTA)
|
||||||
EEPROM_WRITE(endstop_adj); // 3 floats
|
EEPROM_WRITE(delta_endstop_adj); // 3 floats
|
||||||
EEPROM_WRITE(delta_radius); // 1 float
|
EEPROM_WRITE(delta_radius); // 1 float
|
||||||
EEPROM_WRITE(delta_diagonal_rod); // 1 float
|
EEPROM_WRITE(delta_diagonal_rod); // 1 float
|
||||||
EEPROM_WRITE(delta_segments_per_second); // 1 float
|
EEPROM_WRITE(delta_segments_per_second); // 1 float
|
||||||
|
@ -806,7 +802,7 @@ void MarlinSettings::postprocess() {
|
||||||
#endif // AUTO_BED_LEVELING_UBL
|
#endif // AUTO_BED_LEVELING_UBL
|
||||||
|
|
||||||
#if ENABLED(DELTA)
|
#if ENABLED(DELTA)
|
||||||
EEPROM_READ(endstop_adj); // 3 floats
|
EEPROM_READ(delta_endstop_adj); // 3 floats
|
||||||
EEPROM_READ(delta_radius); // 1 float
|
EEPROM_READ(delta_radius); // 1 float
|
||||||
EEPROM_READ(delta_diagonal_rod); // 1 float
|
EEPROM_READ(delta_diagonal_rod); // 1 float
|
||||||
EEPROM_READ(delta_segments_per_second); // 1 float
|
EEPROM_READ(delta_segments_per_second); // 1 float
|
||||||
|
@ -1196,7 +1192,7 @@ void MarlinSettings::reset() {
|
||||||
#if ENABLED(DELTA)
|
#if ENABLED(DELTA)
|
||||||
const float adj[ABC] = DELTA_ENDSTOP_ADJ,
|
const float adj[ABC] = DELTA_ENDSTOP_ADJ,
|
||||||
dta[ABC] = DELTA_TOWER_ANGLE_TRIM;
|
dta[ABC] = DELTA_TOWER_ANGLE_TRIM;
|
||||||
COPY(endstop_adj, adj);
|
COPY(delta_endstop_adj, adj);
|
||||||
delta_radius = DELTA_RADIUS;
|
delta_radius = DELTA_RADIUS;
|
||||||
delta_diagonal_rod = DELTA_DIAGONAL_ROD;
|
delta_diagonal_rod = DELTA_DIAGONAL_ROD;
|
||||||
delta_segments_per_second = DELTA_SEGMENTS_PER_SECOND;
|
delta_segments_per_second = DELTA_SEGMENTS_PER_SECOND;
|
||||||
|
@ -1602,9 +1598,9 @@ void MarlinSettings::reset() {
|
||||||
SERIAL_ECHOLNPGM("Endstop adjustment:");
|
SERIAL_ECHOLNPGM("Endstop adjustment:");
|
||||||
}
|
}
|
||||||
CONFIG_ECHO_START;
|
CONFIG_ECHO_START;
|
||||||
SERIAL_ECHOPAIR(" M666 X", LINEAR_UNIT(endstop_adj[X_AXIS]));
|
SERIAL_ECHOPAIR(" M666 X", LINEAR_UNIT(delta_endstop_adj[X_AXIS]));
|
||||||
SERIAL_ECHOPAIR(" Y", LINEAR_UNIT(endstop_adj[Y_AXIS]));
|
SERIAL_ECHOPAIR(" Y", LINEAR_UNIT(delta_endstop_adj[Y_AXIS]));
|
||||||
SERIAL_ECHOLNPAIR(" Z", LINEAR_UNIT(endstop_adj[Z_AXIS]));
|
SERIAL_ECHOLNPAIR(" Z", LINEAR_UNIT(delta_endstop_adj[Z_AXIS]));
|
||||||
if (!forReplay) {
|
if (!forReplay) {
|
||||||
CONFIG_ECHO_START;
|
CONFIG_ECHO_START;
|
||||||
SERIAL_ECHOLNPGM("Delta settings: L<diagonal_rod> R<radius> H<height> S<segments_per_s> B<calibration radius> XYZ<tower angle corrections>");
|
SERIAL_ECHOLNPGM("Delta settings: L<diagonal_rod> R<radius> H<height> S<segments_per_s> B<calibration radius> XYZ<tower angle corrections>");
|
||||||
|
|
269
Marlin/src/module/delta.cpp
Normal file
269
Marlin/src/module/delta.cpp
Normal file
|
@ -0,0 +1,269 @@
|
||||||
|
/**
|
||||||
|
* Marlin 3D Printer Firmware
|
||||||
|
* Copyright (C) 2016 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
|
||||||
|
*
|
||||||
|
* Based on Sprinter and grbl.
|
||||||
|
* Copyright (C) 2011 Camiel Gubbels / Erik van der Zalm
|
||||||
|
*
|
||||||
|
* This program is free software: you can redistribute it and/or modify
|
||||||
|
* it under the terms of the GNU General Public License as published by
|
||||||
|
* the Free Software Foundation, either version 3 of the License, or
|
||||||
|
* (at your option) any later version.
|
||||||
|
*
|
||||||
|
* This program is distributed in the hope that it will be useful,
|
||||||
|
* but WITHOUT ANY WARRANTY; without even the implied warranty of
|
||||||
|
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
|
||||||
|
* GNU General Public License for more details.
|
||||||
|
*
|
||||||
|
* You should have received a copy of the GNU General Public License
|
||||||
|
* along with this program. If not, see <http://www.gnu.org/licenses/>.
|
||||||
|
*
|
||||||
|
*/
|
||||||
|
|
||||||
|
/**
|
||||||
|
* delta.cpp
|
||||||
|
*/
|
||||||
|
|
||||||
|
#include "../inc/MarlinConfig.h"
|
||||||
|
|
||||||
|
#if ENABLED(DELTA)
|
||||||
|
|
||||||
|
#include "delta.h"
|
||||||
|
#include "motion.h"
|
||||||
|
|
||||||
|
// For homing:
|
||||||
|
#include "stepper.h"
|
||||||
|
#include "endstops.h"
|
||||||
|
#include "../lcd/ultralcd.h"
|
||||||
|
#include "../Marlin.h"
|
||||||
|
|
||||||
|
// Initialized by settings.load()
|
||||||
|
float delta_endstop_adj[ABC] = { 0 },
|
||||||
|
delta_radius,
|
||||||
|
delta_diagonal_rod,
|
||||||
|
delta_segments_per_second,
|
||||||
|
delta_calibration_radius,
|
||||||
|
delta_tower_angle_trim[2];
|
||||||
|
|
||||||
|
float delta_tower[ABC][2],
|
||||||
|
delta_diagonal_rod_2_tower[ABC],
|
||||||
|
delta_clip_start_height = Z_MAX_POS;
|
||||||
|
|
||||||
|
float delta_safe_distance_from_top();
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Recalculate factors used for delta kinematics whenever
|
||||||
|
* settings have been changed (e.g., by M665).
|
||||||
|
*/
|
||||||
|
void recalc_delta_settings(float radius, float diagonal_rod) {
|
||||||
|
const float trt[ABC] = DELTA_RADIUS_TRIM_TOWER,
|
||||||
|
drt[ABC] = DELTA_DIAGONAL_ROD_TRIM_TOWER;
|
||||||
|
delta_tower[A_AXIS][X_AXIS] = cos(RADIANS(210 + delta_tower_angle_trim[A_AXIS])) * (radius + trt[A_AXIS]); // front left tower
|
||||||
|
delta_tower[A_AXIS][Y_AXIS] = sin(RADIANS(210 + delta_tower_angle_trim[A_AXIS])) * (radius + trt[A_AXIS]);
|
||||||
|
delta_tower[B_AXIS][X_AXIS] = cos(RADIANS(330 + delta_tower_angle_trim[B_AXIS])) * (radius + trt[B_AXIS]); // front right tower
|
||||||
|
delta_tower[B_AXIS][Y_AXIS] = sin(RADIANS(330 + delta_tower_angle_trim[B_AXIS])) * (radius + trt[B_AXIS]);
|
||||||
|
delta_tower[C_AXIS][X_AXIS] = 0.0; // back middle tower
|
||||||
|
delta_tower[C_AXIS][Y_AXIS] = (radius + trt[C_AXIS]);
|
||||||
|
delta_diagonal_rod_2_tower[A_AXIS] = sq(diagonal_rod + drt[A_AXIS]);
|
||||||
|
delta_diagonal_rod_2_tower[B_AXIS] = sq(diagonal_rod + drt[B_AXIS]);
|
||||||
|
delta_diagonal_rod_2_tower[C_AXIS] = sq(diagonal_rod + drt[C_AXIS]);
|
||||||
|
}
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Delta Inverse Kinematics
|
||||||
|
*
|
||||||
|
* Calculate the tower positions for a given logical
|
||||||
|
* position, storing the result in the delta[] array.
|
||||||
|
*
|
||||||
|
* This is an expensive calculation, requiring 3 square
|
||||||
|
* roots per segmented linear move, and strains the limits
|
||||||
|
* of a Mega2560 with a Graphical Display.
|
||||||
|
*
|
||||||
|
* Suggested optimizations include:
|
||||||
|
*
|
||||||
|
* - Disable the home_offset (M206) and/or position_shift (G92)
|
||||||
|
* features to remove up to 12 float additions.
|
||||||
|
*
|
||||||
|
* - Use a fast-inverse-sqrt function and add the reciprocal.
|
||||||
|
* (see above)
|
||||||
|
*/
|
||||||
|
|
||||||
|
#if ENABLED(DELTA_FAST_SQRT) && defined(ARDUINO_ARCH_AVR)
|
||||||
|
/**
|
||||||
|
* Fast inverse sqrt from Quake III Arena
|
||||||
|
* See: https://en.wikipedia.org/wiki/Fast_inverse_square_root
|
||||||
|
*/
|
||||||
|
float Q_rsqrt(float number) {
|
||||||
|
long i;
|
||||||
|
float x2, y;
|
||||||
|
const float threehalfs = 1.5f;
|
||||||
|
x2 = number * 0.5f;
|
||||||
|
y = number;
|
||||||
|
i = * ( long * ) &y; // evil floating point bit level hacking
|
||||||
|
i = 0x5F3759DF - ( i >> 1 ); // what the f***?
|
||||||
|
y = * ( float * ) &i;
|
||||||
|
y = y * ( threehalfs - ( x2 * y * y ) ); // 1st iteration
|
||||||
|
// y = y * ( threehalfs - ( x2 * y * y ) ); // 2nd iteration, this can be removed
|
||||||
|
return y;
|
||||||
|
}
|
||||||
|
#endif
|
||||||
|
|
||||||
|
#define DELTA_DEBUG() do { \
|
||||||
|
SERIAL_ECHOPAIR("cartesian X:", raw[X_AXIS]); \
|
||||||
|
SERIAL_ECHOPAIR(" Y:", raw[Y_AXIS]); \
|
||||||
|
SERIAL_ECHOLNPAIR(" Z:", raw[Z_AXIS]); \
|
||||||
|
SERIAL_ECHOPAIR("delta A:", delta[A_AXIS]); \
|
||||||
|
SERIAL_ECHOPAIR(" B:", delta[B_AXIS]); \
|
||||||
|
SERIAL_ECHOLNPAIR(" C:", delta[C_AXIS]); \
|
||||||
|
}while(0)
|
||||||
|
|
||||||
|
void inverse_kinematics(const float logical[XYZ]) {
|
||||||
|
DELTA_LOGICAL_IK();
|
||||||
|
// DELTA_DEBUG();
|
||||||
|
}
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Calculate the highest Z position where the
|
||||||
|
* effector has the full range of XY motion.
|
||||||
|
*/
|
||||||
|
float delta_safe_distance_from_top() {
|
||||||
|
float cartesian[XYZ] = {
|
||||||
|
LOGICAL_X_POSITION(0),
|
||||||
|
LOGICAL_Y_POSITION(0),
|
||||||
|
LOGICAL_Z_POSITION(0)
|
||||||
|
};
|
||||||
|
inverse_kinematics(cartesian);
|
||||||
|
float distance = delta[A_AXIS];
|
||||||
|
cartesian[Y_AXIS] = LOGICAL_Y_POSITION(DELTA_PRINTABLE_RADIUS);
|
||||||
|
inverse_kinematics(cartesian);
|
||||||
|
return FABS(distance - delta[A_AXIS]);
|
||||||
|
}
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Delta Forward Kinematics
|
||||||
|
*
|
||||||
|
* See the Wikipedia article "Trilateration"
|
||||||
|
* https://en.wikipedia.org/wiki/Trilateration
|
||||||
|
*
|
||||||
|
* Establish a new coordinate system in the plane of the
|
||||||
|
* three carriage points. This system has its origin at
|
||||||
|
* tower1, with tower2 on the X axis. Tower3 is in the X-Y
|
||||||
|
* plane with a Z component of zero.
|
||||||
|
* We will define unit vectors in this coordinate system
|
||||||
|
* in our original coordinate system. Then when we calculate
|
||||||
|
* the Xnew, Ynew and Znew values, we can translate back into
|
||||||
|
* the original system by moving along those unit vectors
|
||||||
|
* by the corresponding values.
|
||||||
|
*
|
||||||
|
* Variable names matched to Marlin, c-version, and avoid the
|
||||||
|
* use of any vector library.
|
||||||
|
*
|
||||||
|
* by Andreas Hardtung 2016-06-07
|
||||||
|
* based on a Java function from "Delta Robot Kinematics V3"
|
||||||
|
* by Steve Graves
|
||||||
|
*
|
||||||
|
* The result is stored in the cartes[] array.
|
||||||
|
*/
|
||||||
|
void forward_kinematics_DELTA(float z1, float z2, float z3) {
|
||||||
|
// Create a vector in old coordinates along x axis of new coordinate
|
||||||
|
float p12[3] = { delta_tower[B_AXIS][X_AXIS] - delta_tower[A_AXIS][X_AXIS], delta_tower[B_AXIS][Y_AXIS] - delta_tower[A_AXIS][Y_AXIS], z2 - z1 };
|
||||||
|
|
||||||
|
// Get the Magnitude of vector.
|
||||||
|
float d = SQRT( sq(p12[0]) + sq(p12[1]) + sq(p12[2]) );
|
||||||
|
|
||||||
|
// Create unit vector by dividing by magnitude.
|
||||||
|
float ex[3] = { p12[0] / d, p12[1] / d, p12[2] / d };
|
||||||
|
|
||||||
|
// Get the vector from the origin of the new system to the third point.
|
||||||
|
float p13[3] = { delta_tower[C_AXIS][X_AXIS] - delta_tower[A_AXIS][X_AXIS], delta_tower[C_AXIS][Y_AXIS] - delta_tower[A_AXIS][Y_AXIS], z3 - z1 };
|
||||||
|
|
||||||
|
// Use the dot product to find the component of this vector on the X axis.
|
||||||
|
float i = ex[0] * p13[0] + ex[1] * p13[1] + ex[2] * p13[2];
|
||||||
|
|
||||||
|
// Create a vector along the x axis that represents the x component of p13.
|
||||||
|
float iex[3] = { ex[0] * i, ex[1] * i, ex[2] * i };
|
||||||
|
|
||||||
|
// Subtract the X component from the original vector leaving only Y. We use the
|
||||||
|
// variable that will be the unit vector after we scale it.
|
||||||
|
float ey[3] = { p13[0] - iex[0], p13[1] - iex[1], p13[2] - iex[2] };
|
||||||
|
|
||||||
|
// The magnitude of Y component
|
||||||
|
float j = SQRT( sq(ey[0]) + sq(ey[1]) + sq(ey[2]) );
|
||||||
|
|
||||||
|
// Convert to a unit vector
|
||||||
|
ey[0] /= j; ey[1] /= j; ey[2] /= j;
|
||||||
|
|
||||||
|
// The cross product of the unit x and y is the unit z
|
||||||
|
// float[] ez = vectorCrossProd(ex, ey);
|
||||||
|
float ez[3] = {
|
||||||
|
ex[1] * ey[2] - ex[2] * ey[1],
|
||||||
|
ex[2] * ey[0] - ex[0] * ey[2],
|
||||||
|
ex[0] * ey[1] - ex[1] * ey[0]
|
||||||
|
};
|
||||||
|
|
||||||
|
// We now have the d, i and j values defined in Wikipedia.
|
||||||
|
// Plug them into the equations defined in Wikipedia for Xnew, Ynew and Znew
|
||||||
|
float Xnew = (delta_diagonal_rod_2_tower[A_AXIS] - delta_diagonal_rod_2_tower[B_AXIS] + sq(d)) / (d * 2),
|
||||||
|
Ynew = ((delta_diagonal_rod_2_tower[A_AXIS] - delta_diagonal_rod_2_tower[C_AXIS] + HYPOT2(i, j)) / 2 - i * Xnew) / j,
|
||||||
|
Znew = SQRT(delta_diagonal_rod_2_tower[A_AXIS] - HYPOT2(Xnew, Ynew));
|
||||||
|
|
||||||
|
// Start from the origin of the old coordinates and add vectors in the
|
||||||
|
// old coords that represent the Xnew, Ynew and Znew to find the point
|
||||||
|
// in the old system.
|
||||||
|
cartes[X_AXIS] = delta_tower[A_AXIS][X_AXIS] + ex[0] * Xnew + ey[0] * Ynew - ez[0] * Znew;
|
||||||
|
cartes[Y_AXIS] = delta_tower[A_AXIS][Y_AXIS] + ex[1] * Xnew + ey[1] * Ynew - ez[1] * Znew;
|
||||||
|
cartes[Z_AXIS] = z1 + ex[2] * Xnew + ey[2] * Ynew - ez[2] * Znew;
|
||||||
|
}
|
||||||
|
|
||||||
|
/**
|
||||||
|
* A delta can only safely home all axes at the same time
|
||||||
|
* This is like quick_home_xy() but for 3 towers.
|
||||||
|
*/
|
||||||
|
bool home_delta() {
|
||||||
|
#if ENABLED(DEBUG_LEVELING_FEATURE)
|
||||||
|
if (DEBUGGING(LEVELING)) DEBUG_POS(">>> home_delta", current_position);
|
||||||
|
#endif
|
||||||
|
// Init the current position of all carriages to 0,0,0
|
||||||
|
ZERO(current_position);
|
||||||
|
sync_plan_position();
|
||||||
|
|
||||||
|
// Move all carriages together linearly until an endstop is hit.
|
||||||
|
current_position[X_AXIS] = current_position[Y_AXIS] = current_position[Z_AXIS] = (DELTA_HEIGHT + home_offset[Z_AXIS] + 10);
|
||||||
|
feedrate_mm_s = homing_feedrate(X_AXIS);
|
||||||
|
line_to_current_position();
|
||||||
|
stepper.synchronize();
|
||||||
|
|
||||||
|
// If an endstop was not hit, then damage can occur if homing is continued.
|
||||||
|
// This can occur if the delta height (DELTA_HEIGHT + home_offset[Z_AXIS]) is
|
||||||
|
// not set correctly.
|
||||||
|
if (!(Endstops::endstop_hit_bits & (_BV(X_MAX) | _BV(Y_MAX) | _BV(Z_MAX)))) {
|
||||||
|
LCD_MESSAGEPGM(MSG_ERR_HOMING_FAILED);
|
||||||
|
SERIAL_ERROR_START();
|
||||||
|
SERIAL_ERRORLNPGM(MSG_ERR_HOMING_FAILED);
|
||||||
|
return false;
|
||||||
|
}
|
||||||
|
|
||||||
|
endstops.hit_on_purpose(); // clear endstop hit flags
|
||||||
|
|
||||||
|
// At least one carriage has reached the top.
|
||||||
|
// Now re-home each carriage separately.
|
||||||
|
HOMEAXIS(A);
|
||||||
|
HOMEAXIS(B);
|
||||||
|
HOMEAXIS(C);
|
||||||
|
|
||||||
|
// Set all carriages to their home positions
|
||||||
|
// Do this here all at once for Delta, because
|
||||||
|
// XYZ isn't ABC. Applying this per-tower would
|
||||||
|
// give the impression that they are the same.
|
||||||
|
LOOP_XYZ(i) set_axis_is_at_home((AxisEnum)i);
|
||||||
|
|
||||||
|
SYNC_PLAN_POSITION_KINEMATIC();
|
||||||
|
|
||||||
|
#if ENABLED(DEBUG_LEVELING_FEATURE)
|
||||||
|
if (DEBUGGING(LEVELING)) DEBUG_POS("<<< home_delta", current_position);
|
||||||
|
#endif
|
||||||
|
|
||||||
|
return true;
|
||||||
|
}
|
||||||
|
|
||||||
|
#endif // DELTA
|
141
Marlin/src/module/delta.h
Normal file
141
Marlin/src/module/delta.h
Normal file
|
@ -0,0 +1,141 @@
|
||||||
|
/**
|
||||||
|
* Marlin 3D Printer Firmware
|
||||||
|
* Copyright (C) 2016 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
|
||||||
|
*
|
||||||
|
* Based on Sprinter and grbl.
|
||||||
|
* Copyright (C) 2011 Camiel Gubbels / Erik van der Zalm
|
||||||
|
*
|
||||||
|
* This program is free software: you can redistribute it and/or modify
|
||||||
|
* it under the terms of the GNU General Public License as published by
|
||||||
|
* the Free Software Foundation, either version 3 of the License, or
|
||||||
|
* (at your option) any later version.
|
||||||
|
*
|
||||||
|
* This program is distributed in the hope that it will be useful,
|
||||||
|
* but WITHOUT ANY WARRANTY; without even the implied warranty of
|
||||||
|
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
|
||||||
|
* GNU General Public License for more details.
|
||||||
|
*
|
||||||
|
* You should have received a copy of the GNU General Public License
|
||||||
|
* along with this program. If not, see <http://www.gnu.org/licenses/>.
|
||||||
|
*
|
||||||
|
*/
|
||||||
|
|
||||||
|
/**
|
||||||
|
* delta.h - Delta-specific functions
|
||||||
|
*/
|
||||||
|
|
||||||
|
#ifndef __DELTA_H__
|
||||||
|
#define __DELTA_H__
|
||||||
|
|
||||||
|
extern float delta_endstop_adj[ABC],
|
||||||
|
delta_radius,
|
||||||
|
delta_diagonal_rod,
|
||||||
|
delta_segments_per_second,
|
||||||
|
delta_calibration_radius,
|
||||||
|
delta_tower_angle_trim[2];
|
||||||
|
|
||||||
|
extern float delta_tower[ABC][2],
|
||||||
|
delta_diagonal_rod_2_tower[ABC],
|
||||||
|
delta_clip_start_height;
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Recalculate factors used for delta kinematics whenever
|
||||||
|
* settings have been changed (e.g., by M665).
|
||||||
|
*/
|
||||||
|
void recalc_delta_settings(float radius, float diagonal_rod);
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Delta Inverse Kinematics
|
||||||
|
*
|
||||||
|
* Calculate the tower positions for a given logical
|
||||||
|
* position, storing the result in the delta[] array.
|
||||||
|
*
|
||||||
|
* This is an expensive calculation, requiring 3 square
|
||||||
|
* roots per segmented linear move, and strains the limits
|
||||||
|
* of a Mega2560 with a Graphical Display.
|
||||||
|
*
|
||||||
|
* Suggested optimizations include:
|
||||||
|
*
|
||||||
|
* - Disable the home_offset (M206) and/or position_shift (G92)
|
||||||
|
* features to remove up to 12 float additions.
|
||||||
|
*
|
||||||
|
* - Use a fast-inverse-sqrt function and add the reciprocal.
|
||||||
|
* (see above)
|
||||||
|
*/
|
||||||
|
|
||||||
|
#if ENABLED(DELTA_FAST_SQRT) && defined(ARDUINO_ARCH_AVR)
|
||||||
|
/**
|
||||||
|
* Fast inverse sqrt from Quake III Arena
|
||||||
|
* See: https://en.wikipedia.org/wiki/Fast_inverse_square_root
|
||||||
|
*/
|
||||||
|
float Q_rsqrt(float number);
|
||||||
|
#define _SQRT(n) (1.0f / Q_rsqrt(n))
|
||||||
|
#else
|
||||||
|
#define _SQRT(n) SQRT(n)
|
||||||
|
#endif
|
||||||
|
|
||||||
|
// Macro to obtain the Z position of an individual tower
|
||||||
|
#define DELTA_Z(T) raw[Z_AXIS] + _SQRT( \
|
||||||
|
delta_diagonal_rod_2_tower[T] - HYPOT2( \
|
||||||
|
delta_tower[T][X_AXIS] - raw[X_AXIS], \
|
||||||
|
delta_tower[T][Y_AXIS] - raw[Y_AXIS] \
|
||||||
|
) \
|
||||||
|
)
|
||||||
|
|
||||||
|
#define DELTA_RAW_IK() do { \
|
||||||
|
delta[A_AXIS] = DELTA_Z(A_AXIS); \
|
||||||
|
delta[B_AXIS] = DELTA_Z(B_AXIS); \
|
||||||
|
delta[C_AXIS] = DELTA_Z(C_AXIS); \
|
||||||
|
}while(0)
|
||||||
|
|
||||||
|
#define DELTA_LOGICAL_IK() do { \
|
||||||
|
const float raw[XYZ] = { \
|
||||||
|
RAW_X_POSITION(logical[X_AXIS]), \
|
||||||
|
RAW_Y_POSITION(logical[Y_AXIS]), \
|
||||||
|
RAW_Z_POSITION(logical[Z_AXIS]) \
|
||||||
|
}; \
|
||||||
|
DELTA_RAW_IK(); \
|
||||||
|
}while(0)
|
||||||
|
|
||||||
|
void inverse_kinematics(const float logical[XYZ]);
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Calculate the highest Z position where the
|
||||||
|
* effector has the full range of XY motion.
|
||||||
|
*/
|
||||||
|
float delta_safe_distance_from_top();
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Delta Forward Kinematics
|
||||||
|
*
|
||||||
|
* See the Wikipedia article "Trilateration"
|
||||||
|
* https://en.wikipedia.org/wiki/Trilateration
|
||||||
|
*
|
||||||
|
* Establish a new coordinate system in the plane of the
|
||||||
|
* three carriage points. This system has its origin at
|
||||||
|
* tower1, with tower2 on the X axis. Tower3 is in the X-Y
|
||||||
|
* plane with a Z component of zero.
|
||||||
|
* We will define unit vectors in this coordinate system
|
||||||
|
* in our original coordinate system. Then when we calculate
|
||||||
|
* the Xnew, Ynew and Znew values, we can translate back into
|
||||||
|
* the original system by moving along those unit vectors
|
||||||
|
* by the corresponding values.
|
||||||
|
*
|
||||||
|
* Variable names matched to Marlin, c-version, and avoid the
|
||||||
|
* use of any vector library.
|
||||||
|
*
|
||||||
|
* by Andreas Hardtung 2016-06-07
|
||||||
|
* based on a Java function from "Delta Robot Kinematics V3"
|
||||||
|
* by Steve Graves
|
||||||
|
*
|
||||||
|
* The result is stored in the cartes[] array.
|
||||||
|
*/
|
||||||
|
void forward_kinematics_DELTA(float z1, float z2, float z3);
|
||||||
|
|
||||||
|
FORCE_INLINE void forward_kinematics_DELTA(float point[ABC]) {
|
||||||
|
forward_kinematics_DELTA(point[A_AXIS], point[B_AXIS], point[C_AXIS]);
|
||||||
|
}
|
||||||
|
|
||||||
|
bool home_delta();
|
||||||
|
|
||||||
|
#endif // __DELTA_H__
|
|
@ -25,23 +25,38 @@
|
||||||
*/
|
*/
|
||||||
|
|
||||||
#include "motion.h"
|
#include "motion.h"
|
||||||
|
#include "endstops.h"
|
||||||
|
#include "stepper.h"
|
||||||
|
#include "planner.h"
|
||||||
|
#include "temperature.h"
|
||||||
|
|
||||||
#include "../gcode/gcode.h"
|
#include "../gcode/gcode.h"
|
||||||
// #include "../module/planner.h"
|
|
||||||
// #include "../Marlin.h"
|
|
||||||
// #include "../inc/MarlinConfig.h"
|
|
||||||
|
|
||||||
#include "../core/serial.h"
|
#include "../inc/MarlinConfig.h"
|
||||||
#include "../module/stepper.h"
|
|
||||||
#include "../module/temperature.h"
|
|
||||||
|
|
||||||
#if IS_SCARA
|
#if IS_SCARA
|
||||||
#include "../libs/buzzer.h"
|
#include "../libs/buzzer.h"
|
||||||
#include "../lcd/ultralcd.h"
|
#include "../lcd/ultralcd.h"
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#if ENABLED(AUTO_BED_LEVELING_UBL)
|
// #if ENABLED(DUAL_X_CARRIAGE)
|
||||||
#include "../feature/ubl/ubl.h"
|
// #include "tool_change.h"
|
||||||
|
// #endif
|
||||||
|
|
||||||
|
#if HAS_BED_PROBE
|
||||||
|
#include "probe.h"
|
||||||
|
#endif
|
||||||
|
|
||||||
|
#if HAS_LEVELING
|
||||||
|
#include "../feature/bedlevel/bedlevel.h"
|
||||||
|
#endif
|
||||||
|
|
||||||
|
#if NEED_UNHOMED_ERR && ENABLED(ULTRA_LCD)
|
||||||
|
#include "../lcd/ultralcd.h"
|
||||||
|
#endif
|
||||||
|
|
||||||
|
#if ENABLED(SENSORLESS_HOMING)
|
||||||
|
#include "../feature/tmc2130.h"
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#define XYZ_CONSTS(type, array, CONFIG) const PROGMEM type array##_P[XYZ] = { X_##CONFIG, Y_##CONFIG, Z_##CONFIG }
|
#define XYZ_CONSTS(type, array, CONFIG) const PROGMEM type array##_P[XYZ] = { X_##CONFIG, Y_##CONFIG, Z_##CONFIG }
|
||||||
|
@ -72,15 +87,85 @@ float current_position[XYZE] = { 0.0 };
|
||||||
*/
|
*/
|
||||||
float destination[XYZE] = { 0.0 };
|
float destination[XYZE] = { 0.0 };
|
||||||
|
|
||||||
|
|
||||||
// The active extruder (tool). Set with T<extruder> command.
|
// The active extruder (tool). Set with T<extruder> command.
|
||||||
uint8_t active_extruder = 0;
|
uint8_t active_extruder = 0;
|
||||||
|
|
||||||
|
// Extruder offsets
|
||||||
|
#if HOTENDS > 1
|
||||||
|
float hotend_offset[XYZ][HOTENDS]; // Initialized by settings.load()
|
||||||
|
#endif
|
||||||
|
|
||||||
// The feedrate for the current move, often used as the default if
|
// The feedrate for the current move, often used as the default if
|
||||||
// no other feedrate is specified. Overridden for special moves.
|
// no other feedrate is specified. Overridden for special moves.
|
||||||
// Set by the last G0 through G5 command's "F" parameter.
|
// Set by the last G0 through G5 command's "F" parameter.
|
||||||
// Functions that override this for custom moves *must always* restore it!
|
// Functions that override this for custom moves *must always* restore it!
|
||||||
float feedrate_mm_s = MMM_TO_MMS(1500.0);
|
float feedrate_mm_s = MMM_TO_MMS(1500.0);
|
||||||
|
|
||||||
|
int16_t feedrate_percentage = 100;
|
||||||
|
|
||||||
|
// Homing feedrate is const progmem - compare to constexpr in the header
|
||||||
|
const float homing_feedrate_mm_s[4] PROGMEM = {
|
||||||
|
#if ENABLED(DELTA)
|
||||||
|
MMM_TO_MMS(HOMING_FEEDRATE_Z), MMM_TO_MMS(HOMING_FEEDRATE_Z),
|
||||||
|
#else
|
||||||
|
MMM_TO_MMS(HOMING_FEEDRATE_XY), MMM_TO_MMS(HOMING_FEEDRATE_XY),
|
||||||
|
#endif
|
||||||
|
MMM_TO_MMS(HOMING_FEEDRATE_Z), 0
|
||||||
|
};
|
||||||
|
|
||||||
|
// Cartesian conversion result goes here:
|
||||||
|
float cartes[XYZ];
|
||||||
|
|
||||||
|
// Until kinematics.cpp is created, create this here
|
||||||
|
#if IS_KINEMATIC
|
||||||
|
float delta[ABC];
|
||||||
|
#endif
|
||||||
|
|
||||||
|
/**
|
||||||
|
* The workspace can be offset by some commands, or
|
||||||
|
* these offsets may be omitted to save on computation.
|
||||||
|
*/
|
||||||
|
#if HAS_WORKSPACE_OFFSET
|
||||||
|
#if HAS_POSITION_SHIFT
|
||||||
|
// The distance that XYZ has been offset by G92. Reset by G28.
|
||||||
|
float position_shift[XYZ] = { 0 };
|
||||||
|
#endif
|
||||||
|
#if HAS_HOME_OFFSET
|
||||||
|
// This offset is added to the configured home position.
|
||||||
|
// Set by M206, M428, or menu item. Saved to EEPROM.
|
||||||
|
float home_offset[XYZ] = { 0 };
|
||||||
|
#endif
|
||||||
|
#if HAS_HOME_OFFSET && HAS_POSITION_SHIFT
|
||||||
|
// The above two are combined to save on computes
|
||||||
|
float workspace_offset[XYZ] = { 0 };
|
||||||
|
#endif
|
||||||
|
#endif
|
||||||
|
|
||||||
|
#if OLDSCHOOL_ABL
|
||||||
|
float xy_probe_feedrate_mm_s = MMM_TO_MMS(XY_PROBE_SPEED);
|
||||||
|
#endif
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Output the current position to serial
|
||||||
|
*/
|
||||||
|
void report_current_position() {
|
||||||
|
SERIAL_PROTOCOLPGM("X:");
|
||||||
|
SERIAL_PROTOCOL(current_position[X_AXIS]);
|
||||||
|
SERIAL_PROTOCOLPGM(" Y:");
|
||||||
|
SERIAL_PROTOCOL(current_position[Y_AXIS]);
|
||||||
|
SERIAL_PROTOCOLPGM(" Z:");
|
||||||
|
SERIAL_PROTOCOL(current_position[Z_AXIS]);
|
||||||
|
SERIAL_PROTOCOLPGM(" E:");
|
||||||
|
SERIAL_PROTOCOL(current_position[E_AXIS]);
|
||||||
|
|
||||||
|
stepper.report_positions();
|
||||||
|
|
||||||
|
#if IS_SCARA
|
||||||
|
scara_report_positions();
|
||||||
|
#endif
|
||||||
|
}
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* sync_plan_position
|
* sync_plan_position
|
||||||
*
|
*
|
||||||
|
@ -96,6 +181,56 @@ void sync_plan_position() {
|
||||||
|
|
||||||
void sync_plan_position_e() { planner.set_e_position_mm(current_position[E_AXIS]); }
|
void sync_plan_position_e() { planner.set_e_position_mm(current_position[E_AXIS]); }
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Get the stepper positions in the cartes[] array.
|
||||||
|
* Forward kinematics are applied for DELTA and SCARA.
|
||||||
|
*
|
||||||
|
* The result is in the current coordinate space with
|
||||||
|
* leveling applied. The coordinates need to be run through
|
||||||
|
* unapply_leveling to obtain the "ideal" coordinates
|
||||||
|
* suitable for current_position, etc.
|
||||||
|
*/
|
||||||
|
void get_cartesian_from_steppers() {
|
||||||
|
#if ENABLED(DELTA)
|
||||||
|
forward_kinematics_DELTA(
|
||||||
|
stepper.get_axis_position_mm(A_AXIS),
|
||||||
|
stepper.get_axis_position_mm(B_AXIS),
|
||||||
|
stepper.get_axis_position_mm(C_AXIS)
|
||||||
|
);
|
||||||
|
cartes[X_AXIS] += LOGICAL_X_POSITION(0);
|
||||||
|
cartes[Y_AXIS] += LOGICAL_Y_POSITION(0);
|
||||||
|
cartes[Z_AXIS] += LOGICAL_Z_POSITION(0);
|
||||||
|
#elif IS_SCARA
|
||||||
|
forward_kinematics_SCARA(
|
||||||
|
stepper.get_axis_position_degrees(A_AXIS),
|
||||||
|
stepper.get_axis_position_degrees(B_AXIS)
|
||||||
|
);
|
||||||
|
cartes[X_AXIS] += LOGICAL_X_POSITION(0);
|
||||||
|
cartes[Y_AXIS] += LOGICAL_Y_POSITION(0);
|
||||||
|
cartes[Z_AXIS] = stepper.get_axis_position_mm(Z_AXIS);
|
||||||
|
#else
|
||||||
|
cartes[X_AXIS] = stepper.get_axis_position_mm(X_AXIS);
|
||||||
|
cartes[Y_AXIS] = stepper.get_axis_position_mm(Y_AXIS);
|
||||||
|
cartes[Z_AXIS] = stepper.get_axis_position_mm(Z_AXIS);
|
||||||
|
#endif
|
||||||
|
}
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Set the current_position for an axis based on
|
||||||
|
* the stepper positions, removing any leveling that
|
||||||
|
* may have been applied.
|
||||||
|
*/
|
||||||
|
void set_current_from_steppers_for_axis(const AxisEnum axis) {
|
||||||
|
get_cartesian_from_steppers();
|
||||||
|
#if PLANNER_LEVELING
|
||||||
|
planner.unapply_leveling(cartes);
|
||||||
|
#endif
|
||||||
|
if (axis == ALL_AXES)
|
||||||
|
COPY(current_position, cartes);
|
||||||
|
else
|
||||||
|
current_position[axis] = cartes[axis];
|
||||||
|
}
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* Move the planner to the current position from wherever it last moved
|
* Move the planner to the current position from wherever it last moved
|
||||||
* (or from wherever it has been told it is located).
|
* (or from wherever it has been told it is located).
|
||||||
|
@ -149,6 +284,167 @@ void line_to_destination(const float fr_mm_s) {
|
||||||
|
|
||||||
#endif // IS_KINEMATIC
|
#endif // IS_KINEMATIC
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Plan a move to (X, Y, Z) and set the current_position
|
||||||
|
* The final current_position may not be the one that was requested
|
||||||
|
*/
|
||||||
|
void do_blocking_move_to(const float &lx, const float &ly, const float &lz, const float &fr_mm_s/*=0.0*/) {
|
||||||
|
const float old_feedrate_mm_s = feedrate_mm_s;
|
||||||
|
|
||||||
|
#if ENABLED(DEBUG_LEVELING_FEATURE)
|
||||||
|
if (DEBUGGING(LEVELING)) print_xyz(PSTR(">>> do_blocking_move_to"), NULL, lx, ly, lz);
|
||||||
|
#endif
|
||||||
|
|
||||||
|
#if ENABLED(DELTA)
|
||||||
|
|
||||||
|
if (!position_is_reachable_xy(lx, ly)) return;
|
||||||
|
|
||||||
|
feedrate_mm_s = fr_mm_s ? fr_mm_s : XY_PROBE_FEEDRATE_MM_S;
|
||||||
|
|
||||||
|
set_destination_to_current(); // sync destination at the start
|
||||||
|
|
||||||
|
#if ENABLED(DEBUG_LEVELING_FEATURE)
|
||||||
|
if (DEBUGGING(LEVELING)) DEBUG_POS("set_destination_to_current", destination);
|
||||||
|
#endif
|
||||||
|
|
||||||
|
// when in the danger zone
|
||||||
|
if (current_position[Z_AXIS] > delta_clip_start_height) {
|
||||||
|
if (lz > delta_clip_start_height) { // staying in the danger zone
|
||||||
|
destination[X_AXIS] = lx; // move directly (uninterpolated)
|
||||||
|
destination[Y_AXIS] = ly;
|
||||||
|
destination[Z_AXIS] = lz;
|
||||||
|
prepare_uninterpolated_move_to_destination(); // set_current_to_destination
|
||||||
|
#if ENABLED(DEBUG_LEVELING_FEATURE)
|
||||||
|
if (DEBUGGING(LEVELING)) DEBUG_POS("danger zone move", current_position);
|
||||||
|
#endif
|
||||||
|
return;
|
||||||
|
}
|
||||||
|
else {
|
||||||
|
destination[Z_AXIS] = delta_clip_start_height;
|
||||||
|
prepare_uninterpolated_move_to_destination(); // set_current_to_destination
|
||||||
|
#if ENABLED(DEBUG_LEVELING_FEATURE)
|
||||||
|
if (DEBUGGING(LEVELING)) DEBUG_POS("zone border move", current_position);
|
||||||
|
#endif
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
if (lz > current_position[Z_AXIS]) { // raising?
|
||||||
|
destination[Z_AXIS] = lz;
|
||||||
|
prepare_uninterpolated_move_to_destination(); // set_current_to_destination
|
||||||
|
#if ENABLED(DEBUG_LEVELING_FEATURE)
|
||||||
|
if (DEBUGGING(LEVELING)) DEBUG_POS("z raise move", current_position);
|
||||||
|
#endif
|
||||||
|
}
|
||||||
|
|
||||||
|
destination[X_AXIS] = lx;
|
||||||
|
destination[Y_AXIS] = ly;
|
||||||
|
prepare_move_to_destination(); // set_current_to_destination
|
||||||
|
#if ENABLED(DEBUG_LEVELING_FEATURE)
|
||||||
|
if (DEBUGGING(LEVELING)) DEBUG_POS("xy move", current_position);
|
||||||
|
#endif
|
||||||
|
|
||||||
|
if (lz < current_position[Z_AXIS]) { // lowering?
|
||||||
|
destination[Z_AXIS] = lz;
|
||||||
|
prepare_uninterpolated_move_to_destination(); // set_current_to_destination
|
||||||
|
#if ENABLED(DEBUG_LEVELING_FEATURE)
|
||||||
|
if (DEBUGGING(LEVELING)) DEBUG_POS("z lower move", current_position);
|
||||||
|
#endif
|
||||||
|
}
|
||||||
|
|
||||||
|
#elif IS_SCARA
|
||||||
|
|
||||||
|
if (!position_is_reachable_xy(lx, ly)) return;
|
||||||
|
|
||||||
|
set_destination_to_current();
|
||||||
|
|
||||||
|
// If Z needs to raise, do it before moving XY
|
||||||
|
if (destination[Z_AXIS] < lz) {
|
||||||
|
destination[Z_AXIS] = lz;
|
||||||
|
prepare_uninterpolated_move_to_destination(fr_mm_s ? fr_mm_s : homing_feedrate(Z_AXIS));
|
||||||
|
}
|
||||||
|
|
||||||
|
destination[X_AXIS] = lx;
|
||||||
|
destination[Y_AXIS] = ly;
|
||||||
|
prepare_uninterpolated_move_to_destination(fr_mm_s ? fr_mm_s : XY_PROBE_FEEDRATE_MM_S);
|
||||||
|
|
||||||
|
// If Z needs to lower, do it after moving XY
|
||||||
|
if (destination[Z_AXIS] > lz) {
|
||||||
|
destination[Z_AXIS] = lz;
|
||||||
|
prepare_uninterpolated_move_to_destination(fr_mm_s ? fr_mm_s : homing_feedrate(Z_AXIS));
|
||||||
|
}
|
||||||
|
|
||||||
|
#else
|
||||||
|
|
||||||
|
// If Z needs to raise, do it before moving XY
|
||||||
|
if (current_position[Z_AXIS] < lz) {
|
||||||
|
feedrate_mm_s = fr_mm_s ? fr_mm_s : homing_feedrate(Z_AXIS);
|
||||||
|
current_position[Z_AXIS] = lz;
|
||||||
|
line_to_current_position();
|
||||||
|
}
|
||||||
|
|
||||||
|
feedrate_mm_s = fr_mm_s ? fr_mm_s : XY_PROBE_FEEDRATE_MM_S;
|
||||||
|
current_position[X_AXIS] = lx;
|
||||||
|
current_position[Y_AXIS] = ly;
|
||||||
|
line_to_current_position();
|
||||||
|
|
||||||
|
// If Z needs to lower, do it after moving XY
|
||||||
|
if (current_position[Z_AXIS] > lz) {
|
||||||
|
feedrate_mm_s = fr_mm_s ? fr_mm_s : homing_feedrate(Z_AXIS);
|
||||||
|
current_position[Z_AXIS] = lz;
|
||||||
|
line_to_current_position();
|
||||||
|
}
|
||||||
|
|
||||||
|
#endif
|
||||||
|
|
||||||
|
stepper.synchronize();
|
||||||
|
|
||||||
|
feedrate_mm_s = old_feedrate_mm_s;
|
||||||
|
|
||||||
|
#if ENABLED(DEBUG_LEVELING_FEATURE)
|
||||||
|
if (DEBUGGING(LEVELING)) SERIAL_ECHOLNPGM("<<< do_blocking_move_to");
|
||||||
|
#endif
|
||||||
|
}
|
||||||
|
void do_blocking_move_to_x(const float &lx, const float &fr_mm_s/*=0.0*/) {
|
||||||
|
do_blocking_move_to(lx, current_position[Y_AXIS], current_position[Z_AXIS], fr_mm_s);
|
||||||
|
}
|
||||||
|
void do_blocking_move_to_z(const float &lz, const float &fr_mm_s/*=0.0*/) {
|
||||||
|
do_blocking_move_to(current_position[X_AXIS], current_position[Y_AXIS], lz, fr_mm_s);
|
||||||
|
}
|
||||||
|
void do_blocking_move_to_xy(const float &lx, const float &ly, const float &fr_mm_s/*=0.0*/) {
|
||||||
|
do_blocking_move_to(lx, ly, current_position[Z_AXIS], fr_mm_s);
|
||||||
|
}
|
||||||
|
|
||||||
|
//
|
||||||
|
// Prepare to do endstop or probe moves
|
||||||
|
// with custom feedrates.
|
||||||
|
//
|
||||||
|
// - Save current feedrates
|
||||||
|
// - Reset the rate multiplier
|
||||||
|
// - Reset the command timeout
|
||||||
|
// - Enable the endstops (for endstop moves)
|
||||||
|
//
|
||||||
|
void bracket_probe_move(const bool before) {
|
||||||
|
static float saved_feedrate_mm_s;
|
||||||
|
static int16_t saved_feedrate_percentage;
|
||||||
|
#if ENABLED(DEBUG_LEVELING_FEATURE)
|
||||||
|
if (DEBUGGING(LEVELING)) DEBUG_POS("bracket_probe_move", current_position);
|
||||||
|
#endif
|
||||||
|
if (before) {
|
||||||
|
saved_feedrate_mm_s = feedrate_mm_s;
|
||||||
|
saved_feedrate_percentage = feedrate_percentage;
|
||||||
|
feedrate_percentage = 100;
|
||||||
|
gcode.refresh_cmd_timeout();
|
||||||
|
}
|
||||||
|
else {
|
||||||
|
feedrate_mm_s = saved_feedrate_mm_s;
|
||||||
|
feedrate_percentage = saved_feedrate_percentage;
|
||||||
|
gcode.refresh_cmd_timeout();
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
void setup_for_endstop_or_probe_move() { bracket_probe_move(true); }
|
||||||
|
void clean_up_after_endstop_or_probe_move() { bracket_probe_move(false); }
|
||||||
|
|
||||||
// Software Endstops are based on the configured limits.
|
// Software Endstops are based on the configured limits.
|
||||||
float soft_endstop_min[XYZ] = { X_MIN_BED, Y_MIN_BED, Z_MIN_POS },
|
float soft_endstop_min[XYZ] = { X_MIN_BED, Y_MIN_BED, Z_MIN_POS },
|
||||||
soft_endstop_max[XYZ] = { X_MAX_BED, Y_MAX_BED, Z_MAX_POS };
|
soft_endstop_max[XYZ] = { X_MAX_BED, Y_MAX_BED, Z_MAX_POS };
|
||||||
|
@ -189,73 +485,24 @@ float soft_endstop_min[XYZ] = { X_MIN_BED, Y_MIN_BED, Z_MIN_POS },
|
||||||
|
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#if ENABLED(AUTO_BED_LEVELING_BILINEAR) && !IS_KINEMATIC
|
|
||||||
|
|
||||||
#define CELL_INDEX(A,V) ((RAW_##A##_POSITION(V) - bilinear_start[A##_AXIS]) * ABL_BG_FACTOR(A##_AXIS))
|
|
||||||
|
|
||||||
/**
|
|
||||||
* Prepare a bilinear-leveled linear move on Cartesian,
|
|
||||||
* splitting the move where it crosses grid borders.
|
|
||||||
*/
|
|
||||||
void bilinear_line_to_destination(const float fr_mm_s, uint16_t x_splits=0xFFFF, uint16_t y_splits=0xFFFF);
|
|
||||||
int cx1 = CELL_INDEX(X, current_position[X_AXIS]),
|
|
||||||
cy1 = CELL_INDEX(Y, current_position[Y_AXIS]),
|
|
||||||
cx2 = CELL_INDEX(X, destination[X_AXIS]),
|
|
||||||
cy2 = CELL_INDEX(Y, destination[Y_AXIS]);
|
|
||||||
cx1 = constrain(cx1, 0, ABL_BG_POINTS_X - 2);
|
|
||||||
cy1 = constrain(cy1, 0, ABL_BG_POINTS_Y - 2);
|
|
||||||
cx2 = constrain(cx2, 0, ABL_BG_POINTS_X - 2);
|
|
||||||
cy2 = constrain(cy2, 0, ABL_BG_POINTS_Y - 2);
|
|
||||||
|
|
||||||
if (cx1 == cx2 && cy1 == cy2) {
|
|
||||||
// Start and end on same mesh square
|
|
||||||
line_to_destination(fr_mm_s);
|
|
||||||
set_current_to_destination();
|
|
||||||
return;
|
|
||||||
}
|
|
||||||
|
|
||||||
#define LINE_SEGMENT_END(A) (current_position[A ##_AXIS] + (destination[A ##_AXIS] - current_position[A ##_AXIS]) * normalized_dist)
|
|
||||||
|
|
||||||
float normalized_dist, end[XYZE];
|
|
||||||
|
|
||||||
// Split at the left/front border of the right/top square
|
|
||||||
const int8_t gcx = max(cx1, cx2), gcy = max(cy1, cy2);
|
|
||||||
if (cx2 != cx1 && TEST(x_splits, gcx)) {
|
|
||||||
COPY(end, destination);
|
|
||||||
destination[X_AXIS] = LOGICAL_X_POSITION(bilinear_start[X_AXIS] + ABL_BG_SPACING(X_AXIS) * gcx);
|
|
||||||
normalized_dist = (destination[X_AXIS] - current_position[X_AXIS]) / (end[X_AXIS] - current_position[X_AXIS]);
|
|
||||||
destination[Y_AXIS] = LINE_SEGMENT_END(Y);
|
|
||||||
CBI(x_splits, gcx);
|
|
||||||
}
|
|
||||||
else if (cy2 != cy1 && TEST(y_splits, gcy)) {
|
|
||||||
COPY(end, destination);
|
|
||||||
destination[Y_AXIS] = LOGICAL_Y_POSITION(bilinear_start[Y_AXIS] + ABL_BG_SPACING(Y_AXIS) * gcy);
|
|
||||||
normalized_dist = (destination[Y_AXIS] - current_position[Y_AXIS]) / (end[Y_AXIS] - current_position[Y_AXIS]);
|
|
||||||
destination[X_AXIS] = LINE_SEGMENT_END(X);
|
|
||||||
CBI(y_splits, gcy);
|
|
||||||
}
|
|
||||||
else {
|
|
||||||
// Already split on a border
|
|
||||||
line_to_destination(fr_mm_s);
|
|
||||||
set_current_to_destination();
|
|
||||||
return;
|
|
||||||
}
|
|
||||||
|
|
||||||
destination[Z_AXIS] = LINE_SEGMENT_END(Z);
|
|
||||||
destination[E_AXIS] = LINE_SEGMENT_END(E);
|
|
||||||
|
|
||||||
// Do the split and look for more borders
|
|
||||||
bilinear_line_to_destination(fr_mm_s, x_splits, y_splits);
|
|
||||||
|
|
||||||
// Restore destination from stack
|
|
||||||
COPY(destination, end);
|
|
||||||
bilinear_line_to_destination(fr_mm_s, x_splits, y_splits);
|
|
||||||
}
|
|
||||||
|
|
||||||
#endif // AUTO_BED_LEVELING_BILINEAR
|
|
||||||
|
|
||||||
#if IS_KINEMATIC && !UBL_DELTA
|
#if IS_KINEMATIC && !UBL_DELTA
|
||||||
|
|
||||||
|
#if ENABLED(AUTO_BED_LEVELING_BILINEAR)
|
||||||
|
#if ENABLED(DELTA)
|
||||||
|
#define ADJUST_DELTA(V) \
|
||||||
|
if (planner.abl_enabled) { \
|
||||||
|
const float zadj = bilinear_z_offset(V); \
|
||||||
|
delta[A_AXIS] += zadj; \
|
||||||
|
delta[B_AXIS] += zadj; \
|
||||||
|
delta[C_AXIS] += zadj; \
|
||||||
|
}
|
||||||
|
#else
|
||||||
|
#define ADJUST_DELTA(V) if (planner.abl_enabled) { delta[Z_AXIS] += bilinear_z_offset(V); }
|
||||||
|
#endif
|
||||||
|
#else
|
||||||
|
#define ADJUST_DELTA(V) NOOP
|
||||||
|
#endif
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* Prepare a linear move in a DELTA or SCARA setup.
|
* Prepare a linear move in a DELTA or SCARA setup.
|
||||||
*
|
*
|
||||||
|
@ -572,3 +819,453 @@ void prepare_move_to_destination() {
|
||||||
|
|
||||||
set_current_to_destination();
|
set_current_to_destination();
|
||||||
}
|
}
|
||||||
|
|
||||||
|
#if NEED_UNHOMED_ERR
|
||||||
|
|
||||||
|
bool axis_unhomed_error(const bool x/*=true*/, const bool y/*=true*/, const bool z/*=true*/) {
|
||||||
|
#if ENABLED(HOME_AFTER_DEACTIVATE)
|
||||||
|
const bool xx = x && !axis_known_position[X_AXIS],
|
||||||
|
yy = y && !axis_known_position[Y_AXIS],
|
||||||
|
zz = z && !axis_known_position[Z_AXIS];
|
||||||
|
#else
|
||||||
|
const bool xx = x && !axis_homed[X_AXIS],
|
||||||
|
yy = y && !axis_homed[Y_AXIS],
|
||||||
|
zz = z && !axis_homed[Z_AXIS];
|
||||||
|
#endif
|
||||||
|
if (xx || yy || zz) {
|
||||||
|
SERIAL_ECHO_START();
|
||||||
|
SERIAL_ECHOPGM(MSG_HOME " ");
|
||||||
|
if (xx) SERIAL_ECHOPGM(MSG_X);
|
||||||
|
if (yy) SERIAL_ECHOPGM(MSG_Y);
|
||||||
|
if (zz) SERIAL_ECHOPGM(MSG_Z);
|
||||||
|
SERIAL_ECHOLNPGM(" " MSG_FIRST);
|
||||||
|
|
||||||
|
#if ENABLED(ULTRA_LCD)
|
||||||
|
lcd_status_printf_P(0, PSTR(MSG_HOME " %s%s%s " MSG_FIRST), xx ? MSG_X : "", yy ? MSG_Y : "", zz ? MSG_Z : "");
|
||||||
|
#endif
|
||||||
|
return true;
|
||||||
|
}
|
||||||
|
return false;
|
||||||
|
}
|
||||||
|
|
||||||
|
#endif
|
||||||
|
|
||||||
|
/**
|
||||||
|
* The homing feedrate may vary
|
||||||
|
*/
|
||||||
|
inline float get_homing_bump_feedrate(const AxisEnum axis) {
|
||||||
|
static const uint8_t homing_bump_divisor[] PROGMEM = HOMING_BUMP_DIVISOR;
|
||||||
|
uint8_t hbd = pgm_read_byte(&homing_bump_divisor[axis]);
|
||||||
|
if (hbd < 1) {
|
||||||
|
hbd = 10;
|
||||||
|
SERIAL_ECHO_START();
|
||||||
|
SERIAL_ECHOLNPGM("Warning: Homing Bump Divisor < 1");
|
||||||
|
}
|
||||||
|
return homing_feedrate(axis) / hbd;
|
||||||
|
}
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Home an individual linear axis
|
||||||
|
*/
|
||||||
|
static void do_homing_move(const AxisEnum axis, const float distance, const float fr_mm_s=0.0) {
|
||||||
|
|
||||||
|
#if ENABLED(DEBUG_LEVELING_FEATURE)
|
||||||
|
if (DEBUGGING(LEVELING)) {
|
||||||
|
SERIAL_ECHOPAIR(">>> do_homing_move(", axis_codes[axis]);
|
||||||
|
SERIAL_ECHOPAIR(", ", distance);
|
||||||
|
SERIAL_ECHOPAIR(", ", fr_mm_s);
|
||||||
|
SERIAL_CHAR(')');
|
||||||
|
SERIAL_EOL();
|
||||||
|
}
|
||||||
|
#endif
|
||||||
|
|
||||||
|
#if HOMING_Z_WITH_PROBE && ENABLED(BLTOUCH)
|
||||||
|
const bool deploy_bltouch = (axis == Z_AXIS && distance < 0);
|
||||||
|
if (deploy_bltouch) set_bltouch_deployed(true);
|
||||||
|
#endif
|
||||||
|
|
||||||
|
#if QUIET_PROBING
|
||||||
|
if (axis == Z_AXIS) probing_pause(true);
|
||||||
|
#endif
|
||||||
|
|
||||||
|
// Tell the planner we're at Z=0
|
||||||
|
current_position[axis] = 0;
|
||||||
|
|
||||||
|
#if IS_SCARA
|
||||||
|
SYNC_PLAN_POSITION_KINEMATIC();
|
||||||
|
current_position[axis] = distance;
|
||||||
|
inverse_kinematics(current_position);
|
||||||
|
planner.buffer_line(delta[A_AXIS], delta[B_AXIS], delta[C_AXIS], current_position[E_AXIS], fr_mm_s ? fr_mm_s : homing_feedrate(axis), active_extruder);
|
||||||
|
#else
|
||||||
|
sync_plan_position();
|
||||||
|
current_position[axis] = distance;
|
||||||
|
planner.buffer_line(current_position[X_AXIS], current_position[Y_AXIS], current_position[Z_AXIS], current_position[E_AXIS], fr_mm_s ? fr_mm_s : homing_feedrate(axis), active_extruder);
|
||||||
|
#endif
|
||||||
|
|
||||||
|
stepper.synchronize();
|
||||||
|
|
||||||
|
#if QUIET_PROBING
|
||||||
|
if (axis == Z_AXIS) probing_pause(false);
|
||||||
|
#endif
|
||||||
|
|
||||||
|
#if HOMING_Z_WITH_PROBE && ENABLED(BLTOUCH)
|
||||||
|
if (deploy_bltouch) set_bltouch_deployed(false);
|
||||||
|
#endif
|
||||||
|
|
||||||
|
endstops.hit_on_purpose();
|
||||||
|
|
||||||
|
#if ENABLED(DEBUG_LEVELING_FEATURE)
|
||||||
|
if (DEBUGGING(LEVELING)) {
|
||||||
|
SERIAL_ECHOPAIR("<<< do_homing_move(", axis_codes[axis]);
|
||||||
|
SERIAL_CHAR(')');
|
||||||
|
SERIAL_EOL();
|
||||||
|
}
|
||||||
|
#endif
|
||||||
|
}
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Set an axis' current position to its home position (after homing).
|
||||||
|
*
|
||||||
|
* For Core and Cartesian robots this applies one-to-one when an
|
||||||
|
* individual axis has been homed.
|
||||||
|
*
|
||||||
|
* DELTA should wait until all homing is done before setting the XYZ
|
||||||
|
* current_position to home, because homing is a single operation.
|
||||||
|
* In the case where the axis positions are already known and previously
|
||||||
|
* homed, DELTA could home to X or Y individually by moving either one
|
||||||
|
* to the center. However, homing Z always homes XY and Z.
|
||||||
|
*
|
||||||
|
* SCARA should wait until all XY homing is done before setting the XY
|
||||||
|
* current_position to home, because neither X nor Y is at home until
|
||||||
|
* both are at home. Z can however be homed individually.
|
||||||
|
*
|
||||||
|
* Callers must sync the planner position after calling this!
|
||||||
|
*/
|
||||||
|
void set_axis_is_at_home(const AxisEnum axis) {
|
||||||
|
#if ENABLED(DEBUG_LEVELING_FEATURE)
|
||||||
|
if (DEBUGGING(LEVELING)) {
|
||||||
|
SERIAL_ECHOPAIR(">>> set_axis_is_at_home(", axis_codes[axis]);
|
||||||
|
SERIAL_CHAR(')');
|
||||||
|
SERIAL_EOL();
|
||||||
|
}
|
||||||
|
#endif
|
||||||
|
|
||||||
|
axis_known_position[axis] = axis_homed[axis] = true;
|
||||||
|
|
||||||
|
#if HAS_POSITION_SHIFT
|
||||||
|
position_shift[axis] = 0;
|
||||||
|
update_software_endstops(axis);
|
||||||
|
#endif
|
||||||
|
|
||||||
|
#if ENABLED(DUAL_X_CARRIAGE)
|
||||||
|
if (axis == X_AXIS && (active_extruder == 1 || dual_x_carriage_mode == DXC_DUPLICATION_MODE)) {
|
||||||
|
current_position[X_AXIS] = x_home_pos(active_extruder);
|
||||||
|
return;
|
||||||
|
}
|
||||||
|
#endif
|
||||||
|
|
||||||
|
#if ENABLED(MORGAN_SCARA)
|
||||||
|
scara_set_axis_is_at_home(axis);
|
||||||
|
#else
|
||||||
|
current_position[axis] = LOGICAL_POSITION(base_home_pos(axis), axis);
|
||||||
|
#endif
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Z Probe Z Homing? Account for the probe's Z offset.
|
||||||
|
*/
|
||||||
|
#if HAS_BED_PROBE && Z_HOME_DIR < 0
|
||||||
|
if (axis == Z_AXIS) {
|
||||||
|
#if HOMING_Z_WITH_PROBE
|
||||||
|
|
||||||
|
current_position[Z_AXIS] -= zprobe_zoffset;
|
||||||
|
|
||||||
|
#if ENABLED(DEBUG_LEVELING_FEATURE)
|
||||||
|
if (DEBUGGING(LEVELING)) {
|
||||||
|
SERIAL_ECHOLNPGM("*** Z HOMED WITH PROBE (Z_MIN_PROBE_USES_Z_MIN_ENDSTOP_PIN) ***");
|
||||||
|
SERIAL_ECHOLNPAIR("> zprobe_zoffset = ", zprobe_zoffset);
|
||||||
|
}
|
||||||
|
#endif
|
||||||
|
|
||||||
|
#elif ENABLED(DEBUG_LEVELING_FEATURE)
|
||||||
|
|
||||||
|
if (DEBUGGING(LEVELING)) SERIAL_ECHOLNPGM("*** Z HOMED TO ENDSTOP (Z_MIN_PROBE_ENDSTOP) ***");
|
||||||
|
|
||||||
|
#endif
|
||||||
|
}
|
||||||
|
#endif
|
||||||
|
|
||||||
|
#if ENABLED(DEBUG_LEVELING_FEATURE)
|
||||||
|
if (DEBUGGING(LEVELING)) {
|
||||||
|
#if HAS_HOME_OFFSET
|
||||||
|
SERIAL_ECHOPAIR("> home_offset[", axis_codes[axis]);
|
||||||
|
SERIAL_ECHOLNPAIR("] = ", home_offset[axis]);
|
||||||
|
#endif
|
||||||
|
DEBUG_POS("", current_position);
|
||||||
|
SERIAL_ECHOPAIR("<<< set_axis_is_at_home(", axis_codes[axis]);
|
||||||
|
SERIAL_CHAR(')');
|
||||||
|
SERIAL_EOL();
|
||||||
|
}
|
||||||
|
#endif
|
||||||
|
|
||||||
|
#if ENABLED(I2C_POSITION_ENCODERS)
|
||||||
|
I2CPEM.homed(axis);
|
||||||
|
#endif
|
||||||
|
}
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Home an individual "raw axis" to its endstop.
|
||||||
|
* This applies to XYZ on Cartesian and Core robots, and
|
||||||
|
* to the individual ABC steppers on DELTA and SCARA.
|
||||||
|
*
|
||||||
|
* At the end of the procedure the axis is marked as
|
||||||
|
* homed and the current position of that axis is updated.
|
||||||
|
* Kinematic robots should wait till all axes are homed
|
||||||
|
* before updating the current position.
|
||||||
|
*/
|
||||||
|
|
||||||
|
void homeaxis(const AxisEnum axis) {
|
||||||
|
|
||||||
|
#if IS_SCARA
|
||||||
|
// Only Z homing (with probe) is permitted
|
||||||
|
if (axis != Z_AXIS) { BUZZ(100, 880); return; }
|
||||||
|
#else
|
||||||
|
#define CAN_HOME(A) \
|
||||||
|
(axis == A##_AXIS && ((A##_MIN_PIN > -1 && A##_HOME_DIR < 0) || (A##_MAX_PIN > -1 && A##_HOME_DIR > 0)))
|
||||||
|
if (!CAN_HOME(X) && !CAN_HOME(Y) && !CAN_HOME(Z)) return;
|
||||||
|
#endif
|
||||||
|
|
||||||
|
#if ENABLED(DEBUG_LEVELING_FEATURE)
|
||||||
|
if (DEBUGGING(LEVELING)) {
|
||||||
|
SERIAL_ECHOPAIR(">>> homeaxis(", axis_codes[axis]);
|
||||||
|
SERIAL_CHAR(')');
|
||||||
|
SERIAL_EOL();
|
||||||
|
}
|
||||||
|
#endif
|
||||||
|
|
||||||
|
const int axis_home_dir =
|
||||||
|
#if ENABLED(DUAL_X_CARRIAGE)
|
||||||
|
(axis == X_AXIS) ? x_home_dir(active_extruder) :
|
||||||
|
#endif
|
||||||
|
home_dir(axis);
|
||||||
|
|
||||||
|
// Homing Z towards the bed? Deploy the Z probe or endstop.
|
||||||
|
#if HOMING_Z_WITH_PROBE
|
||||||
|
if (axis == Z_AXIS && DEPLOY_PROBE()) return;
|
||||||
|
#endif
|
||||||
|
|
||||||
|
// Set a flag for Z motor locking
|
||||||
|
#if ENABLED(Z_DUAL_ENDSTOPS)
|
||||||
|
if (axis == Z_AXIS) stepper.set_homing_flag(true);
|
||||||
|
#endif
|
||||||
|
|
||||||
|
// Disable stealthChop if used. Enable diag1 pin on driver.
|
||||||
|
#if ENABLED(SENSORLESS_HOMING)
|
||||||
|
#if ENABLED(X_IS_TMC2130)
|
||||||
|
if (axis == X_AXIS) tmc2130_sensorless_homing(stepperX);
|
||||||
|
#endif
|
||||||
|
#if ENABLED(Y_IS_TMC2130)
|
||||||
|
if (axis == Y_AXIS) tmc2130_sensorless_homing(stepperY);
|
||||||
|
#endif
|
||||||
|
#endif
|
||||||
|
|
||||||
|
// Fast move towards endstop until triggered
|
||||||
|
#if ENABLED(DEBUG_LEVELING_FEATURE)
|
||||||
|
if (DEBUGGING(LEVELING)) SERIAL_ECHOLNPGM("Home 1 Fast:");
|
||||||
|
#endif
|
||||||
|
do_homing_move(axis, 1.5 * max_length(axis) * axis_home_dir);
|
||||||
|
|
||||||
|
// When homing Z with probe respect probe clearance
|
||||||
|
const float bump = axis_home_dir * (
|
||||||
|
#if HOMING_Z_WITH_PROBE
|
||||||
|
(axis == Z_AXIS) ? max(Z_CLEARANCE_BETWEEN_PROBES, home_bump_mm(Z_AXIS)) :
|
||||||
|
#endif
|
||||||
|
home_bump_mm(axis)
|
||||||
|
);
|
||||||
|
|
||||||
|
// If a second homing move is configured...
|
||||||
|
if (bump) {
|
||||||
|
// Move away from the endstop by the axis HOME_BUMP_MM
|
||||||
|
#if ENABLED(DEBUG_LEVELING_FEATURE)
|
||||||
|
if (DEBUGGING(LEVELING)) SERIAL_ECHOLNPGM("Move Away:");
|
||||||
|
#endif
|
||||||
|
do_homing_move(axis, -bump);
|
||||||
|
|
||||||
|
// Slow move towards endstop until triggered
|
||||||
|
#if ENABLED(DEBUG_LEVELING_FEATURE)
|
||||||
|
if (DEBUGGING(LEVELING)) SERIAL_ECHOLNPGM("Home 2 Slow:");
|
||||||
|
#endif
|
||||||
|
do_homing_move(axis, 2 * bump, get_homing_bump_feedrate(axis));
|
||||||
|
}
|
||||||
|
|
||||||
|
#if ENABLED(Z_DUAL_ENDSTOPS)
|
||||||
|
if (axis == Z_AXIS) {
|
||||||
|
float adj = FABS(z_endstop_adj);
|
||||||
|
bool lockZ1;
|
||||||
|
if (axis_home_dir > 0) {
|
||||||
|
adj = -adj;
|
||||||
|
lockZ1 = (z_endstop_adj > 0);
|
||||||
|
}
|
||||||
|
else
|
||||||
|
lockZ1 = (z_endstop_adj < 0);
|
||||||
|
|
||||||
|
if (lockZ1) stepper.set_z_lock(true); else stepper.set_z2_lock(true);
|
||||||
|
|
||||||
|
// Move to the adjusted endstop height
|
||||||
|
do_homing_move(axis, adj);
|
||||||
|
|
||||||
|
if (lockZ1) stepper.set_z_lock(false); else stepper.set_z2_lock(false);
|
||||||
|
stepper.set_homing_flag(false);
|
||||||
|
} // Z_AXIS
|
||||||
|
#endif
|
||||||
|
|
||||||
|
#if IS_SCARA
|
||||||
|
|
||||||
|
set_axis_is_at_home(axis);
|
||||||
|
SYNC_PLAN_POSITION_KINEMATIC();
|
||||||
|
|
||||||
|
#elif ENABLED(DELTA)
|
||||||
|
|
||||||
|
// Delta has already moved all three towers up in G28
|
||||||
|
// so here it re-homes each tower in turn.
|
||||||
|
// Delta homing treats the axes as normal linear axes.
|
||||||
|
|
||||||
|
// retrace by the amount specified in delta_endstop_adj + additional 0.1mm in order to have minimum steps
|
||||||
|
if (delta_endstop_adj[axis] * Z_HOME_DIR <= 0) {
|
||||||
|
#if ENABLED(DEBUG_LEVELING_FEATURE)
|
||||||
|
if (DEBUGGING(LEVELING)) SERIAL_ECHOLNPGM("delta_endstop_adj:");
|
||||||
|
#endif
|
||||||
|
do_homing_move(axis, delta_endstop_adj[axis] - 0.1);
|
||||||
|
}
|
||||||
|
|
||||||
|
#else
|
||||||
|
|
||||||
|
// For cartesian/core machines,
|
||||||
|
// set the axis to its home position
|
||||||
|
set_axis_is_at_home(axis);
|
||||||
|
sync_plan_position();
|
||||||
|
|
||||||
|
destination[axis] = current_position[axis];
|
||||||
|
|
||||||
|
#if ENABLED(DEBUG_LEVELING_FEATURE)
|
||||||
|
if (DEBUGGING(LEVELING)) DEBUG_POS("> AFTER set_axis_is_at_home", current_position);
|
||||||
|
#endif
|
||||||
|
|
||||||
|
#endif
|
||||||
|
|
||||||
|
// Re-enable stealthChop if used. Disable diag1 pin on driver.
|
||||||
|
#if ENABLED(SENSORLESS_HOMING)
|
||||||
|
#if ENABLED(X_IS_TMC2130)
|
||||||
|
if (axis == X_AXIS) tmc2130_sensorless_homing(stepperX, false);
|
||||||
|
#endif
|
||||||
|
#if ENABLED(Y_IS_TMC2130)
|
||||||
|
if (axis == Y_AXIS) tmc2130_sensorless_homing(stepperY, false);
|
||||||
|
#endif
|
||||||
|
#endif
|
||||||
|
|
||||||
|
// Put away the Z probe
|
||||||
|
#if HOMING_Z_WITH_PROBE
|
||||||
|
if (axis == Z_AXIS && STOW_PROBE()) return;
|
||||||
|
#endif
|
||||||
|
|
||||||
|
#if ENABLED(DEBUG_LEVELING_FEATURE)
|
||||||
|
if (DEBUGGING(LEVELING)) {
|
||||||
|
SERIAL_ECHOPAIR("<<< homeaxis(", axis_codes[axis]);
|
||||||
|
SERIAL_CHAR(')');
|
||||||
|
SERIAL_EOL();
|
||||||
|
}
|
||||||
|
#endif
|
||||||
|
} // homeaxis()
|
||||||
|
|
||||||
|
#if HAS_WORKSPACE_OFFSET || ENABLED(DUAL_X_CARRIAGE)
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Software endstops can be used to monitor the open end of
|
||||||
|
* an axis that has a hardware endstop on the other end. Or
|
||||||
|
* they can prevent axes from moving past endstops and grinding.
|
||||||
|
*
|
||||||
|
* To keep doing their job as the coordinate system changes,
|
||||||
|
* the software endstop positions must be refreshed to remain
|
||||||
|
* at the same positions relative to the machine.
|
||||||
|
*/
|
||||||
|
void update_software_endstops(const AxisEnum axis) {
|
||||||
|
const float offs = 0.0
|
||||||
|
#if HAS_HOME_OFFSET
|
||||||
|
+ home_offset[axis]
|
||||||
|
#endif
|
||||||
|
#if HAS_POSITION_SHIFT
|
||||||
|
+ position_shift[axis]
|
||||||
|
#endif
|
||||||
|
;
|
||||||
|
|
||||||
|
#if HAS_HOME_OFFSET && HAS_POSITION_SHIFT
|
||||||
|
workspace_offset[axis] = offs;
|
||||||
|
#endif
|
||||||
|
|
||||||
|
#if ENABLED(DUAL_X_CARRIAGE)
|
||||||
|
if (axis == X_AXIS) {
|
||||||
|
|
||||||
|
// In Dual X mode hotend_offset[X] is T1's home position
|
||||||
|
float dual_max_x = max(hotend_offset[X_AXIS][1], X2_MAX_POS);
|
||||||
|
|
||||||
|
if (active_extruder != 0) {
|
||||||
|
// T1 can move from X2_MIN_POS to X2_MAX_POS or X2 home position (whichever is larger)
|
||||||
|
soft_endstop_min[X_AXIS] = X2_MIN_POS + offs;
|
||||||
|
soft_endstop_max[X_AXIS] = dual_max_x + offs;
|
||||||
|
}
|
||||||
|
else if (dual_x_carriage_mode == DXC_DUPLICATION_MODE) {
|
||||||
|
// In Duplication Mode, T0 can move as far left as X_MIN_POS
|
||||||
|
// but not so far to the right that T1 would move past the end
|
||||||
|
soft_endstop_min[X_AXIS] = base_min_pos(X_AXIS) + offs;
|
||||||
|
soft_endstop_max[X_AXIS] = min(base_max_pos(X_AXIS), dual_max_x - duplicate_extruder_x_offset) + offs;
|
||||||
|
}
|
||||||
|
else {
|
||||||
|
// In other modes, T0 can move from X_MIN_POS to X_MAX_POS
|
||||||
|
soft_endstop_min[axis] = base_min_pos(axis) + offs;
|
||||||
|
soft_endstop_max[axis] = base_max_pos(axis) + offs;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
#elif ENABLED(DELTA)
|
||||||
|
soft_endstop_min[axis] = base_min_pos(axis) + (axis == Z_AXIS ? 0 : offs);
|
||||||
|
soft_endstop_max[axis] = base_max_pos(axis) + offs;
|
||||||
|
#else
|
||||||
|
soft_endstop_min[axis] = base_min_pos(axis) + offs;
|
||||||
|
soft_endstop_max[axis] = base_max_pos(axis) + offs;
|
||||||
|
#endif
|
||||||
|
|
||||||
|
#if ENABLED(DEBUG_LEVELING_FEATURE)
|
||||||
|
if (DEBUGGING(LEVELING)) {
|
||||||
|
SERIAL_ECHOPAIR("For ", axis_codes[axis]);
|
||||||
|
#if HAS_HOME_OFFSET
|
||||||
|
SERIAL_ECHOPAIR(" axis:\n home_offset = ", home_offset[axis]);
|
||||||
|
#endif
|
||||||
|
#if HAS_POSITION_SHIFT
|
||||||
|
SERIAL_ECHOPAIR("\n position_shift = ", position_shift[axis]);
|
||||||
|
#endif
|
||||||
|
SERIAL_ECHOPAIR("\n soft_endstop_min = ", soft_endstop_min[axis]);
|
||||||
|
SERIAL_ECHOLNPAIR("\n soft_endstop_max = ", soft_endstop_max[axis]);
|
||||||
|
}
|
||||||
|
#endif
|
||||||
|
|
||||||
|
#if ENABLED(DELTA)
|
||||||
|
if (axis == Z_AXIS)
|
||||||
|
delta_clip_start_height = soft_endstop_max[axis] - delta_safe_distance_from_top();
|
||||||
|
#endif
|
||||||
|
}
|
||||||
|
|
||||||
|
#endif // HAS_WORKSPACE_OFFSET || DUAL_X_CARRIAGE
|
||||||
|
|
||||||
|
#if HAS_M206_COMMAND
|
||||||
|
/**
|
||||||
|
* Change the home offset for an axis, update the current
|
||||||
|
* position and the software endstops to retain the same
|
||||||
|
* relative distance to the new home.
|
||||||
|
*
|
||||||
|
* Since this changes the current_position, code should
|
||||||
|
* call sync_plan_position soon after this.
|
||||||
|
*/
|
||||||
|
void set_home_offset(const AxisEnum axis, const float v) {
|
||||||
|
current_position[axis] += v - home_offset[axis];
|
||||||
|
home_offset[axis] = v;
|
||||||
|
update_software_endstops(axis);
|
||||||
|
}
|
||||||
|
#endif // HAS_M206_COMMAND
|
||||||
|
|
|
@ -32,20 +32,53 @@
|
||||||
|
|
||||||
#include "../inc/MarlinConfig.h"
|
#include "../inc/MarlinConfig.h"
|
||||||
|
|
||||||
//#include "../HAL/HAL.h"
|
#if IS_SCARA
|
||||||
|
#include "../module/scara.h"
|
||||||
// #if ENABLED(DELTA)
|
#endif
|
||||||
// #include "../module/delta.h"
|
|
||||||
// #endif
|
|
||||||
|
|
||||||
extern bool relative_mode;
|
extern bool relative_mode;
|
||||||
|
|
||||||
extern float current_position[XYZE], destination[XYZE];
|
extern float current_position[XYZE], // High-level current tool position
|
||||||
|
destination[XYZE]; // Destination for a move
|
||||||
|
|
||||||
|
// Scratch space for a cartesian result
|
||||||
|
extern float cartes[XYZ];
|
||||||
|
|
||||||
|
// Until kinematics.cpp is created, declare this here
|
||||||
|
#if IS_KINEMATIC
|
||||||
|
extern float delta[ABC];
|
||||||
|
#endif
|
||||||
|
|
||||||
|
#if OLDSCHOOL_ABL
|
||||||
|
extern float xy_probe_feedrate_mm_s;
|
||||||
|
#define XY_PROBE_FEEDRATE_MM_S xy_probe_feedrate_mm_s
|
||||||
|
#elif defined(XY_PROBE_SPEED)
|
||||||
|
#define XY_PROBE_FEEDRATE_MM_S MMM_TO_MMS(XY_PROBE_SPEED)
|
||||||
|
#else
|
||||||
|
#define XY_PROBE_FEEDRATE_MM_S PLANNER_XY_FEEDRATE()
|
||||||
|
#endif
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Feed rates are often configured with mm/m
|
||||||
|
* but the planner and stepper like mm/s units.
|
||||||
|
*/
|
||||||
|
extern const float homing_feedrate_mm_s[4];
|
||||||
|
FORCE_INLINE float homing_feedrate(const AxisEnum a) { return pgm_read_float(&homing_feedrate_mm_s[a]); }
|
||||||
|
|
||||||
extern float feedrate_mm_s;
|
extern float feedrate_mm_s;
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Feedrate scaling and conversion
|
||||||
|
*/
|
||||||
|
extern int16_t feedrate_percentage;
|
||||||
|
#define MMS_SCALED(MM_S) ((MM_S)*feedrate_percentage*0.01)
|
||||||
|
|
||||||
extern uint8_t active_extruder;
|
extern uint8_t active_extruder;
|
||||||
|
|
||||||
|
#if HOTENDS > 1
|
||||||
|
extern float hotend_offset[XYZ][HOTENDS];
|
||||||
|
#endif
|
||||||
|
|
||||||
extern float soft_endstop_min[XYZ], soft_endstop_max[XYZ];
|
extern float soft_endstop_min[XYZ], soft_endstop_max[XYZ];
|
||||||
|
|
||||||
FORCE_INLINE float pgm_read_any(const float *p) { return pgm_read_float_near(p); }
|
FORCE_INLINE float pgm_read_any(const float *p) { return pgm_read_float_near(p); }
|
||||||
|
@ -71,9 +104,14 @@ XYZ_DEFS(signed char, home_dir, HOME_DIR);
|
||||||
#define clamp_to_software_endstops(x) NOOP
|
#define clamp_to_software_endstops(x) NOOP
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
void report_current_position();
|
||||||
|
|
||||||
inline void set_current_to_destination() { COPY(current_position, destination); }
|
inline void set_current_to_destination() { COPY(current_position, destination); }
|
||||||
inline void set_destination_to_current() { COPY(destination, current_position); }
|
inline void set_destination_to_current() { COPY(destination, current_position); }
|
||||||
|
|
||||||
|
void get_cartesian_from_steppers();
|
||||||
|
void set_current_from_steppers_for_axis(const AxisEnum axis);
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* sync_plan_position
|
* sync_plan_position
|
||||||
*
|
*
|
||||||
|
@ -110,7 +148,35 @@ inline void line_to_destination() { line_to_destination(feedrate_mm_s); }
|
||||||
|
|
||||||
void prepare_move_to_destination();
|
void prepare_move_to_destination();
|
||||||
|
|
||||||
void clamp_to_software_endstops(float target[XYZ]);
|
/**
|
||||||
|
* Blocking movement and shorthand functions
|
||||||
|
*/
|
||||||
|
void do_blocking_move_to(const float &x, const float &y, const float &z, const float &fr_mm_s=0.0);
|
||||||
|
void do_blocking_move_to_x(const float &x, const float &fr_mm_s=0.0);
|
||||||
|
void do_blocking_move_to_z(const float &z, const float &fr_mm_s=0.0);
|
||||||
|
void do_blocking_move_to_xy(const float &x, const float &y, const float &fr_mm_s=0.0);
|
||||||
|
|
||||||
|
void setup_for_endstop_or_probe_move();
|
||||||
|
void clean_up_after_endstop_or_probe_move();
|
||||||
|
|
||||||
|
void bracket_probe_move(const bool before);
|
||||||
|
void setup_for_endstop_or_probe_move();
|
||||||
|
void clean_up_after_endstop_or_probe_move();
|
||||||
|
|
||||||
|
//
|
||||||
|
// Homing
|
||||||
|
//
|
||||||
|
|
||||||
|
#define NEED_UNHOMED_ERR (HAS_PROBING_PROCEDURE || HOTENDS > 1 || ENABLED(Z_PROBE_ALLEN_KEY) || ENABLED(Z_PROBE_SLED) || ENABLED(NOZZLE_CLEAN_FEATURE) || ENABLED(NOZZLE_PARK_FEATURE) || ENABLED(DELTA_AUTO_CALIBRATION))
|
||||||
|
|
||||||
|
#if NEED_UNHOMED_ERR
|
||||||
|
bool axis_unhomed_error(const bool x=true, const bool y=true, const bool z=true);
|
||||||
|
#endif
|
||||||
|
|
||||||
|
void set_axis_is_at_home(const AxisEnum axis);
|
||||||
|
|
||||||
|
void homeaxis(const AxisEnum axis);
|
||||||
|
#define HOMEAXIS(LETTER) homeaxis(LETTER##_AXIS)
|
||||||
|
|
||||||
//
|
//
|
||||||
// Macros
|
// Macros
|
||||||
|
@ -162,10 +228,6 @@ void clamp_to_software_endstops(float target[XYZ]);
|
||||||
|
|
||||||
#if IS_KINEMATIC // (DELTA or SCARA)
|
#if IS_KINEMATIC // (DELTA or SCARA)
|
||||||
|
|
||||||
#if IS_SCARA
|
|
||||||
extern const float L1, L2;
|
|
||||||
#endif
|
|
||||||
|
|
||||||
inline bool position_is_reachable_raw_xy(const float &rx, const float &ry) {
|
inline bool position_is_reachable_raw_xy(const float &rx, const float &ry) {
|
||||||
#if ENABLED(DELTA)
|
#if ENABLED(DELTA)
|
||||||
return HYPOT2(rx, ry) <= sq(DELTA_PRINTABLE_RADIUS);
|
return HYPOT2(rx, ry) <= sq(DELTA_PRINTABLE_RADIUS);
|
||||||
|
@ -214,10 +276,16 @@ FORCE_INLINE bool position_is_reachable_xy(const float &lx, const float &ly) {
|
||||||
return position_is_reachable_raw_xy(RAW_X_POSITION(lx), RAW_Y_POSITION(ly));
|
return position_is_reachable_raw_xy(RAW_X_POSITION(lx), RAW_Y_POSITION(ly));
|
||||||
}
|
}
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Dual X Carriage / Dual Nozzle
|
||||||
|
*/
|
||||||
#if ENABLED(DUAL_X_CARRIAGE) || ENABLED(DUAL_NOZZLE_DUPLICATION_MODE)
|
#if ENABLED(DUAL_X_CARRIAGE) || ENABLED(DUAL_NOZZLE_DUPLICATION_MODE)
|
||||||
extern bool extruder_duplication_enabled; // Used in Dual X mode 2
|
extern bool extruder_duplication_enabled; // Used in Dual X mode 2
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Dual X Carriage
|
||||||
|
*/
|
||||||
#if ENABLED(DUAL_X_CARRIAGE)
|
#if ENABLED(DUAL_X_CARRIAGE)
|
||||||
|
|
||||||
extern DualXMode dual_x_carriage_mode;
|
extern DualXMode dual_x_carriage_mode;
|
||||||
|
@ -234,4 +302,12 @@ FORCE_INLINE bool position_is_reachable_xy(const float &lx, const float &ly) {
|
||||||
|
|
||||||
#endif // DUAL_X_CARRIAGE
|
#endif // DUAL_X_CARRIAGE
|
||||||
|
|
||||||
|
#if HAS_WORKSPACE_OFFSET || ENABLED(DUAL_X_CARRIAGE)
|
||||||
|
void update_software_endstops(const AxisEnum axis);
|
||||||
|
#endif
|
||||||
|
|
||||||
|
#if HAS_M206_COMMAND
|
||||||
|
void set_home_offset(const AxisEnum axis, const float v);
|
||||||
|
#endif
|
||||||
|
|
||||||
#endif // MOTION_H
|
#endif // MOTION_H
|
||||||
|
|
|
@ -64,13 +64,12 @@
|
||||||
#include "../module/temperature.h"
|
#include "../module/temperature.h"
|
||||||
#include "../lcd/ultralcd.h"
|
#include "../lcd/ultralcd.h"
|
||||||
#include "../core/language.h"
|
#include "../core/language.h"
|
||||||
#include "../feature/ubl/ubl.h"
|
|
||||||
#include "../gcode/parser.h"
|
#include "../gcode/parser.h"
|
||||||
|
|
||||||
#include "../Marlin.h"
|
#include "../Marlin.h"
|
||||||
|
|
||||||
#if ENABLED(MESH_BED_LEVELING)
|
#if HAS_LEVELING
|
||||||
#include "../feature/mbl/mesh_bed_leveling.h"
|
#include "../feature/bedlevel/bedlevel.h"
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
Planner planner;
|
Planner planner;
|
||||||
|
@ -107,12 +106,11 @@ float Planner::min_feedrate_mm_s,
|
||||||
Planner::max_jerk[XYZE], // The largest speed change requiring no acceleration
|
Planner::max_jerk[XYZE], // The largest speed change requiring no acceleration
|
||||||
Planner::min_travel_feedrate_mm_s;
|
Planner::min_travel_feedrate_mm_s;
|
||||||
|
|
||||||
#if HAS_ABL
|
#if OLDSCHOOL_ABL
|
||||||
bool Planner::abl_enabled = false; // Flag that auto bed leveling is enabled
|
bool Planner::abl_enabled = false; // Flag that auto bed leveling is enabled
|
||||||
#endif
|
#if ABL_PLANAR
|
||||||
|
matrix_3x3 Planner::bed_level_matrix; // Transform to compensate for bed level
|
||||||
#if ABL_PLANAR
|
#endif
|
||||||
matrix_3x3 Planner::bed_level_matrix; // Transform to compensate for bed level
|
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#if ENABLED(ENABLE_LEVELING_FADE_HEIGHT)
|
#if ENABLED(ENABLE_LEVELING_FADE_HEIGHT)
|
||||||
|
@ -546,7 +544,7 @@ void Planner::check_axes_activity() {
|
||||||
#endif // FADE
|
#endif // FADE
|
||||||
#endif // UBL
|
#endif // UBL
|
||||||
|
|
||||||
#if HAS_ABL
|
#if OLDSCHOOL_ABL
|
||||||
if (!abl_enabled) return;
|
if (!abl_enabled) return;
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
@ -634,7 +632,7 @@ void Planner::check_axes_activity() {
|
||||||
|
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#if HAS_ABL
|
#if OLDSCHOOL_ABL
|
||||||
if (!abl_enabled) return;
|
if (!abl_enabled) return;
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
|
|
@ -34,6 +34,12 @@
|
||||||
|
|
||||||
#include "../Marlin.h"
|
#include "../Marlin.h"
|
||||||
|
|
||||||
|
#include "motion.h"
|
||||||
|
|
||||||
|
#if ENABLED(DELTA)
|
||||||
|
#include "delta.h"
|
||||||
|
#endif
|
||||||
|
|
||||||
#if HAS_ABL
|
#if HAS_ABL
|
||||||
#include "../libs/vector_3.h"
|
#include "../libs/vector_3.h"
|
||||||
#endif
|
#endif
|
||||||
|
@ -159,7 +165,7 @@ class Planner {
|
||||||
max_jerk[XYZE], // The largest speed change requiring no acceleration
|
max_jerk[XYZE], // The largest speed change requiring no acceleration
|
||||||
min_travel_feedrate_mm_s;
|
min_travel_feedrate_mm_s;
|
||||||
|
|
||||||
#if HAS_ABL
|
#if OLDSCHOOL_ABL
|
||||||
static bool abl_enabled; // Flag that bed leveling is enabled
|
static bool abl_enabled; // Flag that bed leveling is enabled
|
||||||
#if ABL_PLANAR
|
#if ABL_PLANAR
|
||||||
static matrix_3x3 bed_level_matrix; // Transform to compensate for bed level
|
static matrix_3x3 bed_level_matrix; // Transform to compensate for bed level
|
||||||
|
|
709
Marlin/src/module/probe.cpp
Normal file
709
Marlin/src/module/probe.cpp
Normal file
|
@ -0,0 +1,709 @@
|
||||||
|
/**
|
||||||
|
* Marlin 3D Printer Firmware
|
||||||
|
* Copyright (C) 2016 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
|
||||||
|
*
|
||||||
|
* Based on Sprinter and grbl.
|
||||||
|
* Copyright (C) 2011 Camiel Gubbels / Erik van der Zalm
|
||||||
|
*
|
||||||
|
* This program is free software: you can redistribute it and/or modify
|
||||||
|
* it under the terms of the GNU General Public License as published by
|
||||||
|
* the Free Software Foundation, either version 3 of the License, or
|
||||||
|
* (at your option) any later version.
|
||||||
|
*
|
||||||
|
* This program is distributed in the hope that it will be useful,
|
||||||
|
* but WITHOUT ANY WARRANTY; without even the implied warranty of
|
||||||
|
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
|
||||||
|
* GNU General Public License for more details.
|
||||||
|
*
|
||||||
|
* You should have received a copy of the GNU General Public License
|
||||||
|
* along with this program. If not, see <http://www.gnu.org/licenses/>.
|
||||||
|
*
|
||||||
|
*/
|
||||||
|
|
||||||
|
/**
|
||||||
|
* probe.cpp
|
||||||
|
*/
|
||||||
|
|
||||||
|
#include "../inc/MarlinConfig.h"
|
||||||
|
|
||||||
|
#if HAS_BED_PROBE
|
||||||
|
|
||||||
|
#include "probe.h"
|
||||||
|
#include "motion.h"
|
||||||
|
#include "temperature.h"
|
||||||
|
#include "endstops.h"
|
||||||
|
|
||||||
|
#include "../gcode/gcode.h"
|
||||||
|
#include "../lcd/ultralcd.h"
|
||||||
|
|
||||||
|
#include "../Marlin.h"
|
||||||
|
|
||||||
|
#if HAS_LEVELING
|
||||||
|
#include "../feature/bedlevel/bedlevel.h"
|
||||||
|
#endif
|
||||||
|
|
||||||
|
#if ENABLED(DELTA)
|
||||||
|
#include "../module/delta.h"
|
||||||
|
#endif
|
||||||
|
|
||||||
|
float zprobe_zoffset; // Initialized by settings.load()
|
||||||
|
|
||||||
|
#if HAS_Z_SERVO_ENDSTOP
|
||||||
|
const int z_servo_angle[2] = Z_SERVO_ANGLES;
|
||||||
|
#endif
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Raise Z to a minimum height to make room for a probe to move
|
||||||
|
*/
|
||||||
|
inline void do_probe_raise(const float z_raise) {
|
||||||
|
#if ENABLED(DEBUG_LEVELING_FEATURE)
|
||||||
|
if (DEBUGGING(LEVELING)) {
|
||||||
|
SERIAL_ECHOPAIR("do_probe_raise(", z_raise);
|
||||||
|
SERIAL_CHAR(')');
|
||||||
|
SERIAL_EOL();
|
||||||
|
}
|
||||||
|
#endif
|
||||||
|
|
||||||
|
float z_dest = z_raise;
|
||||||
|
if (zprobe_zoffset < 0) z_dest -= zprobe_zoffset;
|
||||||
|
|
||||||
|
if (z_dest > current_position[Z_AXIS])
|
||||||
|
do_blocking_move_to_z(z_dest);
|
||||||
|
}
|
||||||
|
|
||||||
|
#if ENABLED(Z_PROBE_SLED)
|
||||||
|
|
||||||
|
#ifndef SLED_DOCKING_OFFSET
|
||||||
|
#define SLED_DOCKING_OFFSET 0
|
||||||
|
#endif
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Method to dock/undock a sled designed by Charles Bell.
|
||||||
|
*
|
||||||
|
* stow[in] If false, move to MAX_X and engage the solenoid
|
||||||
|
* If true, move to MAX_X and release the solenoid
|
||||||
|
*/
|
||||||
|
static void dock_sled(bool stow) {
|
||||||
|
#if ENABLED(DEBUG_LEVELING_FEATURE)
|
||||||
|
if (DEBUGGING(LEVELING)) {
|
||||||
|
SERIAL_ECHOPAIR("dock_sled(", stow);
|
||||||
|
SERIAL_CHAR(')');
|
||||||
|
SERIAL_EOL();
|
||||||
|
}
|
||||||
|
#endif
|
||||||
|
|
||||||
|
// Dock sled a bit closer to ensure proper capturing
|
||||||
|
do_blocking_move_to_x(X_MAX_POS + SLED_DOCKING_OFFSET - ((stow) ? 1 : 0));
|
||||||
|
|
||||||
|
#if HAS_SOLENOID_1 && DISABLED(EXT_SOLENOID)
|
||||||
|
WRITE(SOL1_PIN, !stow); // switch solenoid
|
||||||
|
#endif
|
||||||
|
}
|
||||||
|
|
||||||
|
#elif ENABLED(Z_PROBE_ALLEN_KEY)
|
||||||
|
|
||||||
|
FORCE_INLINE void do_blocking_move_to(const float logical[XYZ], const float &fr_mm_s) {
|
||||||
|
do_blocking_move_to(logical[X_AXIS], logical[Y_AXIS], logical[Z_AXIS], fr_mm_s);
|
||||||
|
}
|
||||||
|
|
||||||
|
void run_deploy_moves_script() {
|
||||||
|
#if defined(Z_PROBE_ALLEN_KEY_DEPLOY_1_X) || defined(Z_PROBE_ALLEN_KEY_DEPLOY_1_Y) || defined(Z_PROBE_ALLEN_KEY_DEPLOY_1_Z)
|
||||||
|
#ifndef Z_PROBE_ALLEN_KEY_DEPLOY_1_X
|
||||||
|
#define Z_PROBE_ALLEN_KEY_DEPLOY_1_X current_position[X_AXIS]
|
||||||
|
#endif
|
||||||
|
#ifndef Z_PROBE_ALLEN_KEY_DEPLOY_1_Y
|
||||||
|
#define Z_PROBE_ALLEN_KEY_DEPLOY_1_Y current_position[Y_AXIS]
|
||||||
|
#endif
|
||||||
|
#ifndef Z_PROBE_ALLEN_KEY_DEPLOY_1_Z
|
||||||
|
#define Z_PROBE_ALLEN_KEY_DEPLOY_1_Z current_position[Z_AXIS]
|
||||||
|
#endif
|
||||||
|
#ifndef Z_PROBE_ALLEN_KEY_DEPLOY_1_FEEDRATE
|
||||||
|
#define Z_PROBE_ALLEN_KEY_DEPLOY_1_FEEDRATE 0.0
|
||||||
|
#endif
|
||||||
|
const float deploy_1[] = { Z_PROBE_ALLEN_KEY_DEPLOY_1_X, Z_PROBE_ALLEN_KEY_DEPLOY_1_Y, Z_PROBE_ALLEN_KEY_DEPLOY_1_Z };
|
||||||
|
do_blocking_move_to(deploy_1, MMM_TO_MMS(Z_PROBE_ALLEN_KEY_DEPLOY_1_FEEDRATE));
|
||||||
|
#endif
|
||||||
|
#if defined(Z_PROBE_ALLEN_KEY_DEPLOY_2_X) || defined(Z_PROBE_ALLEN_KEY_DEPLOY_2_Y) || defined(Z_PROBE_ALLEN_KEY_DEPLOY_2_Z)
|
||||||
|
#ifndef Z_PROBE_ALLEN_KEY_DEPLOY_2_X
|
||||||
|
#define Z_PROBE_ALLEN_KEY_DEPLOY_2_X current_position[X_AXIS]
|
||||||
|
#endif
|
||||||
|
#ifndef Z_PROBE_ALLEN_KEY_DEPLOY_2_Y
|
||||||
|
#define Z_PROBE_ALLEN_KEY_DEPLOY_2_Y current_position[Y_AXIS]
|
||||||
|
#endif
|
||||||
|
#ifndef Z_PROBE_ALLEN_KEY_DEPLOY_2_Z
|
||||||
|
#define Z_PROBE_ALLEN_KEY_DEPLOY_2_Z current_position[Z_AXIS]
|
||||||
|
#endif
|
||||||
|
#ifndef Z_PROBE_ALLEN_KEY_DEPLOY_2_FEEDRATE
|
||||||
|
#define Z_PROBE_ALLEN_KEY_DEPLOY_2_FEEDRATE 0.0
|
||||||
|
#endif
|
||||||
|
const float deploy_2[] = { Z_PROBE_ALLEN_KEY_DEPLOY_2_X, Z_PROBE_ALLEN_KEY_DEPLOY_2_Y, Z_PROBE_ALLEN_KEY_DEPLOY_2_Z };
|
||||||
|
do_blocking_move_to(deploy_2, MMM_TO_MMS(Z_PROBE_ALLEN_KEY_DEPLOY_2_FEEDRATE));
|
||||||
|
#endif
|
||||||
|
#if defined(Z_PROBE_ALLEN_KEY_DEPLOY_3_X) || defined(Z_PROBE_ALLEN_KEY_DEPLOY_3_Y) || defined(Z_PROBE_ALLEN_KEY_DEPLOY_3_Z)
|
||||||
|
#ifndef Z_PROBE_ALLEN_KEY_DEPLOY_3_X
|
||||||
|
#define Z_PROBE_ALLEN_KEY_DEPLOY_3_X current_position[X_AXIS]
|
||||||
|
#endif
|
||||||
|
#ifndef Z_PROBE_ALLEN_KEY_DEPLOY_3_Y
|
||||||
|
#define Z_PROBE_ALLEN_KEY_DEPLOY_3_Y current_position[Y_AXIS]
|
||||||
|
#endif
|
||||||
|
#ifndef Z_PROBE_ALLEN_KEY_DEPLOY_3_Z
|
||||||
|
#define Z_PROBE_ALLEN_KEY_DEPLOY_3_Z current_position[Z_AXIS]
|
||||||
|
#endif
|
||||||
|
#ifndef Z_PROBE_ALLEN_KEY_DEPLOY_3_FEEDRATE
|
||||||
|
#define Z_PROBE_ALLEN_KEY_DEPLOY_3_FEEDRATE 0.0
|
||||||
|
#endif
|
||||||
|
const float deploy_3[] = { Z_PROBE_ALLEN_KEY_DEPLOY_3_X, Z_PROBE_ALLEN_KEY_DEPLOY_3_Y, Z_PROBE_ALLEN_KEY_DEPLOY_3_Z };
|
||||||
|
do_blocking_move_to(deploy_3, MMM_TO_MMS(Z_PROBE_ALLEN_KEY_DEPLOY_3_FEEDRATE));
|
||||||
|
#endif
|
||||||
|
#if defined(Z_PROBE_ALLEN_KEY_DEPLOY_4_X) || defined(Z_PROBE_ALLEN_KEY_DEPLOY_4_Y) || defined(Z_PROBE_ALLEN_KEY_DEPLOY_4_Z)
|
||||||
|
#ifndef Z_PROBE_ALLEN_KEY_DEPLOY_4_X
|
||||||
|
#define Z_PROBE_ALLEN_KEY_DEPLOY_4_X current_position[X_AXIS]
|
||||||
|
#endif
|
||||||
|
#ifndef Z_PROBE_ALLEN_KEY_DEPLOY_4_Y
|
||||||
|
#define Z_PROBE_ALLEN_KEY_DEPLOY_4_Y current_position[Y_AXIS]
|
||||||
|
#endif
|
||||||
|
#ifndef Z_PROBE_ALLEN_KEY_DEPLOY_4_Z
|
||||||
|
#define Z_PROBE_ALLEN_KEY_DEPLOY_4_Z current_position[Z_AXIS]
|
||||||
|
#endif
|
||||||
|
#ifndef Z_PROBE_ALLEN_KEY_DEPLOY_4_FEEDRATE
|
||||||
|
#define Z_PROBE_ALLEN_KEY_DEPLOY_4_FEEDRATE 0.0
|
||||||
|
#endif
|
||||||
|
const float deploy_4[] = { Z_PROBE_ALLEN_KEY_DEPLOY_4_X, Z_PROBE_ALLEN_KEY_DEPLOY_4_Y, Z_PROBE_ALLEN_KEY_DEPLOY_4_Z };
|
||||||
|
do_blocking_move_to(deploy_4, MMM_TO_MMS(Z_PROBE_ALLEN_KEY_DEPLOY_4_FEEDRATE));
|
||||||
|
#endif
|
||||||
|
#if defined(Z_PROBE_ALLEN_KEY_DEPLOY_5_X) || defined(Z_PROBE_ALLEN_KEY_DEPLOY_5_Y) || defined(Z_PROBE_ALLEN_KEY_DEPLOY_5_Z)
|
||||||
|
#ifndef Z_PROBE_ALLEN_KEY_DEPLOY_5_X
|
||||||
|
#define Z_PROBE_ALLEN_KEY_DEPLOY_5_X current_position[X_AXIS]
|
||||||
|
#endif
|
||||||
|
#ifndef Z_PROBE_ALLEN_KEY_DEPLOY_5_Y
|
||||||
|
#define Z_PROBE_ALLEN_KEY_DEPLOY_5_Y current_position[Y_AXIS]
|
||||||
|
#endif
|
||||||
|
#ifndef Z_PROBE_ALLEN_KEY_DEPLOY_5_Z
|
||||||
|
#define Z_PROBE_ALLEN_KEY_DEPLOY_5_Z current_position[Z_AXIS]
|
||||||
|
#endif
|
||||||
|
#ifndef Z_PROBE_ALLEN_KEY_DEPLOY_5_FEEDRATE
|
||||||
|
#define Z_PROBE_ALLEN_KEY_DEPLOY_5_FEEDRATE 0.0
|
||||||
|
#endif
|
||||||
|
const float deploy_5[] = { Z_PROBE_ALLEN_KEY_DEPLOY_5_X, Z_PROBE_ALLEN_KEY_DEPLOY_5_Y, Z_PROBE_ALLEN_KEY_DEPLOY_5_Z };
|
||||||
|
do_blocking_move_to(deploy_5, MMM_TO_MMS(Z_PROBE_ALLEN_KEY_DEPLOY_5_FEEDRATE));
|
||||||
|
#endif
|
||||||
|
}
|
||||||
|
|
||||||
|
void run_stow_moves_script() {
|
||||||
|
#if defined(Z_PROBE_ALLEN_KEY_STOW_1_X) || defined(Z_PROBE_ALLEN_KEY_STOW_1_Y) || defined(Z_PROBE_ALLEN_KEY_STOW_1_Z)
|
||||||
|
#ifndef Z_PROBE_ALLEN_KEY_STOW_1_X
|
||||||
|
#define Z_PROBE_ALLEN_KEY_STOW_1_X current_position[X_AXIS]
|
||||||
|
#endif
|
||||||
|
#ifndef Z_PROBE_ALLEN_KEY_STOW_1_Y
|
||||||
|
#define Z_PROBE_ALLEN_KEY_STOW_1_Y current_position[Y_AXIS]
|
||||||
|
#endif
|
||||||
|
#ifndef Z_PROBE_ALLEN_KEY_STOW_1_Z
|
||||||
|
#define Z_PROBE_ALLEN_KEY_STOW_1_Z current_position[Z_AXIS]
|
||||||
|
#endif
|
||||||
|
#ifndef Z_PROBE_ALLEN_KEY_STOW_1_FEEDRATE
|
||||||
|
#define Z_PROBE_ALLEN_KEY_STOW_1_FEEDRATE 0.0
|
||||||
|
#endif
|
||||||
|
const float stow_1[] = { Z_PROBE_ALLEN_KEY_STOW_1_X, Z_PROBE_ALLEN_KEY_STOW_1_Y, Z_PROBE_ALLEN_KEY_STOW_1_Z };
|
||||||
|
do_blocking_move_to(stow_1, MMM_TO_MMS(Z_PROBE_ALLEN_KEY_STOW_1_FEEDRATE));
|
||||||
|
#endif
|
||||||
|
#if defined(Z_PROBE_ALLEN_KEY_STOW_2_X) || defined(Z_PROBE_ALLEN_KEY_STOW_2_Y) || defined(Z_PROBE_ALLEN_KEY_STOW_2_Z)
|
||||||
|
#ifndef Z_PROBE_ALLEN_KEY_STOW_2_X
|
||||||
|
#define Z_PROBE_ALLEN_KEY_STOW_2_X current_position[X_AXIS]
|
||||||
|
#endif
|
||||||
|
#ifndef Z_PROBE_ALLEN_KEY_STOW_2_Y
|
||||||
|
#define Z_PROBE_ALLEN_KEY_STOW_2_Y current_position[Y_AXIS]
|
||||||
|
#endif
|
||||||
|
#ifndef Z_PROBE_ALLEN_KEY_STOW_2_Z
|
||||||
|
#define Z_PROBE_ALLEN_KEY_STOW_2_Z current_position[Z_AXIS]
|
||||||
|
#endif
|
||||||
|
#ifndef Z_PROBE_ALLEN_KEY_STOW_2_FEEDRATE
|
||||||
|
#define Z_PROBE_ALLEN_KEY_STOW_2_FEEDRATE 0.0
|
||||||
|
#endif
|
||||||
|
const float stow_2[] = { Z_PROBE_ALLEN_KEY_STOW_2_X, Z_PROBE_ALLEN_KEY_STOW_2_Y, Z_PROBE_ALLEN_KEY_STOW_2_Z };
|
||||||
|
do_blocking_move_to(stow_2, MMM_TO_MMS(Z_PROBE_ALLEN_KEY_STOW_2_FEEDRATE));
|
||||||
|
#endif
|
||||||
|
#if defined(Z_PROBE_ALLEN_KEY_STOW_3_X) || defined(Z_PROBE_ALLEN_KEY_STOW_3_Y) || defined(Z_PROBE_ALLEN_KEY_STOW_3_Z)
|
||||||
|
#ifndef Z_PROBE_ALLEN_KEY_STOW_3_X
|
||||||
|
#define Z_PROBE_ALLEN_KEY_STOW_3_X current_position[X_AXIS]
|
||||||
|
#endif
|
||||||
|
#ifndef Z_PROBE_ALLEN_KEY_STOW_3_Y
|
||||||
|
#define Z_PROBE_ALLEN_KEY_STOW_3_Y current_position[Y_AXIS]
|
||||||
|
#endif
|
||||||
|
#ifndef Z_PROBE_ALLEN_KEY_STOW_3_Z
|
||||||
|
#define Z_PROBE_ALLEN_KEY_STOW_3_Z current_position[Z_AXIS]
|
||||||
|
#endif
|
||||||
|
#ifndef Z_PROBE_ALLEN_KEY_STOW_3_FEEDRATE
|
||||||
|
#define Z_PROBE_ALLEN_KEY_STOW_3_FEEDRATE 0.0
|
||||||
|
#endif
|
||||||
|
const float stow_3[] = { Z_PROBE_ALLEN_KEY_STOW_3_X, Z_PROBE_ALLEN_KEY_STOW_3_Y, Z_PROBE_ALLEN_KEY_STOW_3_Z };
|
||||||
|
do_blocking_move_to(stow_3, MMM_TO_MMS(Z_PROBE_ALLEN_KEY_STOW_3_FEEDRATE));
|
||||||
|
#endif
|
||||||
|
#if defined(Z_PROBE_ALLEN_KEY_STOW_4_X) || defined(Z_PROBE_ALLEN_KEY_STOW_4_Y) || defined(Z_PROBE_ALLEN_KEY_STOW_4_Z)
|
||||||
|
#ifndef Z_PROBE_ALLEN_KEY_STOW_4_X
|
||||||
|
#define Z_PROBE_ALLEN_KEY_STOW_4_X current_position[X_AXIS]
|
||||||
|
#endif
|
||||||
|
#ifndef Z_PROBE_ALLEN_KEY_STOW_4_Y
|
||||||
|
#define Z_PROBE_ALLEN_KEY_STOW_4_Y current_position[Y_AXIS]
|
||||||
|
#endif
|
||||||
|
#ifndef Z_PROBE_ALLEN_KEY_STOW_4_Z
|
||||||
|
#define Z_PROBE_ALLEN_KEY_STOW_4_Z current_position[Z_AXIS]
|
||||||
|
#endif
|
||||||
|
#ifndef Z_PROBE_ALLEN_KEY_STOW_4_FEEDRATE
|
||||||
|
#define Z_PROBE_ALLEN_KEY_STOW_4_FEEDRATE 0.0
|
||||||
|
#endif
|
||||||
|
const float stow_4[] = { Z_PROBE_ALLEN_KEY_STOW_4_X, Z_PROBE_ALLEN_KEY_STOW_4_Y, Z_PROBE_ALLEN_KEY_STOW_4_Z };
|
||||||
|
do_blocking_move_to(stow_4, MMM_TO_MMS(Z_PROBE_ALLEN_KEY_STOW_4_FEEDRATE));
|
||||||
|
#endif
|
||||||
|
#if defined(Z_PROBE_ALLEN_KEY_STOW_5_X) || defined(Z_PROBE_ALLEN_KEY_STOW_5_Y) || defined(Z_PROBE_ALLEN_KEY_STOW_5_Z)
|
||||||
|
#ifndef Z_PROBE_ALLEN_KEY_STOW_5_X
|
||||||
|
#define Z_PROBE_ALLEN_KEY_STOW_5_X current_position[X_AXIS]
|
||||||
|
#endif
|
||||||
|
#ifndef Z_PROBE_ALLEN_KEY_STOW_5_Y
|
||||||
|
#define Z_PROBE_ALLEN_KEY_STOW_5_Y current_position[Y_AXIS]
|
||||||
|
#endif
|
||||||
|
#ifndef Z_PROBE_ALLEN_KEY_STOW_5_Z
|
||||||
|
#define Z_PROBE_ALLEN_KEY_STOW_5_Z current_position[Z_AXIS]
|
||||||
|
#endif
|
||||||
|
#ifndef Z_PROBE_ALLEN_KEY_STOW_5_FEEDRATE
|
||||||
|
#define Z_PROBE_ALLEN_KEY_STOW_5_FEEDRATE 0.0
|
||||||
|
#endif
|
||||||
|
const float stow_5[] = { Z_PROBE_ALLEN_KEY_STOW_5_X, Z_PROBE_ALLEN_KEY_STOW_5_Y, Z_PROBE_ALLEN_KEY_STOW_5_Z };
|
||||||
|
do_blocking_move_to(stow_5, MMM_TO_MMS(Z_PROBE_ALLEN_KEY_STOW_5_FEEDRATE));
|
||||||
|
#endif
|
||||||
|
}
|
||||||
|
|
||||||
|
#endif
|
||||||
|
|
||||||
|
#if ENABLED(PROBING_FANS_OFF)
|
||||||
|
|
||||||
|
void fans_pause(const bool p) {
|
||||||
|
if (p != fans_paused) {
|
||||||
|
fans_paused = p;
|
||||||
|
if (p)
|
||||||
|
for (uint8_t x = 0; x < FAN_COUNT; x++) {
|
||||||
|
paused_fanSpeeds[x] = fanSpeeds[x];
|
||||||
|
fanSpeeds[x] = 0;
|
||||||
|
}
|
||||||
|
else
|
||||||
|
for (uint8_t x = 0; x < FAN_COUNT; x++)
|
||||||
|
fanSpeeds[x] = paused_fanSpeeds[x];
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
#endif // PROBING_FANS_OFF
|
||||||
|
|
||||||
|
#if QUIET_PROBING
|
||||||
|
void probing_pause(const bool p) {
|
||||||
|
#if ENABLED(PROBING_HEATERS_OFF)
|
||||||
|
thermalManager.pause(p);
|
||||||
|
#endif
|
||||||
|
#if ENABLED(PROBING_FANS_OFF)
|
||||||
|
fans_pause(p);
|
||||||
|
#endif
|
||||||
|
if (p) safe_delay(
|
||||||
|
#if DELAY_BEFORE_PROBING > 25
|
||||||
|
DELAY_BEFORE_PROBING
|
||||||
|
#else
|
||||||
|
25
|
||||||
|
#endif
|
||||||
|
);
|
||||||
|
}
|
||||||
|
#endif // QUIET_PROBING
|
||||||
|
|
||||||
|
#if ENABLED(BLTOUCH)
|
||||||
|
|
||||||
|
void bltouch_command(const int angle) {
|
||||||
|
MOVE_SERVO(Z_ENDSTOP_SERVO_NR, angle); // Give the BL-Touch the command and wait
|
||||||
|
safe_delay(BLTOUCH_DELAY);
|
||||||
|
}
|
||||||
|
|
||||||
|
bool set_bltouch_deployed(const bool deploy) {
|
||||||
|
if (deploy && TEST_BLTOUCH()) { // If BL-Touch says it's triggered
|
||||||
|
bltouch_command(BLTOUCH_RESET); // try to reset it.
|
||||||
|
bltouch_command(BLTOUCH_DEPLOY); // Also needs to deploy and stow to
|
||||||
|
bltouch_command(BLTOUCH_STOW); // clear the triggered condition.
|
||||||
|
safe_delay(1500); // Wait for internal self-test to complete.
|
||||||
|
// (Measured completion time was 0.65 seconds
|
||||||
|
// after reset, deploy, and stow sequence)
|
||||||
|
if (TEST_BLTOUCH()) { // If it still claims to be triggered...
|
||||||
|
SERIAL_ERROR_START();
|
||||||
|
SERIAL_ERRORLNPGM(MSG_STOP_BLTOUCH);
|
||||||
|
stop(); // punt!
|
||||||
|
return true;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
bltouch_command(deploy ? BLTOUCH_DEPLOY : BLTOUCH_STOW);
|
||||||
|
|
||||||
|
#if ENABLED(DEBUG_LEVELING_FEATURE)
|
||||||
|
if (DEBUGGING(LEVELING)) {
|
||||||
|
SERIAL_ECHOPAIR("set_bltouch_deployed(", deploy);
|
||||||
|
SERIAL_CHAR(')');
|
||||||
|
SERIAL_EOL();
|
||||||
|
}
|
||||||
|
#endif
|
||||||
|
|
||||||
|
return false;
|
||||||
|
}
|
||||||
|
|
||||||
|
#endif // BLTOUCH
|
||||||
|
|
||||||
|
// returns false for ok and true for failure
|
||||||
|
bool set_probe_deployed(const bool deploy) {
|
||||||
|
|
||||||
|
// Can be extended to servo probes, if needed.
|
||||||
|
#if ENABLED(PROBE_IS_TRIGGERED_WHEN_STOWED_TEST)
|
||||||
|
#if ENABLED(Z_MIN_PROBE_ENDSTOP)
|
||||||
|
#define _TRIGGERED_WHEN_STOWED_TEST (READ(Z_MIN_PROBE_PIN) != Z_MIN_PROBE_ENDSTOP_INVERTING)
|
||||||
|
#else
|
||||||
|
#define _TRIGGERED_WHEN_STOWED_TEST (READ(Z_MIN_PIN) != Z_MIN_ENDSTOP_INVERTING)
|
||||||
|
#endif
|
||||||
|
#endif
|
||||||
|
|
||||||
|
#if ENABLED(DEBUG_LEVELING_FEATURE)
|
||||||
|
if (DEBUGGING(LEVELING)) {
|
||||||
|
DEBUG_POS("set_probe_deployed", current_position);
|
||||||
|
SERIAL_ECHOLNPAIR("deploy: ", deploy);
|
||||||
|
}
|
||||||
|
#endif
|
||||||
|
|
||||||
|
if (endstops.z_probe_enabled == deploy) return false;
|
||||||
|
|
||||||
|
// Make room for probe
|
||||||
|
do_probe_raise(_Z_CLEARANCE_DEPLOY_PROBE);
|
||||||
|
|
||||||
|
#if ENABLED(Z_PROBE_SLED) || ENABLED(Z_PROBE_ALLEN_KEY)
|
||||||
|
#if ENABLED(Z_PROBE_SLED)
|
||||||
|
#define _AUE_ARGS true, false, false
|
||||||
|
#else
|
||||||
|
#define _AUE_ARGS
|
||||||
|
#endif
|
||||||
|
if (axis_unhomed_error(_AUE_ARGS)) {
|
||||||
|
SERIAL_ERROR_START();
|
||||||
|
SERIAL_ERRORLNPGM(MSG_STOP_UNHOMED);
|
||||||
|
stop();
|
||||||
|
return true;
|
||||||
|
}
|
||||||
|
#endif
|
||||||
|
|
||||||
|
const float oldXpos = current_position[X_AXIS],
|
||||||
|
oldYpos = current_position[Y_AXIS];
|
||||||
|
|
||||||
|
#ifdef _TRIGGERED_WHEN_STOWED_TEST
|
||||||
|
|
||||||
|
// If endstop is already false, the Z probe is deployed
|
||||||
|
if (_TRIGGERED_WHEN_STOWED_TEST == deploy) { // closed after the probe specific actions.
|
||||||
|
// Would a goto be less ugly?
|
||||||
|
//while (!_TRIGGERED_WHEN_STOWED_TEST) idle(); // would offer the opportunity
|
||||||
|
// for a triggered when stowed manual probe.
|
||||||
|
|
||||||
|
if (!deploy) endstops.enable_z_probe(false); // Switch off triggered when stowed probes early
|
||||||
|
// otherwise an Allen-Key probe can't be stowed.
|
||||||
|
#endif
|
||||||
|
|
||||||
|
#if ENABLED(SOLENOID_PROBE)
|
||||||
|
|
||||||
|
#if HAS_SOLENOID_1
|
||||||
|
WRITE(SOL1_PIN, deploy);
|
||||||
|
#endif
|
||||||
|
|
||||||
|
#elif ENABLED(Z_PROBE_SLED)
|
||||||
|
|
||||||
|
dock_sled(!deploy);
|
||||||
|
|
||||||
|
#elif HAS_Z_SERVO_ENDSTOP && DISABLED(BLTOUCH)
|
||||||
|
|
||||||
|
MOVE_SERVO(Z_ENDSTOP_SERVO_NR, z_servo_angle[deploy ? 0 : 1]);
|
||||||
|
|
||||||
|
#elif ENABLED(Z_PROBE_ALLEN_KEY)
|
||||||
|
|
||||||
|
deploy ? run_deploy_moves_script() : run_stow_moves_script();
|
||||||
|
|
||||||
|
#endif
|
||||||
|
|
||||||
|
#ifdef _TRIGGERED_WHEN_STOWED_TEST
|
||||||
|
} // _TRIGGERED_WHEN_STOWED_TEST == deploy
|
||||||
|
|
||||||
|
if (_TRIGGERED_WHEN_STOWED_TEST == deploy) { // State hasn't changed?
|
||||||
|
|
||||||
|
if (IsRunning()) {
|
||||||
|
SERIAL_ERROR_START();
|
||||||
|
SERIAL_ERRORLNPGM("Z-Probe failed");
|
||||||
|
LCD_ALERTMESSAGEPGM("Err: ZPROBE");
|
||||||
|
}
|
||||||
|
stop();
|
||||||
|
return true;
|
||||||
|
|
||||||
|
} // _TRIGGERED_WHEN_STOWED_TEST == deploy
|
||||||
|
|
||||||
|
#endif
|
||||||
|
|
||||||
|
do_blocking_move_to(oldXpos, oldYpos, current_position[Z_AXIS]); // return to position before deploy
|
||||||
|
endstops.enable_z_probe(deploy);
|
||||||
|
return false;
|
||||||
|
}
|
||||||
|
|
||||||
|
/**
|
||||||
|
* @brief Used by run_z_probe to do a single Z probe move.
|
||||||
|
*
|
||||||
|
* @param z Z destination
|
||||||
|
* @param fr_mm_s Feedrate in mm/s
|
||||||
|
* @return true to indicate an error
|
||||||
|
*/
|
||||||
|
static bool do_probe_move(const float z, const float fr_mm_m) {
|
||||||
|
#if ENABLED(DEBUG_LEVELING_FEATURE)
|
||||||
|
if (DEBUGGING(LEVELING)) DEBUG_POS(">>> do_probe_move", current_position);
|
||||||
|
#endif
|
||||||
|
|
||||||
|
// Deploy BLTouch at the start of any probe
|
||||||
|
#if ENABLED(BLTOUCH)
|
||||||
|
if (set_bltouch_deployed(true)) return true;
|
||||||
|
#endif
|
||||||
|
|
||||||
|
#if QUIET_PROBING
|
||||||
|
probing_pause(true);
|
||||||
|
#endif
|
||||||
|
|
||||||
|
// Move down until probe triggered
|
||||||
|
do_blocking_move_to_z(z, MMM_TO_MMS(fr_mm_m));
|
||||||
|
|
||||||
|
// Check to see if the probe was triggered
|
||||||
|
const bool probe_triggered = TEST(Endstops::endstop_hit_bits,
|
||||||
|
#if ENABLED(Z_MIN_PROBE_USES_Z_MIN_ENDSTOP_PIN)
|
||||||
|
Z_MIN
|
||||||
|
#else
|
||||||
|
Z_MIN_PROBE
|
||||||
|
#endif
|
||||||
|
);
|
||||||
|
|
||||||
|
#if QUIET_PROBING
|
||||||
|
probing_pause(false);
|
||||||
|
#endif
|
||||||
|
|
||||||
|
// Retract BLTouch immediately after a probe if it was triggered
|
||||||
|
#if ENABLED(BLTOUCH)
|
||||||
|
if (probe_triggered && set_bltouch_deployed(false)) return true;
|
||||||
|
#endif
|
||||||
|
|
||||||
|
// Clear endstop flags
|
||||||
|
endstops.hit_on_purpose();
|
||||||
|
|
||||||
|
// Get Z where the steppers were interrupted
|
||||||
|
set_current_from_steppers_for_axis(Z_AXIS);
|
||||||
|
|
||||||
|
// Tell the planner where we actually are
|
||||||
|
SYNC_PLAN_POSITION_KINEMATIC();
|
||||||
|
|
||||||
|
#if ENABLED(DEBUG_LEVELING_FEATURE)
|
||||||
|
if (DEBUGGING(LEVELING)) DEBUG_POS("<<< do_probe_move", current_position);
|
||||||
|
#endif
|
||||||
|
|
||||||
|
return !probe_triggered;
|
||||||
|
}
|
||||||
|
|
||||||
|
/**
|
||||||
|
* @details Used by probe_pt to do a single Z probe.
|
||||||
|
* Leaves current_position[Z_AXIS] at the height where the probe triggered.
|
||||||
|
*
|
||||||
|
* @param short_move Flag for a shorter probe move towards the bed
|
||||||
|
* @return The raw Z position where the probe was triggered
|
||||||
|
*/
|
||||||
|
static float run_z_probe(const bool short_move=true) {
|
||||||
|
|
||||||
|
#if ENABLED(DEBUG_LEVELING_FEATURE)
|
||||||
|
if (DEBUGGING(LEVELING)) DEBUG_POS(">>> run_z_probe", current_position);
|
||||||
|
#endif
|
||||||
|
|
||||||
|
// Prevent stepper_inactive_time from running out and EXTRUDER_RUNOUT_PREVENT from extruding
|
||||||
|
gcode.refresh_cmd_timeout();
|
||||||
|
|
||||||
|
#if ENABLED(PROBE_DOUBLE_TOUCH)
|
||||||
|
|
||||||
|
// Do a first probe at the fast speed
|
||||||
|
if (do_probe_move(-10, Z_PROBE_SPEED_FAST)) return NAN;
|
||||||
|
|
||||||
|
#if ENABLED(DEBUG_LEVELING_FEATURE)
|
||||||
|
float first_probe_z = current_position[Z_AXIS];
|
||||||
|
if (DEBUGGING(LEVELING)) SERIAL_ECHOLNPAIR("1st Probe Z:", first_probe_z);
|
||||||
|
#endif
|
||||||
|
|
||||||
|
// move up to make clearance for the probe
|
||||||
|
do_blocking_move_to_z(current_position[Z_AXIS] + Z_CLEARANCE_BETWEEN_PROBES, MMM_TO_MMS(Z_PROBE_SPEED_FAST));
|
||||||
|
|
||||||
|
#else
|
||||||
|
|
||||||
|
// If the nozzle is above the travel height then
|
||||||
|
// move down quickly before doing the slow probe
|
||||||
|
float z = Z_CLEARANCE_DEPLOY_PROBE;
|
||||||
|
if (zprobe_zoffset < 0) z -= zprobe_zoffset;
|
||||||
|
|
||||||
|
if (z < current_position[Z_AXIS]) {
|
||||||
|
|
||||||
|
// If we don't make it to the z position (i.e. the probe triggered), move up to make clearance for the probe
|
||||||
|
if (!do_probe_move(z, Z_PROBE_SPEED_FAST))
|
||||||
|
do_blocking_move_to_z(current_position[Z_AXIS] + Z_CLEARANCE_BETWEEN_PROBES, MMM_TO_MMS(Z_PROBE_SPEED_FAST));
|
||||||
|
}
|
||||||
|
#endif
|
||||||
|
|
||||||
|
// move down slowly to find bed
|
||||||
|
if (do_probe_move(-10 + (short_move ? 0 : -(Z_MAX_LENGTH)), Z_PROBE_SPEED_SLOW)) return NAN;
|
||||||
|
|
||||||
|
#if ENABLED(DEBUG_LEVELING_FEATURE)
|
||||||
|
if (DEBUGGING(LEVELING)) DEBUG_POS("<<< run_z_probe", current_position);
|
||||||
|
#endif
|
||||||
|
|
||||||
|
// Debug: compare probe heights
|
||||||
|
#if ENABLED(PROBE_DOUBLE_TOUCH) && ENABLED(DEBUG_LEVELING_FEATURE)
|
||||||
|
if (DEBUGGING(LEVELING)) {
|
||||||
|
SERIAL_ECHOPAIR("2nd Probe Z:", current_position[Z_AXIS]);
|
||||||
|
SERIAL_ECHOLNPAIR(" Discrepancy:", first_probe_z - current_position[Z_AXIS]);
|
||||||
|
}
|
||||||
|
#endif
|
||||||
|
|
||||||
|
return RAW_CURRENT_POSITION(Z) + zprobe_zoffset
|
||||||
|
#if ENABLED(DELTA)
|
||||||
|
+ home_offset[Z_AXIS] // Account for delta height adjustment
|
||||||
|
#endif
|
||||||
|
;
|
||||||
|
}
|
||||||
|
|
||||||
|
/**
|
||||||
|
* - Move to the given XY
|
||||||
|
* - Deploy the probe, if not already deployed
|
||||||
|
* - Probe the bed, get the Z position
|
||||||
|
* - Depending on the 'stow' flag
|
||||||
|
* - Stow the probe, or
|
||||||
|
* - Raise to the BETWEEN height
|
||||||
|
* - Return the probed Z position
|
||||||
|
*/
|
||||||
|
float probe_pt(const float &lx, const float &ly, const bool stow, const uint8_t verbose_level, const bool printable/*=true*/) {
|
||||||
|
#if ENABLED(DEBUG_LEVELING_FEATURE)
|
||||||
|
if (DEBUGGING(LEVELING)) {
|
||||||
|
SERIAL_ECHOPAIR(">>> probe_pt(", lx);
|
||||||
|
SERIAL_ECHOPAIR(", ", ly);
|
||||||
|
SERIAL_ECHOPAIR(", ", stow ? "" : "no ");
|
||||||
|
SERIAL_ECHOLNPGM("stow)");
|
||||||
|
DEBUG_POS("", current_position);
|
||||||
|
}
|
||||||
|
#endif
|
||||||
|
|
||||||
|
const float nx = lx - (X_PROBE_OFFSET_FROM_EXTRUDER), ny = ly - (Y_PROBE_OFFSET_FROM_EXTRUDER);
|
||||||
|
|
||||||
|
if (printable
|
||||||
|
? !position_is_reachable_xy(nx, ny)
|
||||||
|
: !position_is_reachable_by_probe_xy(lx, ly)
|
||||||
|
) return NAN;
|
||||||
|
|
||||||
|
|
||||||
|
const float old_feedrate_mm_s = feedrate_mm_s;
|
||||||
|
|
||||||
|
#if ENABLED(DELTA)
|
||||||
|
if (current_position[Z_AXIS] > delta_clip_start_height)
|
||||||
|
do_blocking_move_to_z(delta_clip_start_height);
|
||||||
|
#endif
|
||||||
|
|
||||||
|
#if HAS_SOFTWARE_ENDSTOPS
|
||||||
|
// Store the status of the soft endstops and disable if we're probing a non-printable location
|
||||||
|
static bool enable_soft_endstops = soft_endstops_enabled;
|
||||||
|
if (!printable) soft_endstops_enabled = false;
|
||||||
|
#endif
|
||||||
|
|
||||||
|
feedrate_mm_s = XY_PROBE_FEEDRATE_MM_S;
|
||||||
|
|
||||||
|
// Move the probe to the given XY
|
||||||
|
do_blocking_move_to_xy(nx, ny);
|
||||||
|
|
||||||
|
float measured_z = NAN;
|
||||||
|
if (!DEPLOY_PROBE()) {
|
||||||
|
measured_z = run_z_probe(printable);
|
||||||
|
|
||||||
|
if (!stow)
|
||||||
|
do_blocking_move_to_z(current_position[Z_AXIS] + Z_CLEARANCE_BETWEEN_PROBES, MMM_TO_MMS(Z_PROBE_SPEED_FAST));
|
||||||
|
else
|
||||||
|
if (STOW_PROBE()) measured_z = NAN;
|
||||||
|
}
|
||||||
|
|
||||||
|
#if HAS_SOFTWARE_ENDSTOPS
|
||||||
|
// Restore the soft endstop status
|
||||||
|
soft_endstops_enabled = enable_soft_endstops;
|
||||||
|
#endif
|
||||||
|
|
||||||
|
if (verbose_level > 2) {
|
||||||
|
SERIAL_PROTOCOLPGM("Bed X: ");
|
||||||
|
SERIAL_PROTOCOL_F(lx, 3);
|
||||||
|
SERIAL_PROTOCOLPGM(" Y: ");
|
||||||
|
SERIAL_PROTOCOL_F(ly, 3);
|
||||||
|
SERIAL_PROTOCOLPGM(" Z: ");
|
||||||
|
SERIAL_PROTOCOL_F(measured_z, 3);
|
||||||
|
SERIAL_EOL();
|
||||||
|
}
|
||||||
|
|
||||||
|
#if ENABLED(DEBUG_LEVELING_FEATURE)
|
||||||
|
if (DEBUGGING(LEVELING)) SERIAL_ECHOLNPGM("<<< probe_pt");
|
||||||
|
#endif
|
||||||
|
|
||||||
|
feedrate_mm_s = old_feedrate_mm_s;
|
||||||
|
|
||||||
|
if (isnan(measured_z)) {
|
||||||
|
LCD_MESSAGEPGM(MSG_ERR_PROBING_FAILED);
|
||||||
|
SERIAL_ERROR_START();
|
||||||
|
SERIAL_ERRORLNPGM(MSG_ERR_PROBING_FAILED);
|
||||||
|
}
|
||||||
|
|
||||||
|
return measured_z;
|
||||||
|
}
|
||||||
|
|
||||||
|
void refresh_zprobe_zoffset(const bool no_babystep/*=false*/) {
|
||||||
|
static float last_zoffset = NAN;
|
||||||
|
|
||||||
|
if (!isnan(last_zoffset)) {
|
||||||
|
|
||||||
|
#if ENABLED(AUTO_BED_LEVELING_BILINEAR) || ENABLED(BABYSTEP_ZPROBE_OFFSET) || ENABLED(DELTA)
|
||||||
|
const float diff = zprobe_zoffset - last_zoffset;
|
||||||
|
#endif
|
||||||
|
|
||||||
|
#if ENABLED(AUTO_BED_LEVELING_BILINEAR)
|
||||||
|
// Correct bilinear grid for new probe offset
|
||||||
|
if (diff) {
|
||||||
|
for (uint8_t x = 0; x < GRID_MAX_POINTS_X; x++)
|
||||||
|
for (uint8_t y = 0; y < GRID_MAX_POINTS_Y; y++)
|
||||||
|
z_values[x][y] -= diff;
|
||||||
|
}
|
||||||
|
#if ENABLED(ABL_BILINEAR_SUBDIVISION)
|
||||||
|
bed_level_virt_interpolate();
|
||||||
|
#endif
|
||||||
|
#endif
|
||||||
|
|
||||||
|
#if ENABLED(BABYSTEP_ZPROBE_OFFSET)
|
||||||
|
if (!no_babystep && leveling_is_active())
|
||||||
|
thermalManager.babystep_axis(Z_AXIS, -LROUND(diff * planner.axis_steps_per_mm[Z_AXIS]));
|
||||||
|
#else
|
||||||
|
UNUSED(no_babystep);
|
||||||
|
#endif
|
||||||
|
|
||||||
|
#if ENABLED(DELTA) // correct the delta_height
|
||||||
|
home_offset[Z_AXIS] -= diff;
|
||||||
|
#endif
|
||||||
|
}
|
||||||
|
|
||||||
|
last_zoffset = zprobe_zoffset;
|
||||||
|
}
|
||||||
|
|
||||||
|
#if HAS_Z_SERVO_ENDSTOP
|
||||||
|
|
||||||
|
void servo_probe_init() {
|
||||||
|
/**
|
||||||
|
* Set position of Z Servo Endstop
|
||||||
|
*
|
||||||
|
* The servo might be deployed and positioned too low to stow
|
||||||
|
* when starting up the machine or rebooting the board.
|
||||||
|
* There's no way to know where the nozzle is positioned until
|
||||||
|
* homing has been done - no homing with z-probe without init!
|
||||||
|
*
|
||||||
|
*/
|
||||||
|
STOW_Z_SERVO();
|
||||||
|
}
|
||||||
|
|
||||||
|
#endif // HAS_Z_SERVO_ENDSTOP
|
||||||
|
|
||||||
|
#endif // HAS_BED_PROBE
|
69
Marlin/src/module/probe.h
Normal file
69
Marlin/src/module/probe.h
Normal file
|
@ -0,0 +1,69 @@
|
||||||
|
/**
|
||||||
|
* Marlin 3D Printer Firmware
|
||||||
|
* Copyright (C) 2016 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
|
||||||
|
*
|
||||||
|
* Based on Sprinter and grbl.
|
||||||
|
* Copyright (C) 2011 Camiel Gubbels / Erik van der Zalm
|
||||||
|
*
|
||||||
|
* This program is free software: you can redistribute it and/or modify
|
||||||
|
* it under the terms of the GNU General Public License as published by
|
||||||
|
* the Free Software Foundation, either version 3 of the License, or
|
||||||
|
* (at your option) any later version.
|
||||||
|
*
|
||||||
|
* This program is distributed in the hope that it will be useful,
|
||||||
|
* but WITHOUT ANY WARRANTY; without even the implied warranty of
|
||||||
|
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
|
||||||
|
* GNU General Public License for more details.
|
||||||
|
*
|
||||||
|
* You should have received a copy of the GNU General Public License
|
||||||
|
* along with this program. If not, see <http://www.gnu.org/licenses/>.
|
||||||
|
*
|
||||||
|
*/
|
||||||
|
|
||||||
|
/**
|
||||||
|
* probe.h - Move, deploy, enable, etc.
|
||||||
|
*/
|
||||||
|
|
||||||
|
#ifndef PROBE_H
|
||||||
|
#define PROBE_H
|
||||||
|
|
||||||
|
#include "../inc/MarlinConfig.h"
|
||||||
|
|
||||||
|
bool set_probe_deployed(const bool deploy);
|
||||||
|
float probe_pt(const float &lx, const float &ly, const bool, const uint8_t, const bool printable=true);
|
||||||
|
|
||||||
|
#if HAS_BED_PROBE
|
||||||
|
extern float zprobe_zoffset;
|
||||||
|
void refresh_zprobe_zoffset(const bool no_babystep=false);
|
||||||
|
#define DEPLOY_PROBE() set_probe_deployed(true)
|
||||||
|
#define STOW_PROBE() set_probe_deployed(false)
|
||||||
|
#else
|
||||||
|
#define DEPLOY_PROBE()
|
||||||
|
#define STOW_PROBE()
|
||||||
|
#endif
|
||||||
|
|
||||||
|
#if HAS_Z_SERVO_ENDSTOP
|
||||||
|
extern const int z_servo_angle[2];
|
||||||
|
void servo_probe_init();
|
||||||
|
#endif
|
||||||
|
|
||||||
|
#if QUIET_PROBING
|
||||||
|
void probing_pause(const bool p);
|
||||||
|
#endif
|
||||||
|
|
||||||
|
#if ENABLED(PROBING_FANS_OFF)
|
||||||
|
void fans_pause(const bool p);
|
||||||
|
#endif
|
||||||
|
|
||||||
|
#if ENABLED(BLTOUCH)
|
||||||
|
void bltouch_command(int angle);
|
||||||
|
bool set_bltouch_deployed(const bool deploy);
|
||||||
|
FORCE_INLINE void bltouch_init() {
|
||||||
|
// Make sure any BLTouch error condition is cleared
|
||||||
|
bltouch_command(BLTOUCH_RESET);
|
||||||
|
set_bltouch_deployed(true);
|
||||||
|
set_bltouch_deployed(false);
|
||||||
|
}
|
||||||
|
#endif
|
||||||
|
|
||||||
|
#endif // PROBE_H
|
155
Marlin/src/module/scara.cpp
Normal file
155
Marlin/src/module/scara.cpp
Normal file
|
@ -0,0 +1,155 @@
|
||||||
|
/**
|
||||||
|
* Marlin 3D Printer Firmware
|
||||||
|
* Copyright (C) 2016 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
|
||||||
|
*
|
||||||
|
* Based on Sprinter and grbl.
|
||||||
|
* Copyright (C) 2011 Camiel Gubbels / Erik van der Zalm
|
||||||
|
*
|
||||||
|
* This program is free software: you can redistribute it and/or modify
|
||||||
|
* it under the terms of the GNU General Public License as published by
|
||||||
|
* the Free Software Foundation, either version 3 of the License, or
|
||||||
|
* (at your option) any later version.
|
||||||
|
*
|
||||||
|
* This program is distributed in the hope that it will be useful,
|
||||||
|
* but WITHOUT ANY WARRANTY; without even the implied warranty of
|
||||||
|
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
|
||||||
|
* GNU General Public License for more details.
|
||||||
|
*
|
||||||
|
* You should have received a copy of the GNU General Public License
|
||||||
|
* along with this program. If not, see <http://www.gnu.org/licenses/>.
|
||||||
|
*
|
||||||
|
*/
|
||||||
|
|
||||||
|
/**
|
||||||
|
* scara.cpp
|
||||||
|
*/
|
||||||
|
|
||||||
|
#include "../inc/MarlinConfig.h"
|
||||||
|
|
||||||
|
#if IS_SCARA
|
||||||
|
|
||||||
|
#include "scara.h"
|
||||||
|
#include "motion.h"
|
||||||
|
#include "stepper.h"
|
||||||
|
|
||||||
|
float delta_segments_per_second = SCARA_SEGMENTS_PER_SECOND;
|
||||||
|
|
||||||
|
void scara_set_axis_is_at_home(const AxisEnum axis) {
|
||||||
|
if (axis == Z_AXIS)
|
||||||
|
current_position[Z_AXIS] = LOGICAL_POSITION(Z_HOME_POS, Z_AXIS);
|
||||||
|
else {
|
||||||
|
|
||||||
|
/**
|
||||||
|
* SCARA homes XY at the same time
|
||||||
|
*/
|
||||||
|
float homeposition[XYZ];
|
||||||
|
LOOP_XYZ(i) homeposition[i] = LOGICAL_POSITION(base_home_pos((AxisEnum)i), i);
|
||||||
|
|
||||||
|
// SERIAL_ECHOPAIR("homeposition X:", homeposition[X_AXIS]);
|
||||||
|
// SERIAL_ECHOLNPAIR(" Y:", homeposition[Y_AXIS]);
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Get Home position SCARA arm angles using inverse kinematics,
|
||||||
|
* and calculate homing offset using forward kinematics
|
||||||
|
*/
|
||||||
|
inverse_kinematics(homeposition);
|
||||||
|
forward_kinematics_SCARA(delta[A_AXIS], delta[B_AXIS]);
|
||||||
|
|
||||||
|
// SERIAL_ECHOPAIR("Cartesian X:", cartes[X_AXIS]);
|
||||||
|
// SERIAL_ECHOLNPAIR(" Y:", cartes[Y_AXIS]);
|
||||||
|
|
||||||
|
current_position[axis] = LOGICAL_POSITION(cartes[axis], axis);
|
||||||
|
|
||||||
|
/**
|
||||||
|
* SCARA home positions are based on configuration since the actual
|
||||||
|
* limits are determined by the inverse kinematic transform.
|
||||||
|
*/
|
||||||
|
soft_endstop_min[axis] = base_min_pos(axis); // + (cartes[axis] - base_home_pos(axis));
|
||||||
|
soft_endstop_max[axis] = base_max_pos(axis); // + (cartes[axis] - base_home_pos(axis));
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Morgan SCARA Forward Kinematics. Results in cartes[].
|
||||||
|
* Maths and first version by QHARLEY.
|
||||||
|
* Integrated into Marlin and slightly restructured by Joachim Cerny.
|
||||||
|
*/
|
||||||
|
void forward_kinematics_SCARA(const float &a, const float &b) {
|
||||||
|
|
||||||
|
const float a_sin = sin(RADIANS(a)) * L1,
|
||||||
|
a_cos = cos(RADIANS(a)) * L1,
|
||||||
|
b_sin = sin(RADIANS(b)) * L2,
|
||||||
|
b_cos = cos(RADIANS(b)) * L2;
|
||||||
|
|
||||||
|
cartes[X_AXIS] = a_cos + b_cos + SCARA_OFFSET_X; //theta
|
||||||
|
cartes[Y_AXIS] = a_sin + b_sin + SCARA_OFFSET_Y; //theta+phi
|
||||||
|
|
||||||
|
/*
|
||||||
|
SERIAL_ECHOPAIR("SCARA FK Angle a=", a);
|
||||||
|
SERIAL_ECHOPAIR(" b=", b);
|
||||||
|
SERIAL_ECHOPAIR(" a_sin=", a_sin);
|
||||||
|
SERIAL_ECHOPAIR(" a_cos=", a_cos);
|
||||||
|
SERIAL_ECHOPAIR(" b_sin=", b_sin);
|
||||||
|
SERIAL_ECHOLNPAIR(" b_cos=", b_cos);
|
||||||
|
SERIAL_ECHOPAIR(" cartes[X_AXIS]=", cartes[X_AXIS]);
|
||||||
|
SERIAL_ECHOLNPAIR(" cartes[Y_AXIS]=", cartes[Y_AXIS]);
|
||||||
|
//*/
|
||||||
|
}
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Morgan SCARA Inverse Kinematics. Results in delta[].
|
||||||
|
*
|
||||||
|
* See http://forums.reprap.org/read.php?185,283327
|
||||||
|
*
|
||||||
|
* Maths and first version by QHARLEY.
|
||||||
|
* Integrated into Marlin and slightly restructured by Joachim Cerny.
|
||||||
|
*/
|
||||||
|
void inverse_kinematics(const float logical[XYZ]) {
|
||||||
|
|
||||||
|
static float C2, S2, SK1, SK2, THETA, PSI;
|
||||||
|
|
||||||
|
float sx = RAW_X_POSITION(logical[X_AXIS]) - SCARA_OFFSET_X, // Translate SCARA to standard X Y
|
||||||
|
sy = RAW_Y_POSITION(logical[Y_AXIS]) - SCARA_OFFSET_Y; // With scaling factor.
|
||||||
|
|
||||||
|
if (L1 == L2)
|
||||||
|
C2 = HYPOT2(sx, sy) / L1_2_2 - 1;
|
||||||
|
else
|
||||||
|
C2 = (HYPOT2(sx, sy) - (L1_2 + L2_2)) / (2.0 * L1 * L2);
|
||||||
|
|
||||||
|
S2 = SQRT(1 - sq(C2));
|
||||||
|
|
||||||
|
// Unrotated Arm1 plus rotated Arm2 gives the distance from Center to End
|
||||||
|
SK1 = L1 + L2 * C2;
|
||||||
|
|
||||||
|
// Rotated Arm2 gives the distance from Arm1 to Arm2
|
||||||
|
SK2 = L2 * S2;
|
||||||
|
|
||||||
|
// Angle of Arm1 is the difference between Center-to-End angle and the Center-to-Elbow
|
||||||
|
THETA = ATAN2(SK1, SK2) - ATAN2(sx, sy);
|
||||||
|
|
||||||
|
// Angle of Arm2
|
||||||
|
PSI = ATAN2(S2, C2);
|
||||||
|
|
||||||
|
delta[A_AXIS] = DEGREES(THETA); // theta is support arm angle
|
||||||
|
delta[B_AXIS] = DEGREES(THETA + PSI); // equal to sub arm angle (inverted motor)
|
||||||
|
delta[C_AXIS] = logical[Z_AXIS];
|
||||||
|
|
||||||
|
/*
|
||||||
|
DEBUG_POS("SCARA IK", logical);
|
||||||
|
DEBUG_POS("SCARA IK", delta);
|
||||||
|
SERIAL_ECHOPAIR(" SCARA (x,y) ", sx);
|
||||||
|
SERIAL_ECHOPAIR(",", sy);
|
||||||
|
SERIAL_ECHOPAIR(" C2=", C2);
|
||||||
|
SERIAL_ECHOPAIR(" S2=", S2);
|
||||||
|
SERIAL_ECHOPAIR(" Theta=", THETA);
|
||||||
|
SERIAL_ECHOLNPAIR(" Phi=", PHI);
|
||||||
|
//*/
|
||||||
|
}
|
||||||
|
|
||||||
|
void scara_report_positions() {
|
||||||
|
SERIAL_PROTOCOLPAIR("SCARA Theta:", stepper.get_axis_position_degrees(A_AXIS));
|
||||||
|
SERIAL_PROTOCOLLNPAIR(" Psi+Theta:", stepper.get_axis_position_degrees(B_AXIS));
|
||||||
|
SERIAL_EOL();
|
||||||
|
}
|
||||||
|
|
||||||
|
#endif // IS_SCARA
|
46
Marlin/src/module/scara.h
Normal file
46
Marlin/src/module/scara.h
Normal file
|
@ -0,0 +1,46 @@
|
||||||
|
/**
|
||||||
|
* Marlin 3D Printer Firmware
|
||||||
|
* Copyright (C) 2016 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
|
||||||
|
*
|
||||||
|
* Based on Sprinter and grbl.
|
||||||
|
* Copyright (C) 2011 Camiel Gubbels / Erik van der Zalm
|
||||||
|
*
|
||||||
|
* This program is free software: you can redistribute it and/or modify
|
||||||
|
* it under the terms of the GNU General Public License as published by
|
||||||
|
* the Free Software Foundation, either version 3 of the License, or
|
||||||
|
* (at your option) any later version.
|
||||||
|
*
|
||||||
|
* This program is distributed in the hope that it will be useful,
|
||||||
|
* but WITHOUT ANY WARRANTY; without even the implied warranty of
|
||||||
|
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
|
||||||
|
* GNU General Public License for more details.
|
||||||
|
*
|
||||||
|
* You should have received a copy of the GNU General Public License
|
||||||
|
* along with this program. If not, see <http://www.gnu.org/licenses/>.
|
||||||
|
*
|
||||||
|
*/
|
||||||
|
|
||||||
|
/**
|
||||||
|
* scara.h - SCARA-specific functions
|
||||||
|
*/
|
||||||
|
|
||||||
|
#ifndef __SCARA_H__
|
||||||
|
#define __SCARA_H__
|
||||||
|
|
||||||
|
#include "../core/macros.h"
|
||||||
|
|
||||||
|
extern float delta_segments_per_second;
|
||||||
|
|
||||||
|
// Float constants for SCARA calculations
|
||||||
|
float constexpr L1 = SCARA_LINKAGE_1, L2 = SCARA_LINKAGE_2,
|
||||||
|
L1_2 = sq(float(L1)), L1_2_2 = 2.0 * L1_2,
|
||||||
|
L2_2 = sq(float(L2));
|
||||||
|
|
||||||
|
void scara_set_axis_is_at_home(const AxisEnum axis);
|
||||||
|
|
||||||
|
void inverse_kinematics(const float logical[XYZ]);
|
||||||
|
void forward_kinematics_SCARA(const float &a, const float &b);
|
||||||
|
|
||||||
|
void scara_report_positions();
|
||||||
|
|
||||||
|
#endif // __SCARA_H__
|
|
@ -52,6 +52,7 @@
|
||||||
|
|
||||||
#include "endstops.h"
|
#include "endstops.h"
|
||||||
#include "planner.h"
|
#include "planner.h"
|
||||||
|
#include "motion.h"
|
||||||
|
|
||||||
#include "../Marlin.h"
|
#include "../Marlin.h"
|
||||||
#include "../module/temperature.h"
|
#include "../module/temperature.h"
|
||||||
|
|
Loading…
Reference in a new issue