Merge upstream changes from Marlin 2.1.1
This commit is contained in:
@@ -71,8 +71,8 @@
|
||||
* 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
|
||||
* Q # Multiplier Retraction Multiplier. (Normally not needed.) During G26 retraction will use the length
|
||||
* specified by this parameter (1mm by default). Recover will be 1.2x the retract distance.
|
||||
*
|
||||
* 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.
|
||||
@@ -107,7 +107,6 @@
|
||||
|
||||
#include "../../MarlinCore.h"
|
||||
#include "../../module/planner.h"
|
||||
#include "../../module/stepper.h"
|
||||
#include "../../module/motion.h"
|
||||
#include "../../module/tool_change.h"
|
||||
#include "../../module/temperature.h"
|
||||
@@ -156,15 +155,15 @@ constexpr float g26_e_axis_feedrate = 0.025;
|
||||
static MeshFlags circle_flags;
|
||||
float g26_random_deviation = 0.0;
|
||||
|
||||
#if HAS_LCD_MENU
|
||||
#if HAS_MARLINUI_MENU
|
||||
|
||||
/**
|
||||
* If the LCD is clicked, cancel, wait for release, return true
|
||||
*/
|
||||
bool user_canceled() {
|
||||
if (!ui.button_pressed()) return false; // Return if the button isn't pressed
|
||||
ui.set_status_P(GET_TEXT(MSG_G26_CANCELED), 99);
|
||||
TERN_(HAS_LCD_MENU, ui.quick_feedback());
|
||||
ui.set_status(GET_TEXT_F(MSG_G26_CANCELED), 99);
|
||||
TERN_(HAS_MARLINUI_MENU, ui.quick_feedback());
|
||||
ui.wait_for_release();
|
||||
return true;
|
||||
}
|
||||
@@ -293,10 +292,10 @@ typedef struct {
|
||||
|
||||
if (circle_flags.marked(p1.x, p1.y) && circle_flags.marked(p2.x, p2.y)) {
|
||||
xyz_pos_t s, e;
|
||||
s.x = _GET_MESH_X(p1.x) + (INTERSECTION_CIRCLE_RADIUS - (CROSSHAIRS_SIZE)) * dx;
|
||||
e.x = _GET_MESH_X(p2.x) - (INTERSECTION_CIRCLE_RADIUS - (CROSSHAIRS_SIZE)) * dx;
|
||||
s.y = _GET_MESH_Y(p1.y) + (INTERSECTION_CIRCLE_RADIUS - (CROSSHAIRS_SIZE)) * dy;
|
||||
e.y = _GET_MESH_Y(p2.y) - (INTERSECTION_CIRCLE_RADIUS - (CROSSHAIRS_SIZE)) * dy;
|
||||
s.x = bedlevel.get_mesh_x(p1.x) + (INTERSECTION_CIRCLE_RADIUS - (CROSSHAIRS_SIZE)) * dx;
|
||||
e.x = bedlevel.get_mesh_x(p2.x) - (INTERSECTION_CIRCLE_RADIUS - (CROSSHAIRS_SIZE)) * dx;
|
||||
s.y = bedlevel.get_mesh_y(p1.y) + (INTERSECTION_CIRCLE_RADIUS - (CROSSHAIRS_SIZE)) * dy;
|
||||
e.y = bedlevel.get_mesh_y(p2.y) - (INTERSECTION_CIRCLE_RADIUS - (CROSSHAIRS_SIZE)) * dy;
|
||||
s.z = e.z = layer_height;
|
||||
|
||||
#if HAS_ENDSTOPS
|
||||
@@ -306,7 +305,7 @@ typedef struct {
|
||||
LIMIT(e.x, X_MIN_POS + 1, X_MAX_POS - 1);
|
||||
#endif
|
||||
|
||||
if (position_is_reachable(s.x, s.y) && position_is_reachable(e.x, e.y))
|
||||
if (position_is_reachable(s) && position_is_reachable(e))
|
||||
print_line_from_here_to_there(s, e);
|
||||
}
|
||||
}
|
||||
@@ -323,9 +322,9 @@ typedef struct {
|
||||
|
||||
if (bed_temp > 25) {
|
||||
#if HAS_WIRED_LCD
|
||||
ui.set_status_P(GET_TEXT(MSG_G26_HEATING_BED), 99);
|
||||
ui.set_status(GET_TEXT_F(MSG_G26_HEATING_BED), 99);
|
||||
ui.quick_feedback();
|
||||
TERN_(HAS_LCD_MENU, ui.capture());
|
||||
TERN_(HAS_MARLINUI_MENU, ui.capture());
|
||||
#endif
|
||||
thermalManager.setTargetBed(bed_temp);
|
||||
|
||||
@@ -342,7 +341,7 @@ typedef struct {
|
||||
|
||||
// Start heating the active nozzle
|
||||
#if HAS_WIRED_LCD
|
||||
ui.set_status_P(GET_TEXT(MSG_G26_HEATING_NOZZLE), 99);
|
||||
ui.set_status(GET_TEXT_F(MSG_G26_HEATING_NOZZLE), 99);
|
||||
ui.quick_feedback();
|
||||
#endif
|
||||
thermalManager.setTargetHotend(hotend_temp, active_extruder);
|
||||
@@ -365,14 +364,14 @@ typedef struct {
|
||||
bool prime_nozzle() {
|
||||
|
||||
const feedRate_t fr_slow_e = planner.settings.max_feedrate_mm_s[E_AXIS] / 15.0f;
|
||||
#if HAS_LCD_MENU && !HAS_TOUCH_BUTTONS // ui.button_pressed issue with touchscreen
|
||||
#if HAS_MARLINUI_MENU && !HAS_TOUCH_BUTTONS // ui.button_pressed issue with touchscreen
|
||||
#if ENABLED(PREVENT_LENGTHY_EXTRUDE)
|
||||
float Total_Prime = 0.0;
|
||||
#endif
|
||||
|
||||
if (prime_flag == -1) { // The user wants to control how much filament gets purged
|
||||
ui.capture();
|
||||
ui.set_status_P(GET_TEXT(MSG_G26_MANUAL_PRIME), 99);
|
||||
ui.set_status(GET_TEXT_F(MSG_G26_MANUAL_PRIME), 99);
|
||||
ui.chirp();
|
||||
|
||||
destination = current_position;
|
||||
@@ -399,7 +398,7 @@ typedef struct {
|
||||
|
||||
ui.wait_for_release();
|
||||
|
||||
ui.set_status_P(GET_TEXT(MSG_G26_PRIME_DONE), 99);
|
||||
ui.set_status(GET_TEXT_F(MSG_G26_PRIME_DONE), 99);
|
||||
ui.quick_feedback();
|
||||
ui.release();
|
||||
}
|
||||
@@ -407,7 +406,7 @@ typedef struct {
|
||||
#endif
|
||||
{
|
||||
#if HAS_WIRED_LCD
|
||||
ui.set_status_P(GET_TEXT(MSG_G26_FIXED_LENGTH), 99);
|
||||
ui.set_status(GET_TEXT_F(MSG_G26_FIXED_LENGTH), 99);
|
||||
ui.quick_feedback();
|
||||
#endif
|
||||
destination = current_position;
|
||||
@@ -448,7 +447,7 @@ typedef struct {
|
||||
GRID_LOOP(i, j) {
|
||||
if (!circle_flags.marked(i, j)) {
|
||||
// We found a circle that needs to be printed
|
||||
const xy_pos_t m = { _GET_MESH_X(i), _GET_MESH_Y(j) };
|
||||
const xy_pos_t m = { bedlevel.get_mesh_x(i), bedlevel.get_mesh_y(j) };
|
||||
|
||||
// Get the distance to this intersection
|
||||
float f = (pos - m).magnitude();
|
||||
@@ -520,7 +519,7 @@ void GcodeSuite::G26() {
|
||||
g26.keep_heaters_on = parser.boolval('K');
|
||||
|
||||
// Accept 'I' if temperature presets are defined
|
||||
#if PREHEAT_COUNT
|
||||
#if HAS_PREHEAT
|
||||
const uint8_t preset_index = parser.seenval('I') ? _MIN(parser.value_byte(), PREHEAT_COUNT - 1) + 1 : 0;
|
||||
#endif
|
||||
|
||||
@@ -530,7 +529,7 @@ void GcodeSuite::G26() {
|
||||
celsius_t bedtemp = 0;
|
||||
|
||||
// Use the 'I' index if temperature presets are defined
|
||||
#if PREHEAT_COUNT
|
||||
#if HAS_PREHEAT
|
||||
if (preset_index) bedtemp = ui.material_preset[preset_index - 1].bed_temp;
|
||||
#endif
|
||||
|
||||
@@ -579,7 +578,7 @@ void GcodeSuite::G26() {
|
||||
|
||||
if (parser.seen('P')) {
|
||||
if (!parser.has_value()) {
|
||||
#if HAS_LCD_MENU
|
||||
#if HAS_MARLINUI_MENU
|
||||
g26.prime_flag = -1;
|
||||
#else
|
||||
SERIAL_ECHOLNPGM("?Prime length must be specified when not using an LCD.");
|
||||
@@ -613,7 +612,7 @@ void GcodeSuite::G26() {
|
||||
celsius_t noztemp = 0;
|
||||
|
||||
// Accept 'I' if temperature presets are defined
|
||||
#if PREHEAT_COUNT
|
||||
#if HAS_PREHEAT
|
||||
if (preset_index) noztemp = ui.material_preset[preset_index - 1].hotend_temp;
|
||||
#endif
|
||||
|
||||
@@ -638,7 +637,7 @@ void GcodeSuite::G26() {
|
||||
|
||||
// Get repeat from 'R', otherwise do one full circuit
|
||||
int16_t g26_repeats;
|
||||
#if HAS_LCD_MENU
|
||||
#if HAS_MARLINUI_MENU
|
||||
g26_repeats = parser.intval('R', GRID_MAX_POINTS + 1);
|
||||
#else
|
||||
if (parser.seen('R'))
|
||||
@@ -699,7 +698,7 @@ void GcodeSuite::G26() {
|
||||
move_to(destination, 0.0);
|
||||
move_to(destination, g26.ooze_amount);
|
||||
|
||||
TERN_(HAS_LCD_MENU, ui.capture());
|
||||
TERN_(HAS_MARLINUI_MENU, ui.capture());
|
||||
|
||||
#if DISABLED(ARC_SUPPORT)
|
||||
|
||||
@@ -729,7 +728,7 @@ void GcodeSuite::G26() {
|
||||
|
||||
if (location.valid()) {
|
||||
TERN_(EXTENSIBLE_UI, ExtUI::onMeshUpdate(location.pos, ExtUI::G26_POINT_START));
|
||||
const xy_pos_t circle = _GET_MESH_POS(location.pos);
|
||||
const xy_pos_t circle = { bedlevel.get_mesh_x(location.pos.a), bedlevel.get_mesh_y(location.pos.b) };
|
||||
|
||||
// If this mesh location is outside the printable radius, skip it.
|
||||
if (!position_is_reachable(circle)) continue;
|
||||
@@ -738,8 +737,8 @@ void GcodeSuite::G26() {
|
||||
// which is always drawn counter-clockwise.
|
||||
const xy_int8_t st = location;
|
||||
const bool f = st.y == 0,
|
||||
r = st.x >= GRID_MAX_POINTS_X - 1,
|
||||
b = st.y >= GRID_MAX_POINTS_Y - 1;
|
||||
r = st.x >= (GRID_MAX_POINTS_X) - 1,
|
||||
b = st.y >= (GRID_MAX_POINTS_Y) - 1;
|
||||
|
||||
#if ENABLED(ARC_SUPPORT)
|
||||
|
||||
@@ -795,7 +794,7 @@ void GcodeSuite::G26() {
|
||||
destination = current_position;
|
||||
}
|
||||
|
||||
if (TERN0(HAS_LCD_MENU, user_canceled())) goto LEAVE; // Check if the user wants to stop the Mesh Validation
|
||||
if (TERN0(HAS_MARLINUI_MENU, user_canceled())) goto LEAVE; // Check if the user wants to stop the Mesh Validation
|
||||
|
||||
#else // !ARC_SUPPORT
|
||||
|
||||
@@ -819,7 +818,7 @@ void GcodeSuite::G26() {
|
||||
|
||||
for (int8_t ind = start_ind; ind <= end_ind; ind++) {
|
||||
|
||||
if (TERN0(HAS_LCD_MENU, user_canceled())) goto LEAVE; // Check if the user wants to stop the Mesh Validation
|
||||
if (TERN0(HAS_MARLINUI_MENU, user_canceled())) goto LEAVE; // Check if the user wants to stop the Mesh Validation
|
||||
|
||||
xyz_float_t p = { circle.x + _COS(ind ), circle.y + _SIN(ind ), g26.layer_height },
|
||||
q = { circle.x + _COS(ind + 1), circle.y + _SIN(ind + 1), g26.layer_height };
|
||||
@@ -846,7 +845,7 @@ void GcodeSuite::G26() {
|
||||
g26.connect_neighbor_with_line(location.pos, 0, 1);
|
||||
planner.synchronize();
|
||||
TERN_(EXTENSIBLE_UI, ExtUI::onMeshUpdate(location.pos, ExtUI::G26_POINT_FINISH));
|
||||
if (TERN0(HAS_LCD_MENU, user_canceled())) goto LEAVE;
|
||||
if (TERN0(HAS_MARLINUI_MENU, user_canceled())) goto LEAVE;
|
||||
}
|
||||
|
||||
SERIAL_FLUSH(); // Prevent host M105 buffer overrun.
|
||||
@@ -854,7 +853,7 @@ void GcodeSuite::G26() {
|
||||
} while (--g26_repeats && location.valid());
|
||||
|
||||
LEAVE:
|
||||
ui.set_status_P(GET_TEXT(MSG_G26_LEAVING), -1);
|
||||
ui.set_status(GET_TEXT_F(MSG_G26_LEAVING), -1);
|
||||
TERN_(EXTENSIBLE_UI, ExtUI::onMeshUpdate(location, ExtUI::G26_FINISH));
|
||||
|
||||
g26.retract_filament(destination);
|
||||
@@ -866,7 +865,7 @@ void GcodeSuite::G26() {
|
||||
planner.calculate_volumetric_multipliers();
|
||||
#endif
|
||||
|
||||
TERN_(HAS_LCD_MENU, ui.release()); // Give back control of the LCD
|
||||
TERN_(HAS_MARLINUI_MENU, ui.release()); // Give back control of the LCD
|
||||
|
||||
if (!g26.keep_heaters_on) {
|
||||
TERN_(HAS_HEATED_BED, thermalManager.setTargetBed(0));
|
||||
|
@@ -33,6 +33,10 @@
|
||||
#include "../../module/tool_change.h"
|
||||
#endif
|
||||
|
||||
#if ENABLED(BLTOUCH)
|
||||
#include "../../feature/bltouch.h"
|
||||
#endif
|
||||
|
||||
#define DEBUG_OUT ENABLED(DEBUG_LEVELING_FEATURE)
|
||||
#include "../../core/debug_out.h"
|
||||
|
||||
@@ -92,7 +96,7 @@ void GcodeSuite::G35() {
|
||||
TERN_(HAS_DUPLICATION_MODE, set_duplication_enabled(false));
|
||||
|
||||
// Home only Z axis when X and Y is trusted, otherwise all axes, if needed before this procedure
|
||||
if (!all_axes_trusted()) process_subcommands_now_P(PSTR("G28Z"));
|
||||
if (!all_axes_trusted()) process_subcommands_now(F("G28Z"));
|
||||
|
||||
bool err_break = false;
|
||||
|
||||
@@ -102,7 +106,9 @@ void GcodeSuite::G35() {
|
||||
// In BLTOUCH HS mode, the probe travels in a deployed state.
|
||||
// Users of G35 might have a badly misaligned bed, so raise Z by the
|
||||
// length of the deployed pin (BLTOUCH stroke < 7mm)
|
||||
do_blocking_move_to_z(SUM_TERN(BLTOUCH_HS_MODE, Z_CLEARANCE_BETWEEN_PROBES, 7));
|
||||
|
||||
// Unsure if this is even required. The probe seems to lift correctly after probe done.
|
||||
do_blocking_move_to_z(SUM_TERN(BLTOUCH, Z_CLEARANCE_BETWEEN_PROBES, bltouch.z_extra_clearance()));
|
||||
const float z_probed_height = probe.probe_at_point(tramming_points[i], PROBE_PT_RAISE, 0, true);
|
||||
|
||||
if (isnan(z_probed_height)) {
|
||||
@@ -116,7 +122,7 @@ void GcodeSuite::G35() {
|
||||
|
||||
if (DEBUGGING(LEVELING)) {
|
||||
DEBUG_ECHOPGM("Probing point ", i + 1, " (");
|
||||
DEBUG_ECHOPGM_P((char *)pgm_read_ptr(&tramming_point_name[i]));
|
||||
DEBUG_ECHOF(FPSTR(pgm_read_ptr(&tramming_point_name[i])));
|
||||
DEBUG_CHAR(')');
|
||||
DEBUG_ECHOLNPGM_P(SP_X_STR, tramming_points[i].x, SP_Y_STR, tramming_points[i].y, SP_Z_STR, z_probed_height);
|
||||
}
|
||||
@@ -149,7 +155,7 @@ void GcodeSuite::G35() {
|
||||
|
||||
// Restore the active tool after homing
|
||||
#if HAS_MULTI_HOTEND
|
||||
tool_change(old_tool_index, DISABLED(PARKING_EXTRUDER)); // Fetch previous toolhead if not PARKING_EXTRUDER
|
||||
if (old_tool_index != 0) tool_change(old_tool_index, DISABLED(PARKING_EXTRUDER)); // Fetch previous toolhead if not PARKING_EXTRUDER
|
||||
#endif
|
||||
|
||||
#if BOTH(HAS_LEVELING, RESTORE_LEVELING_AFTER_G35)
|
||||
|
@@ -48,8 +48,8 @@ void GcodeSuite::G42() {
|
||||
// Move to current_position, as modified by I, J, P parameters
|
||||
destination = current_position;
|
||||
|
||||
if (hasI) destination.x = _GET_MESH_X(ix);
|
||||
if (hasJ) destination.y = _GET_MESH_Y(iy);
|
||||
if (hasI) destination.x = bedlevel.get_mesh_x(ix);
|
||||
if (hasJ) destination.y = bedlevel.get_mesh_y(iy);
|
||||
|
||||
#if HAS_PROBE_XY_OFFSET
|
||||
if (parser.boolval('P')) {
|
||||
|
@@ -67,14 +67,17 @@ void GcodeSuite::M420() {
|
||||
const float x_min = probe.min_x(), x_max = probe.max_x(),
|
||||
y_min = probe.min_y(), y_max = probe.max_y();
|
||||
#if ENABLED(AUTO_BED_LEVELING_BILINEAR)
|
||||
bilinear_start.set(x_min, y_min);
|
||||
bilinear_grid_spacing.set((x_max - x_min) / (GRID_MAX_CELLS_X),
|
||||
(y_max - y_min) / (GRID_MAX_CELLS_Y));
|
||||
xy_pos_t start, spacing;
|
||||
start.set(x_min, y_min);
|
||||
spacing.set((x_max - x_min) / (GRID_MAX_CELLS_X),
|
||||
(y_max - y_min) / (GRID_MAX_CELLS_Y));
|
||||
bedlevel.set_grid(spacing, start);
|
||||
#endif
|
||||
GRID_LOOP(x, y) {
|
||||
Z_VALUES(x, y) = 0.001 * random(-200, 200);
|
||||
TERN_(EXTENSIBLE_UI, ExtUI::onMeshUpdate(x, y, Z_VALUES(x, y)));
|
||||
bedlevel.z_values[x][y] = 0.001 * random(-200, 200);
|
||||
TERN_(EXTENSIBLE_UI, ExtUI::onMeshUpdate(x, y, bedlevel.z_values[x][y]));
|
||||
}
|
||||
TERN_(AUTO_BED_LEVELING_BILINEAR, bedlevel.refresh_bed_level());
|
||||
SERIAL_ECHOPGM("Simulated " STRINGIFY(GRID_MAX_POINTS_X) "x" STRINGIFY(GRID_MAX_POINTS_Y) " mesh ");
|
||||
SERIAL_ECHOPGM(" (", x_min);
|
||||
SERIAL_CHAR(','); SERIAL_ECHO(y_min);
|
||||
@@ -98,7 +101,7 @@ void GcodeSuite::M420() {
|
||||
set_bed_leveling_enabled(false);
|
||||
|
||||
#if ENABLED(EEPROM_SETTINGS)
|
||||
const int8_t storage_slot = parser.has_value() ? parser.value_int() : ubl.storage_slot;
|
||||
const int8_t storage_slot = parser.has_value() ? parser.value_int() : bedlevel.storage_slot;
|
||||
const int16_t a = settings.calc_num_meshes();
|
||||
|
||||
if (!a) {
|
||||
@@ -113,7 +116,7 @@ void GcodeSuite::M420() {
|
||||
}
|
||||
|
||||
settings.load_mesh(storage_slot);
|
||||
ubl.storage_slot = storage_slot;
|
||||
bedlevel.storage_slot = storage_slot;
|
||||
|
||||
#else
|
||||
|
||||
@@ -125,10 +128,10 @@ void GcodeSuite::M420() {
|
||||
|
||||
// L or V display the map info
|
||||
if (parser.seen("LV")) {
|
||||
ubl.display_map(parser.byteval('T'));
|
||||
bedlevel.display_map(parser.byteval('T'));
|
||||
SERIAL_ECHOPGM("Mesh is ");
|
||||
if (!ubl.mesh_is_valid()) SERIAL_ECHOPGM("in");
|
||||
SERIAL_ECHOLNPGM("valid\nStorage slot: ", ubl.storage_slot);
|
||||
if (!bedlevel.mesh_is_valid()) SERIAL_ECHOPGM("in");
|
||||
SERIAL_ECHOLNPGM("valid\nStorage slot: ", bedlevel.storage_slot);
|
||||
}
|
||||
|
||||
#endif // AUTO_BED_LEVELING_UBL
|
||||
@@ -145,7 +148,7 @@ void GcodeSuite::M420() {
|
||||
#if ENABLED(AUTO_BED_LEVELING_UBL)
|
||||
|
||||
set_bed_leveling_enabled(false);
|
||||
ubl.adjust_mesh_to_mean(true, cval);
|
||||
bedlevel.adjust_mesh_to_mean(true, cval);
|
||||
|
||||
#else
|
||||
|
||||
@@ -153,7 +156,7 @@ void GcodeSuite::M420() {
|
||||
|
||||
// Get the sum and average of all mesh values
|
||||
float mesh_sum = 0;
|
||||
GRID_LOOP(x, y) mesh_sum += Z_VALUES(x, y);
|
||||
GRID_LOOP(x, y) mesh_sum += bedlevel.z_values[x][y];
|
||||
const float zmean = mesh_sum / float(GRID_MAX_POINTS);
|
||||
|
||||
#else // midrange
|
||||
@@ -161,7 +164,7 @@ void GcodeSuite::M420() {
|
||||
// Find the low and high mesh values.
|
||||
float lo_val = 100, hi_val = -100;
|
||||
GRID_LOOP(x, y) {
|
||||
const float z = Z_VALUES(x, y);
|
||||
const float z = bedlevel.z_values[x][y];
|
||||
NOMORE(lo_val, z);
|
||||
NOLESS(hi_val, z);
|
||||
}
|
||||
@@ -175,10 +178,10 @@ void GcodeSuite::M420() {
|
||||
set_bed_leveling_enabled(false);
|
||||
// Subtract the mean from all values
|
||||
GRID_LOOP(x, y) {
|
||||
Z_VALUES(x, y) -= zmean;
|
||||
TERN_(EXTENSIBLE_UI, ExtUI::onMeshUpdate(x, y, Z_VALUES(x, y)));
|
||||
bedlevel.z_values[x][y] -= zmean;
|
||||
TERN_(EXTENSIBLE_UI, ExtUI::onMeshUpdate(x, y, bedlevel.z_values[x][y]));
|
||||
}
|
||||
TERN_(ABL_BILINEAR_SUBDIVISION, bed_level_virt_interpolate());
|
||||
TERN_(AUTO_BED_LEVELING_BILINEAR, bedlevel.refresh_bed_level());
|
||||
}
|
||||
|
||||
#endif
|
||||
@@ -195,15 +198,14 @@ void GcodeSuite::M420() {
|
||||
// V to print the matrix or mesh
|
||||
if (seenV) {
|
||||
#if ABL_PLANAR
|
||||
planner.bed_level_matrix.debug(PSTR("Bed Level Correction Matrix:"));
|
||||
planner.bed_level_matrix.debug(F("Bed Level Correction Matrix:"));
|
||||
#else
|
||||
if (leveling_is_valid()) {
|
||||
#if ENABLED(AUTO_BED_LEVELING_BILINEAR)
|
||||
print_bilinear_leveling_grid();
|
||||
TERN_(ABL_BILINEAR_SUBDIVISION, print_bilinear_leveling_grid_virt());
|
||||
bedlevel.print_leveling_grid();
|
||||
#elif ENABLED(MESH_BED_LEVELING)
|
||||
SERIAL_ECHOLNPGM("Mesh Bed Level data:");
|
||||
mbl.report_mesh();
|
||||
bedlevel.report_mesh();
|
||||
#endif
|
||||
}
|
||||
#endif
|
||||
@@ -243,15 +245,15 @@ void GcodeSuite::M420() {
|
||||
}
|
||||
|
||||
void GcodeSuite::M420_report(const bool forReplay/*=true*/) {
|
||||
report_heading_etc(forReplay, PSTR(
|
||||
report_heading_etc(forReplay, F(
|
||||
TERN(MESH_BED_LEVELING, "Mesh Bed Leveling", TERN(AUTO_BED_LEVELING_UBL, "Unified Bed Leveling", "Auto Bed Leveling"))
|
||||
));
|
||||
SERIAL_ECHOPGM_P(
|
||||
PSTR(" M420 S"), planner.leveling_active
|
||||
SERIAL_ECHOF(
|
||||
F(" M420 S"), planner.leveling_active
|
||||
#if ENABLED(ENABLE_LEVELING_FADE_HEIGHT)
|
||||
, SP_Z_STR, LINEAR_UNIT(planner.z_fade_height)
|
||||
, FPSTR(SP_Z_STR), LINEAR_UNIT(planner.z_fade_height)
|
||||
#endif
|
||||
, PSTR(" ; Leveling ")
|
||||
, F(" ; Leveling ")
|
||||
);
|
||||
serialprintln_onoff(planner.leveling_active);
|
||||
}
|
||||
|
@@ -32,21 +32,11 @@
|
||||
#include "../../../feature/bedlevel/bedlevel.h"
|
||||
#include "../../../module/motion.h"
|
||||
#include "../../../module/planner.h"
|
||||
#include "../../../module/stepper.h"
|
||||
#include "../../../module/probe.h"
|
||||
#include "../../queue.h"
|
||||
|
||||
#if ENABLED(KNUTWURST_TFT_LEVELING)
|
||||
#include "../../../lcd/HardwareSerial.h"
|
||||
#endif
|
||||
|
||||
#if ENABLED(PROBE_TEMP_COMPENSATION)
|
||||
#include "../../../feature/probe_temp_comp.h"
|
||||
#include "../../../module/temperature.h"
|
||||
#endif
|
||||
|
||||
#if HAS_STATUS_MESSAGE
|
||||
#include "../../../lcd/marlinui.h"
|
||||
#include "../../../lcd/HardwareSerial.h"
|
||||
#endif
|
||||
|
||||
#if ENABLED(AUTO_BED_LEVELING_LINEAR)
|
||||
@@ -57,21 +47,22 @@
|
||||
#include "../../../libs/vector_3.h"
|
||||
#endif
|
||||
|
||||
#define DEBUG_OUT ENABLED(DEBUG_LEVELING_FEATURE)
|
||||
#include "../../../core/debug_out.h"
|
||||
|
||||
#include "../../../lcd/marlinui.h"
|
||||
#if ENABLED(EXTENSIBLE_UI)
|
||||
#include "../../../lcd/extui/ui_api.h"
|
||||
#elif ENABLED(DWIN_CREALITY_LCD)
|
||||
#include "../../../lcd/e3v2/creality/dwin.h"
|
||||
#elif ENABLED(DWIN_CREALITY_LCD_ENHANCED)
|
||||
#include "../../../lcd/e3v2/enhanced/dwin.h"
|
||||
#elif ENABLED(DWIN_LCD_PROUI)
|
||||
#include "../../../lcd/e3v2/proui/dwin.h"
|
||||
#endif
|
||||
|
||||
#if HAS_MULTI_HOTEND
|
||||
#include "../../../module/tool_change.h"
|
||||
#endif
|
||||
|
||||
#define DEBUG_OUT ENABLED(DEBUG_LEVELING_FEATURE)
|
||||
#include "../../../core/debug_out.h"
|
||||
|
||||
#if ABL_USES_GRID
|
||||
#if ENABLED(PROBE_Y_FIRST)
|
||||
#define PR_OUTER_VAR abl.meshCount.x
|
||||
@@ -86,7 +77,20 @@
|
||||
#endif
|
||||
#endif
|
||||
|
||||
#define G29_RETURN(b) return TERN_(G29_RETRY_AND_RECOVER, b)
|
||||
static void pre_g29_return(const bool retry, const bool did) {
|
||||
if (!retry) {
|
||||
TERN_(FULL_REPORT_TO_HOST_FEATURE, set_and_report_grblstate(M_IDLE, false));
|
||||
}
|
||||
if (did) {
|
||||
TERN_(HAS_DWIN_E3V2_BASIC, DWIN_LevelingDone());
|
||||
TERN_(EXTENSIBLE_UI, ExtUI::onLevelingDone());
|
||||
}
|
||||
}
|
||||
|
||||
#define G29_RETURN(retry, did) do{ \
|
||||
pre_g29_return(TERN0(G29_RETRY_AND_RECOVER, retry), did); \
|
||||
return TERN_(G29_RETRY_AND_RECOVER, retry); \
|
||||
}while(0)
|
||||
|
||||
// For manual probing values persist over multiple G29
|
||||
class G29_State {
|
||||
@@ -97,6 +101,10 @@ public:
|
||||
bool dryrun,
|
||||
reenable;
|
||||
|
||||
#if HAS_MULTI_HOTEND
|
||||
uint8_t tool_index;
|
||||
#endif
|
||||
|
||||
#if EITHER(PROBE_MANUALLY, AUTO_BED_LEVELING_LINEAR)
|
||||
int abl_probe_index;
|
||||
#endif
|
||||
@@ -127,6 +135,7 @@ public:
|
||||
|
||||
#if ENABLED(AUTO_BED_LEVELING_BILINEAR)
|
||||
float Z_offset;
|
||||
bed_mesh_t z_values;
|
||||
#endif
|
||||
|
||||
#if ENABLED(AUTO_BED_LEVELING_LINEAR)
|
||||
@@ -223,51 +232,63 @@ public:
|
||||
G29_TYPE GcodeSuite::G29() {
|
||||
DEBUG_SECTION(log_G29, "G29", DEBUGGING(LEVELING));
|
||||
|
||||
// Leveling state is persistent when done manually with multiple G29 commands
|
||||
TERN_(PROBE_MANUALLY, static) G29_State abl;
|
||||
|
||||
TERN_(FULL_REPORT_TO_HOST_FEATURE, set_and_report_grblstate(M_PROBE));
|
||||
|
||||
// Keep powered steppers from timing out
|
||||
reset_stepper_timeout();
|
||||
|
||||
// Q = Query leveling and G29 state
|
||||
const bool seenQ = EITHER(DEBUG_LEVELING_FEATURE, PROBE_MANUALLY) && parser.seen_test('Q');
|
||||
|
||||
// G29 Q is also available if debugging
|
||||
#if ENABLED(DEBUG_LEVELING_FEATURE)
|
||||
if (seenQ || DEBUGGING(LEVELING)) log_machine_info();
|
||||
if (DISABLED(PROBE_MANUALLY) && seenQ) G29_RETURN(false);
|
||||
if (DISABLED(PROBE_MANUALLY) && seenQ) G29_RETURN(false, false);
|
||||
#endif
|
||||
|
||||
// A = Abort manual probing
|
||||
// C<bool> = Generate fake probe points (DEBUG_LEVELING_FEATURE)
|
||||
const bool seenA = TERN0(PROBE_MANUALLY, parser.seen_test('A')),
|
||||
no_action = seenA || seenQ,
|
||||
faux = ENABLED(DEBUG_LEVELING_FEATURE) && DISABLED(PROBE_MANUALLY) ? parser.boolval('C') : no_action;
|
||||
|
||||
if (!no_action && planner.leveling_active && parser.boolval('O')) { // Auto-level only if needed
|
||||
// O = Don't level if leveling is already active
|
||||
if (!no_action && planner.leveling_active && parser.boolval('O')) {
|
||||
if (DEBUGGING(LEVELING)) DEBUG_ECHOLNPGM("> Auto-level not needed, skip");
|
||||
G29_RETURN(false);
|
||||
G29_RETURN(false, false);
|
||||
}
|
||||
|
||||
// Send 'N' to force homing before G29 (internal only)
|
||||
if (parser.seen_test('N'))
|
||||
process_subcommands_now_P(TERN(CAN_SET_LEVELING_AFTER_G28, PSTR("G28L0"), G28_STR));
|
||||
process_subcommands_now(TERN(CAN_SET_LEVELING_AFTER_G28, F("G28L0"), FPSTR(G28_STR)));
|
||||
|
||||
// Don't allow auto-leveling without homing first
|
||||
if (homing_needed_error()) G29_RETURN(false);
|
||||
if (homing_needed_error()) G29_RETURN(false, false);
|
||||
|
||||
// 3-point leveling gets points from the probe class
|
||||
#if ENABLED(AUTO_BED_LEVELING_3POINT)
|
||||
vector_3 points[3];
|
||||
probe.get_three_points(points);
|
||||
#endif
|
||||
|
||||
// Storage for ABL Linear results
|
||||
#if ENABLED(AUTO_BED_LEVELING_LINEAR)
|
||||
struct linear_fit_data lsf_results;
|
||||
#endif
|
||||
|
||||
// Set and report "probing" state to host
|
||||
TERN_(FULL_REPORT_TO_HOST_FEATURE, set_and_report_grblstate(M_PROBE, false));
|
||||
|
||||
/**
|
||||
* On the initial G29 fetch command parameters.
|
||||
*/
|
||||
if (!g29_in_progress) {
|
||||
|
||||
TERN_(HAS_MULTI_HOTEND, if (active_extruder) tool_change(0));
|
||||
#if HAS_MULTI_HOTEND
|
||||
abl.tool_index = active_extruder;
|
||||
if (active_extruder != 0) tool_change(0, true);
|
||||
#endif
|
||||
|
||||
#if EITHER(PROBE_MANUALLY, AUTO_BED_LEVELING_LINEAR)
|
||||
abl.abl_probe_index = -1;
|
||||
@@ -281,35 +302,43 @@ G29_TYPE GcodeSuite::G29() {
|
||||
if (seen_w) {
|
||||
if (!leveling_is_valid()) {
|
||||
SERIAL_ERROR_MSG("No bilinear grid");
|
||||
G29_RETURN(false);
|
||||
G29_RETURN(false, false);
|
||||
}
|
||||
|
||||
const float rz = parser.seenval('Z') ? RAW_Z_POSITION(parser.value_linear_units()) : current_position.z;
|
||||
if (!WITHIN(rz, -10, 10)) {
|
||||
SERIAL_ERROR_MSG("Bad Z value");
|
||||
G29_RETURN(false);
|
||||
G29_RETURN(false, false);
|
||||
}
|
||||
|
||||
const float rx = RAW_X_POSITION(parser.linearval('X', NAN)),
|
||||
ry = RAW_Y_POSITION(parser.linearval('Y', NAN));
|
||||
int8_t i = parser.byteval('I', -1), j = parser.byteval('J', -1);
|
||||
|
||||
#pragma GCC diagnostic push
|
||||
#pragma GCC diagnostic ignored "-Wmaybe-uninitialized"
|
||||
|
||||
if (!isnan(rx) && !isnan(ry)) {
|
||||
// Get nearest i / j from rx / ry
|
||||
i = (rx - bilinear_start.x + 0.5 * abl.gridSpacing.x) / abl.gridSpacing.x;
|
||||
j = (ry - bilinear_start.y + 0.5 * abl.gridSpacing.y) / abl.gridSpacing.y;
|
||||
i = (rx - bedlevel.grid_start.x) / bedlevel.grid_spacing.x + 0.5f;
|
||||
j = (ry - bedlevel.grid_start.y) / bedlevel.grid_spacing.y + 0.5f;
|
||||
LIMIT(i, 0, (GRID_MAX_POINTS_X) - 1);
|
||||
LIMIT(j, 0, (GRID_MAX_POINTS_Y) - 1);
|
||||
}
|
||||
|
||||
#pragma GCC diagnostic pop
|
||||
|
||||
if (WITHIN(i, 0, (GRID_MAX_POINTS_X) - 1) && WITHIN(j, 0, (GRID_MAX_POINTS_Y) - 1)) {
|
||||
set_bed_leveling_enabled(false);
|
||||
z_values[i][j] = rz;
|
||||
TERN_(ABL_BILINEAR_SUBDIVISION, bed_level_virt_interpolate());
|
||||
bedlevel.z_values[i][j] = rz;
|
||||
bedlevel.refresh_bed_level();
|
||||
TERN_(EXTENSIBLE_UI, ExtUI::onMeshUpdate(i, j, rz));
|
||||
set_bed_leveling_enabled(abl.reenable);
|
||||
if (abl.reenable) report_current_position();
|
||||
if (abl.reenable) {
|
||||
set_bed_leveling_enabled(true);
|
||||
report_current_position();
|
||||
}
|
||||
}
|
||||
G29_RETURN(false);
|
||||
G29_RETURN(false, false);
|
||||
} // parser.seen_test('W')
|
||||
|
||||
#else
|
||||
@@ -321,13 +350,13 @@ G29_TYPE GcodeSuite::G29() {
|
||||
// Jettison bed leveling data
|
||||
if (!seen_w && parser.seen_test('J')) {
|
||||
reset_bed_level();
|
||||
G29_RETURN(false);
|
||||
G29_RETURN(false, false);
|
||||
}
|
||||
|
||||
abl.verbose_level = parser.intval('V');
|
||||
if (!WITHIN(abl.verbose_level, 0, 4)) {
|
||||
SERIAL_ECHOLNPGM("?(V)erbose level implausible (0-4).");
|
||||
G29_RETURN(false);
|
||||
G29_RETURN(false, false);
|
||||
}
|
||||
|
||||
abl.dryrun = parser.boolval('D') || TERN0(PROBE_MANUALLY, no_action);
|
||||
@@ -348,11 +377,11 @@ G29_TYPE GcodeSuite::G29() {
|
||||
|
||||
if (!WITHIN(abl.grid_points.x, 2, GRID_MAX_POINTS_X)) {
|
||||
SERIAL_ECHOLNPGM("?Probe points (X) implausible (2-" STRINGIFY(GRID_MAX_POINTS_X) ").");
|
||||
G29_RETURN(false);
|
||||
G29_RETURN(false, false);
|
||||
}
|
||||
if (!WITHIN(abl.grid_points.y, 2, GRID_MAX_POINTS_Y)) {
|
||||
SERIAL_ECHOLNPGM("?Probe points (Y) implausible (2-" STRINGIFY(GRID_MAX_POINTS_Y) ").");
|
||||
G29_RETURN(false);
|
||||
G29_RETURN(false, false);
|
||||
}
|
||||
|
||||
abl.abl_points = abl.grid_points.x * abl.grid_points.y;
|
||||
@@ -387,7 +416,7 @@ G29_TYPE GcodeSuite::G29() {
|
||||
" F", abl.probe_position_lf.y, " B", abl.probe_position_rb.y);
|
||||
}
|
||||
SERIAL_ECHOLNPGM("? (L,R,F,B) out of bounds.");
|
||||
G29_RETURN(false);
|
||||
G29_RETURN(false, false);
|
||||
}
|
||||
|
||||
// Probe at the points of a lattice grid
|
||||
@@ -408,46 +437,89 @@ G29_TYPE GcodeSuite::G29() {
|
||||
if (DEBUGGING(LEVELING)) DEBUG_ECHOLNPGM("> 3-point Leveling");
|
||||
points[0].z = points[1].z = points[2].z = 0; // Probe at 3 arbitrary points
|
||||
#elif ENABLED(AUTO_BED_LEVELING_BILINEAR)
|
||||
TERN_(EXTENSIBLE_UI, ExtUI::onMeshLevelingStart());
|
||||
TERN_(DWIN_CREALITY_LCD_ENHANCED, DWIN_MeshLevelingStart());
|
||||
TERN_(DWIN_LCD_PROUI, DWIN_LevelingStart());
|
||||
#endif
|
||||
|
||||
TERN_(EXTENSIBLE_UI, ExtUI::onLevelingStart());
|
||||
|
||||
if (!faux) {
|
||||
remember_feedrate_scaling_off();
|
||||
|
||||
#if ENABLED(PREHEAT_BEFORE_LEVELING)
|
||||
if (!abl.dryrun) probe.preheat_for_probing(LEVELING_NOZZLE_TEMP, LEVELING_BED_TEMP);
|
||||
if (!abl.dryrun) probe.preheat_for_probing(LEVELING_NOZZLE_TEMP,
|
||||
#if BOTH(DWIN_LCD_PROUI, HAS_HEATED_BED)
|
||||
HMI_data.BedLevT
|
||||
#else
|
||||
LEVELING_BED_TEMP
|
||||
#endif
|
||||
);
|
||||
#endif
|
||||
}
|
||||
|
||||
// Position bed horizontally and Z probe vertically.
|
||||
#if defined(SAFE_BED_LEVELING_START_X) || defined(SAFE_BED_LEVELING_START_Y) || defined(SAFE_BED_LEVELING_START_Z) \
|
||||
|| defined(SAFE_BED_LEVELING_START_I) || defined(SAFE_BED_LEVELING_START_J) || defined(SAFE_BED_LEVELING_START_K) \
|
||||
|| defined(SAFE_BED_LEVELING_START_U) || defined(SAFE_BED_LEVELING_START_V) || defined(SAFE_BED_LEVELING_START_W)
|
||||
xyze_pos_t safe_position = current_position;
|
||||
#ifdef SAFE_BED_LEVELING_START_X
|
||||
safe_position.x = SAFE_BED_LEVELING_START_X;
|
||||
#endif
|
||||
#ifdef SAFE_BED_LEVELING_START_Y
|
||||
safe_position.y = SAFE_BED_LEVELING_START_Y;
|
||||
#endif
|
||||
#ifdef SAFE_BED_LEVELING_START_Z
|
||||
safe_position.z = SAFE_BED_LEVELING_START_Z;
|
||||
#endif
|
||||
#ifdef SAFE_BED_LEVELING_START_I
|
||||
safe_position.i = SAFE_BED_LEVELING_START_I;
|
||||
#endif
|
||||
#ifdef SAFE_BED_LEVELING_START_J
|
||||
safe_position.j = SAFE_BED_LEVELING_START_J;
|
||||
#endif
|
||||
#ifdef SAFE_BED_LEVELING_START_K
|
||||
safe_position.k = SAFE_BED_LEVELING_START_K;
|
||||
#endif
|
||||
#ifdef SAFE_BED_LEVELING_START_U
|
||||
safe_position.u = SAFE_BED_LEVELING_START_U;
|
||||
#endif
|
||||
#ifdef SAFE_BED_LEVELING_START_V
|
||||
safe_position.v = SAFE_BED_LEVELING_START_V;
|
||||
#endif
|
||||
#ifdef SAFE_BED_LEVELING_START_W
|
||||
safe_position.w = SAFE_BED_LEVELING_START_W;
|
||||
#endif
|
||||
|
||||
do_blocking_move_to(safe_position);
|
||||
#endif
|
||||
|
||||
// Disable auto bed leveling during G29.
|
||||
// Be formal so G29 can be done successively without G28.
|
||||
if (!no_action) set_bed_leveling_enabled(false);
|
||||
|
||||
// Deploy certain probes before starting probing
|
||||
#if HAS_BED_PROBE
|
||||
if (ENABLED(BLTOUCH))
|
||||
do_z_clearance(Z_CLEARANCE_DEPLOY_PROBE);
|
||||
else if (probe.deploy()) {
|
||||
#if ENABLED(BLTOUCH)
|
||||
do_z_clearance(Z_CLEARANCE_DEPLOY_PROBE);
|
||||
#elif HAS_BED_PROBE
|
||||
if (probe.deploy()) { // (returns true on deploy failure)
|
||||
set_bed_leveling_enabled(abl.reenable);
|
||||
G29_RETURN(false);
|
||||
G29_RETURN(false, true);
|
||||
}
|
||||
#endif
|
||||
|
||||
#if ENABLED(AUTO_BED_LEVELING_BILINEAR)
|
||||
if (TERN1(PROBE_MANUALLY, !no_action)
|
||||
&& (abl.gridSpacing != bilinear_grid_spacing || abl.probe_position_lf != bilinear_start)
|
||||
if (!abl.dryrun
|
||||
&& (abl.gridSpacing != bedlevel.grid_spacing || abl.probe_position_lf != bedlevel.grid_start)
|
||||
) {
|
||||
// Reset grid to 0.0 or "not probed". (Also disables ABL)
|
||||
reset_bed_level();
|
||||
|
||||
// Initialize a grid with the given dimensions
|
||||
bilinear_grid_spacing = abl.gridSpacing;
|
||||
bilinear_start = abl.probe_position_lf;
|
||||
|
||||
// Can't re-enable (on error) until the new grid is written
|
||||
abl.reenable = false;
|
||||
}
|
||||
|
||||
// Pre-populate local Z values from the stored mesh
|
||||
TERN_(IS_KINEMATIC, COPY(abl.z_values, bedlevel.z_values));
|
||||
|
||||
#endif // AUTO_BED_LEVELING_BILINEAR
|
||||
|
||||
} // !g29_in_progress
|
||||
@@ -479,7 +551,8 @@ G29_TYPE GcodeSuite::G29() {
|
||||
SERIAL_ECHOLNPGM("idle");
|
||||
}
|
||||
|
||||
if (no_action) G29_RETURN(false);
|
||||
// For 'A' or 'Q' exit with success state
|
||||
if (no_action) G29_RETURN(false, true);
|
||||
|
||||
if (abl.abl_probe_index == 0) {
|
||||
// For the initial G29 S2 save software endstop state
|
||||
@@ -514,7 +587,7 @@ G29_TYPE GcodeSuite::G29() {
|
||||
#elif ENABLED(AUTO_BED_LEVELING_BILINEAR)
|
||||
|
||||
const float newz = abl.measured_z + abl.Z_offset;
|
||||
z_values[abl.meshCount.x][abl.meshCount.y] = newz;
|
||||
abl.z_values[abl.meshCount.x][abl.meshCount.y] = newz;
|
||||
TERN_(EXTENSIBLE_UI, ExtUI::onMeshUpdate(abl.meshCount, newz));
|
||||
|
||||
if (DEBUGGING(LEVELING)) DEBUG_ECHOLNPGM_P(PSTR("Save X"), abl.meshCount.x, SP_Y_STR, abl.meshCount.y, SP_Z_STR, abl.measured_z + abl.Z_offset);
|
||||
@@ -554,7 +627,7 @@ G29_TYPE GcodeSuite::G29() {
|
||||
// Disable software endstops to allow manual adjustment
|
||||
// If G29 is not completed, they will not be re-enabled
|
||||
SET_SOFT_ENDSTOP_LOOSE(true);
|
||||
G29_RETURN(false);
|
||||
G29_RETURN(false, true);
|
||||
}
|
||||
else {
|
||||
// Leveling done! Fall through to G29 finishing code below
|
||||
@@ -572,7 +645,7 @@ G29_TYPE GcodeSuite::G29() {
|
||||
// Disable software endstops to allow manual adjustment
|
||||
// If G29 is not completed, they will not be re-enabled
|
||||
SET_SOFT_ENDSTOP_LOOSE(true);
|
||||
G29_RETURN(false);
|
||||
G29_RETURN(false, true);
|
||||
}
|
||||
else {
|
||||
|
||||
@@ -604,8 +677,6 @@ G29_TYPE GcodeSuite::G29() {
|
||||
|
||||
bool zig = PR_OUTER_SIZE & 1; // Always end at RIGHT and BACK_PROBE_BED_POSITION
|
||||
|
||||
abl.measured_z = 0;
|
||||
|
||||
// Outer loop is X with PROBE_Y_FIRST enabled
|
||||
// Outer loop is Y with PROBE_Y_FIRST disabled
|
||||
for (PR_OUTER_VAR = 0; PR_OUTER_VAR < PR_OUTER_SIZE && !isnan(abl.measured_z); PR_OUTER_VAR++) {
|
||||
@@ -640,7 +711,7 @@ G29_TYPE GcodeSuite::G29() {
|
||||
if (TERN0(IS_KINEMATIC, !probe.can_reach(abl.probePos))) continue;
|
||||
|
||||
if (abl.verbose_level) SERIAL_ECHOLNPGM("Probing mesh point ", pt_index, "/", abl.abl_points, ".");
|
||||
TERN_(HAS_STATUS_MESSAGE, ui.status_printf_P(0, PSTR(S_FMT " %i/%i"), GET_TEXT(MSG_PROBING_POINT), int(pt_index), int(abl.abl_points)));
|
||||
TERN_(HAS_STATUS_MESSAGE, ui.status_printf(0, F(S_FMT " %i/%i"), GET_TEXT(MSG_PROBING_POINT), int(pt_index), int(abl.abl_points)));
|
||||
|
||||
abl.measured_z = faux ? 0.001f * random(-100, 101) : probe.probe_at_point(abl.probePos, raise_after, abl.verbose_level);
|
||||
|
||||
@@ -649,12 +720,6 @@ G29_TYPE GcodeSuite::G29() {
|
||||
break; // Breaks out of both loops
|
||||
}
|
||||
|
||||
#if ENABLED(PROBE_TEMP_COMPENSATION)
|
||||
temp_comp.compensate_measurement(TSI_BED, thermalManager.degBed(), abl.measured_z);
|
||||
temp_comp.compensate_measurement(TSI_PROBE, thermalManager.degProbe(), abl.measured_z);
|
||||
TERN_(USE_TEMP_EXT_COMPENSATION, temp_comp.compensate_measurement(TSI_EXT, thermalManager.degHotend(), abl.measured_z));
|
||||
#endif
|
||||
|
||||
#if ENABLED(AUTO_BED_LEVELING_LINEAR)
|
||||
|
||||
abl.mean += abl.measured_z;
|
||||
@@ -668,12 +733,12 @@ G29_TYPE GcodeSuite::G29() {
|
||||
#elif ENABLED(AUTO_BED_LEVELING_BILINEAR)
|
||||
|
||||
const float z = abl.measured_z + abl.Z_offset;
|
||||
z_values[abl.meshCount.x][abl.meshCount.y] = z;
|
||||
abl.z_values[abl.meshCount.x][abl.meshCount.y] = z;
|
||||
TERN_(EXTENSIBLE_UI, ExtUI::onMeshUpdate(abl.meshCount, z));
|
||||
|
||||
#endif
|
||||
|
||||
abl.reenable = false;
|
||||
abl.reenable = false; // Don't re-enable after modifying the mesh
|
||||
idle_no_sleep();
|
||||
|
||||
} // inner
|
||||
@@ -685,7 +750,7 @@ G29_TYPE GcodeSuite::G29() {
|
||||
|
||||
LOOP_L_N(i, 3) {
|
||||
if (abl.verbose_level) SERIAL_ECHOLNPGM("Probing point ", i + 1, "/3.");
|
||||
TERN_(HAS_STATUS_MESSAGE, ui.status_printf_P(0, PSTR(S_FMT " %i/3"), GET_TEXT(MSG_PROBING_POINT), int(i + 1)));
|
||||
TERN_(HAS_STATUS_MESSAGE, ui.status_printf(0, F(S_FMT " %i/3"), GET_TEXT(MSG_PROBING_POINT), int(i + 1)));
|
||||
|
||||
// Retain the last probe position
|
||||
abl.probePos = xy_pos_t(points[i]);
|
||||
@@ -739,17 +804,22 @@ G29_TYPE GcodeSuite::G29() {
|
||||
if (!isnan(abl.measured_z)) {
|
||||
#if ENABLED(AUTO_BED_LEVELING_BILINEAR)
|
||||
|
||||
if (!abl.dryrun) extrapolate_unprobed_bed_level();
|
||||
print_bilinear_leveling_grid();
|
||||
if (abl.dryrun)
|
||||
bedlevel.print_leveling_grid(&abl.z_values);
|
||||
else {
|
||||
bedlevel.set_grid(abl.gridSpacing, abl.probe_position_lf);
|
||||
COPY(bedlevel.z_values, abl.z_values);
|
||||
TERN_(IS_KINEMATIC, bedlevel.extrapolate_unprobed_bed_level());
|
||||
|
||||
#if ENABLED(KNUTWURST_TFT_LEVELING)
|
||||
#if ENABLED(KNUTWURST_TFT_LEVELING)
|
||||
HARDWARE_SERIAL_PROTOCOLPGM("J25"); // Autoleveling done!
|
||||
HARDWARE_SERIAL_ENTER();
|
||||
#endif
|
||||
#endif
|
||||
|
||||
refresh_bed_level();
|
||||
bedlevel.refresh_bed_level();
|
||||
|
||||
TERN_(ABL_BILINEAR_SUBDIVISION, print_bilinear_leveling_grid_virt());
|
||||
bedlevel.print_leveling_grid();
|
||||
}
|
||||
|
||||
#elif ENABLED(AUTO_BED_LEVELING_LINEAR)
|
||||
|
||||
@@ -792,8 +862,8 @@ G29_TYPE GcodeSuite::G29() {
|
||||
|
||||
float min_diff = 999;
|
||||
|
||||
auto print_topo_map = [&](PGM_P const title, const bool get_min) {
|
||||
SERIAL_ECHOPGM_P(title);
|
||||
auto print_topo_map = [&](FSTR_P const title, const bool get_min) {
|
||||
SERIAL_ECHOF(title);
|
||||
for (int8_t yy = abl.grid_points.y - 1; yy >= 0; yy--) {
|
||||
LOOP_L_N(xx, abl.grid_points.x) {
|
||||
const int ind = abl.indexIntoAB[xx][yy];
|
||||
@@ -811,19 +881,19 @@ G29_TYPE GcodeSuite::G29() {
|
||||
SERIAL_EOL();
|
||||
};
|
||||
|
||||
print_topo_map(PSTR("\nBed Height Topography:\n"
|
||||
" +--- BACK --+\n"
|
||||
" | |\n"
|
||||
" L | (+) | R\n"
|
||||
" E | | I\n"
|
||||
" F | (-) N (+) | G\n"
|
||||
" T | | H\n"
|
||||
" | (-) | T\n"
|
||||
" | |\n"
|
||||
" O-- FRONT --+\n"
|
||||
" (0,0)\n"), true);
|
||||
print_topo_map(F("\nBed Height Topography:\n"
|
||||
" +--- BACK --+\n"
|
||||
" | |\n"
|
||||
" L | (+) | R\n"
|
||||
" E | | I\n"
|
||||
" F | (-) N (+) | G\n"
|
||||
" T | | H\n"
|
||||
" | (-) | T\n"
|
||||
" | |\n"
|
||||
" O-- FRONT --+\n"
|
||||
" (0,0)\n"), true);
|
||||
if (abl.verbose_level > 3)
|
||||
print_topo_map(PSTR("\nCorrected Bed Height vs. Bed Topology:\n"), false);
|
||||
print_topo_map(F("\nCorrected Bed Height vs. Bed Topology:\n"), false);
|
||||
|
||||
} // abl.topography_map
|
||||
|
||||
@@ -834,7 +904,7 @@ G29_TYPE GcodeSuite::G29() {
|
||||
// For LINEAR and 3POINT leveling correct the current position
|
||||
|
||||
if (abl.verbose_level > 0)
|
||||
planner.bed_level_matrix.debug(PSTR("\n\nBed Level Correction Matrix:"));
|
||||
planner.bed_level_matrix.debug(F("\n\nBed Level Correction Matrix:"));
|
||||
|
||||
if (!abl.dryrun) {
|
||||
//
|
||||
@@ -859,49 +929,41 @@ G29_TYPE GcodeSuite::G29() {
|
||||
current_position = converted;
|
||||
|
||||
if (DEBUGGING(LEVELING)) DEBUG_POS("G29 corrected XYZ", current_position);
|
||||
|
||||
abl.reenable = true;
|
||||
}
|
||||
|
||||
// Auto Bed Leveling is complete! Enable if possible.
|
||||
if (abl.reenable) {
|
||||
planner.leveling_active = true;
|
||||
sync_plan_position();
|
||||
}
|
||||
|
||||
#elif ENABLED(AUTO_BED_LEVELING_BILINEAR)
|
||||
|
||||
if (!abl.dryrun) {
|
||||
if (DEBUGGING(LEVELING)) DEBUG_ECHOLNPGM("G29 uncorrected Z:", current_position.z);
|
||||
// Auto Bed Leveling is complete! Enable if possible.
|
||||
if (!abl.dryrun || abl.reenable) set_bed_leveling_enabled(true);
|
||||
|
||||
// Unapply the offset because it is going to be immediately applied
|
||||
// and cause compensation movement in Z
|
||||
const float fade_scaling_factor = TERN(ENABLE_LEVELING_FADE_HEIGHT, planner.fade_scaling_factor_for_z(current_position.z), 1);
|
||||
current_position.z -= fade_scaling_factor * bilinear_z_offset(current_position);
|
||||
#endif
|
||||
|
||||
if (DEBUGGING(LEVELING)) DEBUG_ECHOLNPGM(" corrected Z:", current_position.z);
|
||||
}
|
||||
|
||||
#endif // ABL_PLANAR
|
||||
|
||||
// Auto Bed Leveling is complete! Enable if possible.
|
||||
planner.leveling_active = !abl.dryrun || abl.reenable;
|
||||
} // !isnan(abl.measured_z)
|
||||
|
||||
// Restore state after probing
|
||||
if (!faux) restore_feedrate_and_scaling();
|
||||
|
||||
// Sync the planner from the current_position
|
||||
if (planner.leveling_active) sync_plan_position();
|
||||
|
||||
TERN_(HAS_BED_PROBE, probe.move_z_after_probing());
|
||||
|
||||
#ifdef Z_PROBE_END_SCRIPT
|
||||
if (DEBUGGING(LEVELING)) DEBUG_ECHOLNPGM("Z Probe End Script: ", Z_PROBE_END_SCRIPT);
|
||||
planner.synchronize();
|
||||
process_subcommands_now_P(PSTR(Z_PROBE_END_SCRIPT));
|
||||
process_subcommands_now(F(Z_PROBE_END_SCRIPT));
|
||||
#endif
|
||||
|
||||
TERN_(HAS_DWIN_E3V2_BASIC, DWIN_CompletedLeveling());
|
||||
TERN_(HAS_MULTI_HOTEND, if (abl.tool_index != 0) tool_change(abl.tool_index));
|
||||
|
||||
report_current_position();
|
||||
|
||||
TERN_(FULL_REPORT_TO_HOST_FEATURE, set_and_report_grblstate(M_IDLE));
|
||||
|
||||
G29_RETURN(isnan(abl.measured_z));
|
||||
|
||||
G29_RETURN(isnan(abl.measured_z), true);
|
||||
}
|
||||
|
||||
#endif // HAS_ABL_NOT_UBL
|
||||
|
@@ -58,11 +58,11 @@ void GcodeSuite::M421() {
|
||||
sy = iy >= 0 ? iy : 0, ey = iy >= 0 ? iy : GRID_MAX_POINTS_Y - 1;
|
||||
LOOP_S_LE_N(x, sx, ex) {
|
||||
LOOP_S_LE_N(y, sy, ey) {
|
||||
z_values[x][y] = zval + (hasQ ? z_values[x][y] : 0);
|
||||
TERN_(EXTENSIBLE_UI, ExtUI::onMeshUpdate(x, y, z_values[x][y]));
|
||||
bedlevel.z_values[x][y] = zval + (hasQ ? bedlevel.z_values[x][y] : 0);
|
||||
TERN_(EXTENSIBLE_UI, ExtUI::onMeshUpdate(x, y, bedlevel.z_values[x][y]));
|
||||
}
|
||||
}
|
||||
TERN_(ABL_BILINEAR_SUBDIVISION, bed_level_virt_interpolate());
|
||||
bedlevel.refresh_bed_level();
|
||||
}
|
||||
else
|
||||
SERIAL_ERROR_MSG(STR_ERR_MESH_XY);
|
||||
|
@@ -36,12 +36,12 @@
|
||||
#include "../../../libs/buzzer.h"
|
||||
#include "../../../lcd/marlinui.h"
|
||||
#include "../../../module/motion.h"
|
||||
#include "../../../module/stepper.h"
|
||||
#include "../../../module/planner.h"
|
||||
|
||||
#if ENABLED(EXTENSIBLE_UI)
|
||||
#include "../../../lcd/extui/ui_api.h"
|
||||
#elif ENABLED(DWIN_CREALITY_LCD_ENHANCED)
|
||||
#include "../../../lcd/e3v2/enhanced/dwin.h"
|
||||
#elif ENABLED(DWIN_LCD_PROUI)
|
||||
#include "../../../lcd/e3v2/proui/dwin.h"
|
||||
#endif
|
||||
|
||||
#define DEBUG_OUT ENABLED(DEBUG_LEVELING_FEATURE)
|
||||
@@ -75,8 +75,6 @@ void GcodeSuite::G29() {
|
||||
}
|
||||
#endif
|
||||
|
||||
TERN_(FULL_REPORT_TO_HOST_FEATURE, set_and_report_grblstate(M_PROBE));
|
||||
|
||||
static int mbl_probe_index = -1;
|
||||
|
||||
MeshLevelingState state = (MeshLevelingState)parser.byteval('S', (int8_t)MeshReport);
|
||||
@@ -85,6 +83,8 @@ void GcodeSuite::G29() {
|
||||
return;
|
||||
}
|
||||
|
||||
TERN_(FULL_REPORT_TO_HOST_FEATURE, set_and_report_grblstate(M_PROBE));
|
||||
|
||||
int8_t ix, iy;
|
||||
ix = iy = 0;
|
||||
|
||||
@@ -93,18 +93,56 @@ void GcodeSuite::G29() {
|
||||
SERIAL_ECHOPGM("Mesh Bed Leveling ");
|
||||
if (leveling_is_valid()) {
|
||||
serialprintln_onoff(planner.leveling_active);
|
||||
mbl.report_mesh();
|
||||
bedlevel.report_mesh();
|
||||
}
|
||||
else
|
||||
SERIAL_ECHOLNPGM("has no data.");
|
||||
break;
|
||||
|
||||
case MeshStart:
|
||||
mbl.reset();
|
||||
bedlevel.reset();
|
||||
mbl_probe_index = 0;
|
||||
if (!ui.wait_for_move) {
|
||||
queue.inject_P(parser.seen_test('N') ? PSTR("G28" TERN(CAN_SET_LEVELING_AFTER_G28, "L0", "") "\nG29S2") : PSTR("G29S2"));
|
||||
TERN_(EXTENSIBLE_UI, ExtUI::onMeshLevelingStart());
|
||||
queue.inject(parser.seen_test('N') ? F("G28" TERN(CAN_SET_LEVELING_AFTER_G28, "L0", "") "\nG29S2") : F("G29S2"));
|
||||
TERN_(EXTENSIBLE_UI, ExtUI::onLevelingStart());
|
||||
TERN_(DWIN_LCD_PROUI, DWIN_LevelingStart());
|
||||
|
||||
// Position bed horizontally and Z probe vertically.
|
||||
#if defined(SAFE_BED_LEVELING_START_X) || defined(SAFE_BED_LEVELING_START_Y) || defined(SAFE_BED_LEVELING_START_Z) \
|
||||
|| defined(SAFE_BED_LEVELING_START_I) || defined(SAFE_BED_LEVELING_START_J) || defined(SAFE_BED_LEVELING_START_K) \
|
||||
|| defined(SAFE_BED_LEVELING_START_U) || defined(SAFE_BED_LEVELING_START_V) || defined(SAFE_BED_LEVELING_START_W)
|
||||
xyze_pos_t safe_position = current_position;
|
||||
#ifdef SAFE_BED_LEVELING_START_X
|
||||
safe_position.x = SAFE_BED_LEVELING_START_X;
|
||||
#endif
|
||||
#ifdef SAFE_BED_LEVELING_START_Y
|
||||
safe_position.y = SAFE_BED_LEVELING_START_Y;
|
||||
#endif
|
||||
#ifdef SAFE_BED_LEVELING_START_Z
|
||||
safe_position.z = SAFE_BED_LEVELING_START_Z;
|
||||
#endif
|
||||
#ifdef SAFE_BED_LEVELING_START_I
|
||||
safe_position.i = SAFE_BED_LEVELING_START_I;
|
||||
#endif
|
||||
#ifdef SAFE_BED_LEVELING_START_J
|
||||
safe_position.j = SAFE_BED_LEVELING_START_J;
|
||||
#endif
|
||||
#ifdef SAFE_BED_LEVELING_START_K
|
||||
safe_position.k = SAFE_BED_LEVELING_START_K;
|
||||
#endif
|
||||
#ifdef SAFE_BED_LEVELING_START_U
|
||||
safe_position.u = SAFE_BED_LEVELING_START_U;
|
||||
#endif
|
||||
#ifdef SAFE_BED_LEVELING_START_V
|
||||
safe_position.v = SAFE_BED_LEVELING_START_V;
|
||||
#endif
|
||||
#ifdef SAFE_BED_LEVELING_START_W
|
||||
safe_position.w = SAFE_BED_LEVELING_START_W;
|
||||
#endif
|
||||
|
||||
do_blocking_move_to(safe_position);
|
||||
#endif
|
||||
|
||||
return;
|
||||
}
|
||||
state = MeshNext;
|
||||
@@ -117,16 +155,19 @@ void GcodeSuite::G29() {
|
||||
// For each G29 S2...
|
||||
if (mbl_probe_index == 0) {
|
||||
// Move close to the bed before the first point
|
||||
do_blocking_move_to_z(0.4f
|
||||
do_blocking_move_to_z(
|
||||
#ifdef MANUAL_PROBE_START_Z
|
||||
+ (MANUAL_PROBE_START_Z) - 0.4f
|
||||
MANUAL_PROBE_START_Z
|
||||
#else
|
||||
0.4f
|
||||
#endif
|
||||
);
|
||||
}
|
||||
else {
|
||||
// Save Z for the previous mesh position
|
||||
mbl.set_zigzag_z(mbl_probe_index - 1, current_position.z);
|
||||
bedlevel.set_zigzag_z(mbl_probe_index - 1, current_position.z);
|
||||
TERN_(EXTENSIBLE_UI, ExtUI::onMeshUpdate(ix, iy, current_position.z));
|
||||
TERN_(DWIN_LCD_PROUI, DWIN_MeshUpdate(_MIN(mbl_probe_index, GRID_MAX_POINTS), int(GRID_MAX_POINTS), current_position.z));
|
||||
SET_SOFT_ENDSTOP_LOOSE(false);
|
||||
}
|
||||
// If there's another point to sample, move there with optional lift.
|
||||
@@ -134,8 +175,8 @@ void GcodeSuite::G29() {
|
||||
// Disable software endstops to allow manual adjustment
|
||||
// If G29 is left hanging without completion they won't be re-enabled!
|
||||
SET_SOFT_ENDSTOP_LOOSE(true);
|
||||
mbl.zigzag(mbl_probe_index++, ix, iy);
|
||||
_manual_goto_xy({ mbl.index_to_xpos[ix], mbl.index_to_ypos[iy] });
|
||||
bedlevel.zigzag(mbl_probe_index++, ix, iy);
|
||||
_manual_goto_xy({ bedlevel.index_to_xpos[ix], bedlevel.index_to_ypos[iy] });
|
||||
}
|
||||
else {
|
||||
// Move to the after probing position
|
||||
@@ -152,9 +193,8 @@ void GcodeSuite::G29() {
|
||||
// After recording the last point, activate home and activate
|
||||
mbl_probe_index = -1;
|
||||
SERIAL_ECHOLNPGM("Mesh probing done.");
|
||||
TERN_(HAS_STATUS_MESSAGE, ui.set_status(GET_TEXT(MSG_MESH_DONE)));
|
||||
BUZZ(100, 659);
|
||||
BUZZ(100, 698);
|
||||
TERN_(HAS_STATUS_MESSAGE, LCD_MESSAGE(MSG_MESH_DONE));
|
||||
OKAY_BUZZ();
|
||||
|
||||
home_all_axes();
|
||||
set_bed_leveling_enabled(true);
|
||||
@@ -166,6 +206,7 @@ void GcodeSuite::G29() {
|
||||
#endif
|
||||
|
||||
TERN_(LCD_BED_LEVELING, ui.wait_for_move = false);
|
||||
TERN_(EXTENSIBLE_UI, ExtUI::onLevelingDone());
|
||||
}
|
||||
break;
|
||||
|
||||
@@ -191,9 +232,9 @@ void GcodeSuite::G29() {
|
||||
return echo_not_entered('J');
|
||||
|
||||
if (parser.seenval('Z')) {
|
||||
mbl.z_values[ix][iy] = parser.value_linear_units();
|
||||
TERN_(EXTENSIBLE_UI, ExtUI::onMeshUpdate(ix, iy, mbl.z_values[ix][iy]));
|
||||
TERN_(DWIN_CREALITY_LCD_ENHANCED, DWIN_MeshUpdate(ix, iy, mbl.z_values[ix][iy]));
|
||||
bedlevel.z_values[ix][iy] = parser.value_linear_units();
|
||||
TERN_(EXTENSIBLE_UI, ExtUI::onMeshUpdate(ix, iy, bedlevel.z_values[ix][iy]));
|
||||
TERN_(DWIN_LCD_PROUI, DWIN_MeshUpdate(ix, iy, bedlevel.z_values[ix][iy]));
|
||||
}
|
||||
else
|
||||
return echo_not_entered('Z');
|
||||
@@ -201,7 +242,7 @@ void GcodeSuite::G29() {
|
||||
|
||||
case MeshSetZOffset:
|
||||
if (parser.seenval('Z'))
|
||||
mbl.z_offset = parser.value_linear_units();
|
||||
bedlevel.z_offset = parser.value_linear_units();
|
||||
else
|
||||
return echo_not_entered('Z');
|
||||
break;
|
||||
@@ -214,7 +255,7 @@ void GcodeSuite::G29() {
|
||||
|
||||
if (state == MeshNext) {
|
||||
SERIAL_ECHOLNPGM("MBL G29 point ", _MIN(mbl_probe_index, GRID_MAX_POINTS), " of ", GRID_MAX_POINTS);
|
||||
if (mbl_probe_index > 0) TERN_(HAS_STATUS_MESSAGE, ui.status_printf_P(0, PSTR(S_FMT " %i/%i"), GET_TEXT(MSG_PROBING_POINT), _MIN(mbl_probe_index, GRID_MAX_POINTS), int(GRID_MAX_POINTS)));
|
||||
if (mbl_probe_index > 0) TERN_(HAS_STATUS_MESSAGE, ui.status_printf(0, F(S_FMT " %i/%i"), GET_TEXT(MSG_PROBING_POINT), _MIN(mbl_probe_index, GRID_MAX_POINTS), int(GRID_MAX_POINTS)));
|
||||
}
|
||||
|
||||
report_current_position();
|
||||
|
@@ -43,9 +43,9 @@
|
||||
*/
|
||||
void GcodeSuite::M421() {
|
||||
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 ? bedlevel.probe_index_x(RAW_X_POSITION(parser.value_linear_units())) : -1;
|
||||
const bool hasY = parser.seen('Y'), hasJ = parser.seen('J');
|
||||
const int8_t iy = hasJ ? parser.value_int() : hasY ? mbl.probe_index_y(RAW_Y_POSITION(parser.value_linear_units())) : -1;
|
||||
const int8_t iy = hasJ ? parser.value_int() : hasY ? bedlevel.probe_index_y(RAW_Y_POSITION(parser.value_linear_units())) : -1;
|
||||
const bool hasZ = parser.seen('Z'), hasQ = !hasZ && parser.seen('Q');
|
||||
|
||||
if (int(hasI && hasJ) + int(hasX && hasY) != 1 || !(hasZ || hasQ))
|
||||
@@ -53,7 +53,7 @@ void GcodeSuite::M421() {
|
||||
else if (ix < 0 || iy < 0)
|
||||
SERIAL_ERROR_MSG(STR_ERR_MESH_XY);
|
||||
else
|
||||
mbl.set_z(ix, iy, parser.value_linear_units() + (hasQ ? mbl.z_values[ix][iy] : 0));
|
||||
bedlevel.set_z(ix, iy, parser.value_linear_units() + (hasQ ? bedlevel.z_values[ix][iy] : 0));
|
||||
}
|
||||
|
||||
#endif // MESH_BED_LEVELING
|
||||
|
@@ -39,7 +39,7 @@ void GcodeSuite::G29() {
|
||||
|
||||
TERN_(FULL_REPORT_TO_HOST_FEATURE, set_and_report_grblstate(M_PROBE));
|
||||
|
||||
ubl.G29();
|
||||
bedlevel.G29();
|
||||
|
||||
TERN_(FULL_REPORT_TO_HOST_FEATURE, set_and_report_grblstate(M_IDLE));
|
||||
}
|
||||
|
@@ -33,8 +33,8 @@
|
||||
|
||||
#if ENABLED(EXTENSIBLE_UI)
|
||||
#include "../../../lcd/extui/ui_api.h"
|
||||
#elif ENABLED(DWIN_CREALITY_LCD_ENHANCED)
|
||||
#include "../../../lcd/e3v2/enhanced/dwin.h"
|
||||
#elif ENABLED(DWIN_LCD_PROUI)
|
||||
#include "../../../lcd/e3v2/proui/dwin.h"
|
||||
#endif
|
||||
|
||||
/**
|
||||
@@ -56,7 +56,7 @@ void GcodeSuite::M421() {
|
||||
hasZ = parser.seen('Z'),
|
||||
hasQ = !hasZ && parser.seen('Q');
|
||||
|
||||
if (hasC) ij = ubl.find_closest_mesh_point_of_type(CLOSEST, current_position);
|
||||
if (hasC) ij = bedlevel.find_closest_mesh_point_of_type(CLOSEST, current_position);
|
||||
|
||||
// Test for bad parameter combinations
|
||||
if (int(hasC) + int(hasI && hasJ) != 1 || !(hasZ || hasQ || hasN))
|
||||
@@ -66,10 +66,10 @@ void GcodeSuite::M421() {
|
||||
else if (!WITHIN(ij.x, 0, GRID_MAX_POINTS_X - 1) || !WITHIN(ij.y, 0, GRID_MAX_POINTS_Y - 1))
|
||||
SERIAL_ERROR_MSG(STR_ERR_MESH_XY);
|
||||
else {
|
||||
float &zval = ubl.z_values[ij.x][ij.y]; // Altering this Mesh Point
|
||||
float &zval = bedlevel.z_values[ij.x][ij.y]; // Altering this Mesh Point
|
||||
zval = hasN ? NAN : parser.value_linear_units() + (hasQ ? zval : 0); // N=NAN, Z=NEWVAL, or Q=ADDVAL
|
||||
TERN_(EXTENSIBLE_UI, ExtUI::onMeshUpdate(ij.x, ij.y, zval)); // Ping ExtUI in case it's showing the mesh
|
||||
TERN_(DWIN_CREALITY_LCD_ENHANCED, DWIN_MeshUpdate(ij.x, ij.y, zval));
|
||||
TERN_(DWIN_LCD_PROUI, DWIN_MeshUpdate(ij.x, ij.y, zval));
|
||||
}
|
||||
}
|
||||
|
||||
|
@@ -24,8 +24,9 @@
|
||||
|
||||
#include "../gcode.h"
|
||||
|
||||
#include "../../module/stepper.h"
|
||||
#include "../../module/endstops.h"
|
||||
#include "../../module/planner.h"
|
||||
#include "../../module/stepper.h" // for various
|
||||
|
||||
#if HAS_MULTI_HOTEND
|
||||
#include "../../module/tool_change.h"
|
||||
@@ -35,6 +36,10 @@
|
||||
#include "../../feature/bedlevel/bedlevel.h"
|
||||
#endif
|
||||
|
||||
#if ENABLED(BD_SENSOR)
|
||||
#include "../../feature/bedlevel/bdl/bdl.h"
|
||||
#endif
|
||||
|
||||
#if ENABLED(SENSORLESS_HOMING)
|
||||
#include "../../feature/tmc_util.h"
|
||||
#endif
|
||||
@@ -51,15 +56,11 @@
|
||||
#include "../../lcd/extui/ui_api.h"
|
||||
#elif ENABLED(DWIN_CREALITY_LCD)
|
||||
#include "../../lcd/e3v2/creality/dwin.h"
|
||||
#elif ENABLED(DWIN_CREALITY_LCD_ENHANCED)
|
||||
#include "../../lcd/e3v2/enhanced/dwin.h"
|
||||
#elif ENABLED(DWIN_LCD_PROUI)
|
||||
#include "../../lcd/e3v2/proui/dwin.h"
|
||||
#endif
|
||||
|
||||
#if HAS_L64XX // set L6470 absolute position registers to counts
|
||||
#include "../../libs/L64XX/L64XX_Marlin.h"
|
||||
#endif
|
||||
|
||||
#if ENABLED(LASER_MOVE_G28_OFF)
|
||||
#if ENABLED(LASER_FEATURE)
|
||||
#include "../../feature/spindle_laser.h"
|
||||
#endif
|
||||
|
||||
@@ -76,42 +77,33 @@
|
||||
|
||||
const int x_axis_home_dir = TOOL_X_HOME_DIR(active_extruder);
|
||||
|
||||
const float mlx = max_length(X_AXIS),
|
||||
mly = max_length(Y_AXIS),
|
||||
mlratio = mlx > mly ? mly / mlx : mlx / mly,
|
||||
fr_mm_s = _MIN(homing_feedrate(X_AXIS), homing_feedrate(Y_AXIS)) * SQRT(sq(mlratio) + 1.0);
|
||||
// Use a higher diagonal feedrate so axes move at homing speed
|
||||
const float minfr = _MIN(homing_feedrate(X_AXIS), homing_feedrate(Y_AXIS)),
|
||||
fr_mm_s = HYPOT(minfr, minfr);
|
||||
|
||||
#if ENABLED(SENSORLESS_HOMING)
|
||||
sensorless_t stealth_states {
|
||||
tmc_enable_stallguard(stepperX)
|
||||
, tmc_enable_stallguard(stepperY)
|
||||
, false
|
||||
, false
|
||||
#if AXIS_HAS_STALLGUARD(X2)
|
||||
|| tmc_enable_stallguard(stepperX2)
|
||||
#endif
|
||||
, false
|
||||
#if AXIS_HAS_STALLGUARD(Y2)
|
||||
|| tmc_enable_stallguard(stepperY2)
|
||||
#endif
|
||||
NUM_AXIS_LIST(
|
||||
TERN0(X_SENSORLESS, tmc_enable_stallguard(stepperX)),
|
||||
TERN0(Y_SENSORLESS, tmc_enable_stallguard(stepperY)),
|
||||
false, false, false, false
|
||||
)
|
||||
, TERN0(X2_SENSORLESS, tmc_enable_stallguard(stepperX2))
|
||||
, TERN0(Y2_SENSORLESS, tmc_enable_stallguard(stepperY2))
|
||||
};
|
||||
#endif
|
||||
|
||||
do_blocking_move_to_xy(1.5 * mlx * x_axis_home_dir, 1.5 * mly * Y_HOME_DIR, fr_mm_s);
|
||||
do_blocking_move_to_xy(1.5 * max_length(X_AXIS) * x_axis_home_dir, 1.5 * max_length(Y_AXIS) * Y_HOME_DIR, fr_mm_s);
|
||||
|
||||
endstops.validate_homing_move();
|
||||
|
||||
current_position.set(0.0, 0.0);
|
||||
|
||||
#if ENABLED(SENSORLESS_HOMING) && DISABLED(ENDSTOPS_ALWAYS_ON_DEFAULT)
|
||||
tmc_disable_stallguard(stepperX, stealth_states.x);
|
||||
tmc_disable_stallguard(stepperY, stealth_states.y);
|
||||
#if AXIS_HAS_STALLGUARD(X2)
|
||||
tmc_disable_stallguard(stepperX2, stealth_states.x2);
|
||||
#endif
|
||||
#if AXIS_HAS_STALLGUARD(Y2)
|
||||
tmc_disable_stallguard(stepperY2, stealth_states.y2);
|
||||
#endif
|
||||
TERN_(X_SENSORLESS, tmc_disable_stallguard(stepperX, stealth_states.x));
|
||||
TERN_(X2_SENSORLESS, tmc_disable_stallguard(stepperX2, stealth_states.x2));
|
||||
TERN_(Y_SENSORLESS, tmc_disable_stallguard(stepperY, stealth_states.y));
|
||||
TERN_(Y2_SENSORLESS, tmc_disable_stallguard(stepperY2, stealth_states.y2));
|
||||
#endif
|
||||
}
|
||||
|
||||
@@ -156,7 +148,7 @@
|
||||
homeaxis(Z_AXIS);
|
||||
}
|
||||
else {
|
||||
LCD_MESSAGEPGM(MSG_ZPROBE_OUT);
|
||||
LCD_MESSAGE(MSG_ZPROBE_OUT);
|
||||
SERIAL_ECHO_MSG(STR_ZPROBE_OUT_SER);
|
||||
}
|
||||
}
|
||||
@@ -178,7 +170,7 @@
|
||||
motion_state.jerk_state = planner.max_jerk;
|
||||
planner.max_jerk.set(0, 0 OPTARG(DELTA, 0));
|
||||
#endif
|
||||
planner.reset_acceleration_rates();
|
||||
planner.refresh_acceleration_rates();
|
||||
return motion_state;
|
||||
}
|
||||
|
||||
@@ -187,7 +179,7 @@
|
||||
planner.settings.max_acceleration_mm_per_s2[Y_AXIS] = motion_state.acceleration.y;
|
||||
TERN_(DELTA, planner.settings.max_acceleration_mm_per_s2[Z_AXIS] = motion_state.acceleration.z);
|
||||
TERN_(HAS_CLASSIC_JERK, planner.max_jerk = motion_state.jerk_state);
|
||||
planner.reset_acceleration_rates();
|
||||
planner.refresh_acceleration_rates();
|
||||
}
|
||||
|
||||
#endif // IMPROVE_HOMING_RELIABILITY
|
||||
@@ -214,9 +206,14 @@ void GcodeSuite::G28() {
|
||||
DEBUG_SECTION(log_G28, "G28", DEBUGGING(LEVELING));
|
||||
if (DEBUGGING(LEVELING)) log_machine_info();
|
||||
|
||||
TERN_(LASER_MOVE_G28_OFF, cutter.set_inline_enabled(false)); // turn off laser
|
||||
TERN_(BD_SENSOR, bdl.config_state = 0);
|
||||
|
||||
TERN_(FULL_REPORT_TO_HOST_FEATURE, set_and_report_grblstate(M_HOMING));
|
||||
/**
|
||||
* Set the laser power to false to stop the planner from processing the current power setting.
|
||||
*/
|
||||
#if ENABLED(LASER_FEATURE)
|
||||
planner.laser_inline.status.isPowered = false;
|
||||
#endif
|
||||
|
||||
#if ENABLED(DUAL_X_CARRIAGE)
|
||||
bool IDEX_saved_duplication_state = extruder_duplication_enabled;
|
||||
@@ -225,7 +222,7 @@ void GcodeSuite::G28() {
|
||||
|
||||
#if ENABLED(MARLIN_DEV_MODE)
|
||||
if (parser.seen_test('S')) {
|
||||
LOOP_LINEAR_AXES(a) set_axis_is_at_home((AxisEnum)a);
|
||||
LOOP_NUM_AXES(a) set_axis_is_at_home((AxisEnum)a);
|
||||
sync_plan_position();
|
||||
SERIAL_ECHOLNPGM("Simulated Homing");
|
||||
report_current_position();
|
||||
@@ -239,7 +236,12 @@ void GcodeSuite::G28() {
|
||||
return;
|
||||
}
|
||||
|
||||
TERN_(HAS_DWIN_E3V2_BASIC, DWIN_StartHoming());
|
||||
#if ENABLED(FULL_REPORT_TO_HOST_FEATURE)
|
||||
const M_StateEnum old_grblstate = M_State_grbl;
|
||||
set_and_report_grblstate(M_HOMING);
|
||||
#endif
|
||||
|
||||
TERN_(HAS_DWIN_E3V2_BASIC, DWIN_HomingStart());
|
||||
TERN_(EXTENSIBLE_UI, ExtUI::onHomingStart());
|
||||
|
||||
planner.synchronize(); // Wait for planner moves to finish!
|
||||
@@ -264,38 +266,71 @@ void GcodeSuite::G28() {
|
||||
reset_stepper_timeout();
|
||||
|
||||
#define HAS_CURRENT_HOME(N) (defined(N##_CURRENT_HOME) && N##_CURRENT_HOME != N##_CURRENT)
|
||||
#if HAS_CURRENT_HOME(X) || HAS_CURRENT_HOME(X2) || HAS_CURRENT_HOME(Y) || HAS_CURRENT_HOME(Y2) || (ENABLED(DELTA) && HAS_CURRENT_HOME(Z))
|
||||
#if HAS_CURRENT_HOME(X) || HAS_CURRENT_HOME(X2) || HAS_CURRENT_HOME(Y) || HAS_CURRENT_HOME(Y2) || (ENABLED(DELTA) && HAS_CURRENT_HOME(Z)) || HAS_CURRENT_HOME(I) || HAS_CURRENT_HOME(J) || HAS_CURRENT_HOME(K) || HAS_CURRENT_HOME(U) || HAS_CURRENT_HOME(V) || HAS_CURRENT_HOME(W)
|
||||
#define HAS_HOMING_CURRENT 1
|
||||
#endif
|
||||
|
||||
#if HAS_HOMING_CURRENT
|
||||
auto debug_current = [](PGM_P const s, const int16_t a, const int16_t b) {
|
||||
DEBUG_ECHOPGM_P(s); DEBUG_ECHOLNPGM(" current: ", a, " -> ", b);
|
||||
auto debug_current = [](FSTR_P const s, const int16_t a, const int16_t b) {
|
||||
DEBUG_ECHOF(s); DEBUG_ECHOLNPGM(" current: ", a, " -> ", b);
|
||||
};
|
||||
#if HAS_CURRENT_HOME(X)
|
||||
const int16_t tmc_save_current_X = stepperX.getMilliamps();
|
||||
stepperX.rms_current(X_CURRENT_HOME);
|
||||
if (DEBUGGING(LEVELING)) debug_current(PSTR("X"), tmc_save_current_X, X_CURRENT_HOME);
|
||||
if (DEBUGGING(LEVELING)) debug_current(F(STR_X), tmc_save_current_X, X_CURRENT_HOME);
|
||||
#endif
|
||||
#if HAS_CURRENT_HOME(X2)
|
||||
const int16_t tmc_save_current_X2 = stepperX2.getMilliamps();
|
||||
stepperX2.rms_current(X2_CURRENT_HOME);
|
||||
if (DEBUGGING(LEVELING)) debug_current(PSTR("X2"), tmc_save_current_X2, X2_CURRENT_HOME);
|
||||
if (DEBUGGING(LEVELING)) debug_current(F(STR_X2), tmc_save_current_X2, X2_CURRENT_HOME);
|
||||
#endif
|
||||
#if HAS_CURRENT_HOME(Y)
|
||||
const int16_t tmc_save_current_Y = stepperY.getMilliamps();
|
||||
stepperY.rms_current(Y_CURRENT_HOME);
|
||||
if (DEBUGGING(LEVELING)) debug_current(PSTR("Y"), tmc_save_current_Y, Y_CURRENT_HOME);
|
||||
if (DEBUGGING(LEVELING)) debug_current(F(STR_Y), tmc_save_current_Y, Y_CURRENT_HOME);
|
||||
#endif
|
||||
#if HAS_CURRENT_HOME(Y2)
|
||||
const int16_t tmc_save_current_Y2 = stepperY2.getMilliamps();
|
||||
stepperY2.rms_current(Y2_CURRENT_HOME);
|
||||
if (DEBUGGING(LEVELING)) debug_current(PSTR("Y2"), tmc_save_current_Y2, Y2_CURRENT_HOME);
|
||||
if (DEBUGGING(LEVELING)) debug_current(F(STR_Y2), tmc_save_current_Y2, Y2_CURRENT_HOME);
|
||||
#endif
|
||||
#if HAS_CURRENT_HOME(Z) && ENABLED(DELTA)
|
||||
const int16_t tmc_save_current_Z = stepperZ.getMilliamps();
|
||||
stepperZ.rms_current(Z_CURRENT_HOME);
|
||||
if (DEBUGGING(LEVELING)) debug_current(PSTR("Z"), tmc_save_current_Z, Z_CURRENT_HOME);
|
||||
if (DEBUGGING(LEVELING)) debug_current(F(STR_Z), tmc_save_current_Z, Z_CURRENT_HOME);
|
||||
#endif
|
||||
#if HAS_CURRENT_HOME(I)
|
||||
const int16_t tmc_save_current_I = stepperI.getMilliamps();
|
||||
stepperI.rms_current(I_CURRENT_HOME);
|
||||
if (DEBUGGING(LEVELING)) debug_current(F(STR_I), tmc_save_current_I, I_CURRENT_HOME);
|
||||
#endif
|
||||
#if HAS_CURRENT_HOME(J)
|
||||
const int16_t tmc_save_current_J = stepperJ.getMilliamps();
|
||||
stepperJ.rms_current(J_CURRENT_HOME);
|
||||
if (DEBUGGING(LEVELING)) debug_current(F(STR_J), tmc_save_current_J, J_CURRENT_HOME);
|
||||
#endif
|
||||
#if HAS_CURRENT_HOME(K)
|
||||
const int16_t tmc_save_current_K = stepperK.getMilliamps();
|
||||
stepperK.rms_current(K_CURRENT_HOME);
|
||||
if (DEBUGGING(LEVELING)) debug_current(F(STR_K), tmc_save_current_K, K_CURRENT_HOME);
|
||||
#endif
|
||||
#if HAS_CURRENT_HOME(U)
|
||||
const int16_t tmc_save_current_U = stepperU.getMilliamps();
|
||||
stepperU.rms_current(U_CURRENT_HOME);
|
||||
if (DEBUGGING(LEVELING)) debug_current(F(STR_U), tmc_save_current_U, U_CURRENT_HOME);
|
||||
#endif
|
||||
#if HAS_CURRENT_HOME(V)
|
||||
const int16_t tmc_save_current_V = stepperV.getMilliamps();
|
||||
stepperV.rms_current(V_CURRENT_HOME);
|
||||
if (DEBUGGING(LEVELING)) debug_current(F(STR_V), tmc_save_current_V, V_CURRENT_HOME);
|
||||
#endif
|
||||
#if HAS_CURRENT_HOME(W)
|
||||
const int16_t tmc_save_current_W = stepperW.getMilliamps();
|
||||
stepperW.rms_current(W_CURRENT_HOME);
|
||||
if (DEBUGGING(LEVELING)) debug_current(F(STR_W), tmc_save_current_W, W_CURRENT_HOME);
|
||||
#endif
|
||||
#if SENSORLESS_STALLGUARD_DELAY
|
||||
safe_delay(SENSORLESS_STALLGUARD_DELAY); // Short delay needed to settle
|
||||
#endif
|
||||
#endif
|
||||
|
||||
@@ -340,23 +375,28 @@ void GcodeSuite::G28() {
|
||||
#define _UNSAFE(A) (homeZ && TERN0(Z_SAFE_HOMING, axes_should_home(_BV(A##_AXIS))))
|
||||
|
||||
const bool homeZ = TERN0(HAS_Z_AXIS, parser.seen_test('Z')),
|
||||
LINEAR_AXIS_LIST( // Other axes should be homed before Z safe-homing
|
||||
NUM_AXIS_LIST( // Other axes should be homed before Z safe-homing
|
||||
needX = _UNSAFE(X), needY = _UNSAFE(Y), needZ = false, // UNUSED
|
||||
needI = _UNSAFE(I), needJ = _UNSAFE(J), needK = _UNSAFE(K)
|
||||
needI = _UNSAFE(I), needJ = _UNSAFE(J), needK = _UNSAFE(K),
|
||||
needU = _UNSAFE(U), needV = _UNSAFE(V), needW = _UNSAFE(W)
|
||||
),
|
||||
LINEAR_AXIS_LIST( // Home each axis if needed or flagged
|
||||
NUM_AXIS_LIST( // Home each axis if needed or flagged
|
||||
homeX = needX || parser.seen_test('X'),
|
||||
homeY = needY || parser.seen_test('Y'),
|
||||
homeZZ = homeZ,
|
||||
homeI = needI || parser.seen_test(AXIS4_NAME), homeJ = needJ || parser.seen_test(AXIS5_NAME), homeK = needK || parser.seen_test(AXIS6_NAME),
|
||||
homeI = needI || parser.seen_test(AXIS4_NAME), homeJ = needJ || parser.seen_test(AXIS5_NAME),
|
||||
homeK = needK || parser.seen_test(AXIS6_NAME), homeU = needU || parser.seen_test(AXIS7_NAME),
|
||||
homeV = needV || parser.seen_test(AXIS8_NAME), homeW = needW || parser.seen_test(AXIS9_NAME)
|
||||
),
|
||||
home_all = LINEAR_AXIS_GANG( // Home-all if all or none are flagged
|
||||
home_all = NUM_AXIS_GANG( // Home-all if all or none are flagged
|
||||
homeX == homeX, && homeY == homeX, && homeZ == homeX,
|
||||
&& homeI == homeX, && homeJ == homeX, && homeK == homeX
|
||||
&& homeI == homeX, && homeJ == homeX, && homeK == homeX,
|
||||
&& homeU == homeX, && homeV == homeX, && homeW == homeX
|
||||
),
|
||||
LINEAR_AXIS_LIST(
|
||||
NUM_AXIS_LIST(
|
||||
doX = home_all || homeX, doY = home_all || homeY, doZ = home_all || homeZ,
|
||||
doI = home_all || homeI, doJ = home_all || homeJ, doK = home_all || homeK
|
||||
doI = home_all || homeI, doJ = home_all || homeJ, doK = home_all || homeK,
|
||||
doU = home_all || homeU, doV = home_all || homeV, doW = home_all || homeW
|
||||
);
|
||||
|
||||
#if HAS_Z_AXIS
|
||||
@@ -367,9 +407,10 @@ void GcodeSuite::G28() {
|
||||
|
||||
TERN_(HOME_Z_FIRST, if (doZ) homeaxis(Z_AXIS));
|
||||
|
||||
const float z_homing_height = parser.seenval('R') ? parser.value_linear_units() : Z_HOMING_HEIGHT;
|
||||
const bool seenR = parser.seenval('R');
|
||||
const float z_homing_height = seenR ? parser.value_linear_units() : Z_HOMING_HEIGHT;
|
||||
|
||||
if (z_homing_height && (LINEAR_AXIS_GANG(doX, || doY, || TERN0(Z_SAFE_HOMING, doZ), || doI, || doJ, || doK))) {
|
||||
if (z_homing_height && (seenR || NUM_AXIS_GANG(doX, || doY, || TERN0(Z_SAFE_HOMING, doZ), || doI, || doJ, || doK, || doU, || doV, || doW))) {
|
||||
// Raise Z before homing any other axes and z is not already high enough (never lower z)
|
||||
if (DEBUGGING(LEVELING)) DEBUG_ECHOLNPGM("Raise Z (before homing) by ", z_homing_height);
|
||||
do_z_clearance(z_homing_height);
|
||||
@@ -409,33 +450,51 @@ void GcodeSuite::G28() {
|
||||
#endif
|
||||
}
|
||||
|
||||
#if BOTH(FOAMCUTTER_XYUV, HAS_I_AXIS)
|
||||
// Home I (after X)
|
||||
if (doI) homeaxis(I_AXIS);
|
||||
#endif
|
||||
|
||||
// Home Y (after X)
|
||||
if (DISABLED(HOME_Y_BEFORE_X) && doY)
|
||||
homeaxis(Y_AXIS);
|
||||
|
||||
TERN_(IMPROVE_HOMING_RELIABILITY, end_slow_homing(saved_motion_state));
|
||||
|
||||
// Home Z last if homing towards the bed
|
||||
#if HAS_Z_AXIS && DISABLED(HOME_Z_FIRST)
|
||||
if (doZ) {
|
||||
#if EITHER(Z_MULTI_ENDSTOPS, Z_STEPPER_AUTO_ALIGN)
|
||||
stepper.set_all_z_lock(false);
|
||||
stepper.set_separate_multi_axis(false);
|
||||
#endif
|
||||
|
||||
TERN(Z_SAFE_HOMING, home_z_safely(), homeaxis(Z_AXIS));
|
||||
probe.move_z_after_homing();
|
||||
}
|
||||
#endif
|
||||
|
||||
#if LINEAR_AXES >= 4
|
||||
if (doI) homeaxis(I_AXIS);
|
||||
#endif
|
||||
#if LINEAR_AXES >= 5
|
||||
#if BOTH(FOAMCUTTER_XYUV, HAS_J_AXIS)
|
||||
// Home J (after Y)
|
||||
if (doJ) homeaxis(J_AXIS);
|
||||
#endif
|
||||
#if LINEAR_AXES >= 6
|
||||
if (doK) homeaxis(K_AXIS);
|
||||
|
||||
TERN_(IMPROVE_HOMING_RELIABILITY, end_slow_homing(saved_motion_state));
|
||||
|
||||
#if ENABLED(FOAMCUTTER_XYUV)
|
||||
// skip homing of unused Z axis for foamcutters
|
||||
if (doZ) set_axis_is_at_home(Z_AXIS);
|
||||
#else
|
||||
// Home Z last if homing towards the bed
|
||||
#if HAS_Z_AXIS && DISABLED(HOME_Z_FIRST)
|
||||
if (doZ) {
|
||||
#if EITHER(Z_MULTI_ENDSTOPS, Z_STEPPER_AUTO_ALIGN)
|
||||
stepper.set_all_z_lock(false);
|
||||
stepper.set_separate_multi_axis(false);
|
||||
#endif
|
||||
|
||||
#if ENABLED(Z_SAFE_HOMING)
|
||||
if (TERN1(POWER_LOSS_RECOVERY, !parser.seen_test('H'))) home_z_safely(); else homeaxis(Z_AXIS);
|
||||
#else
|
||||
homeaxis(Z_AXIS);
|
||||
#endif
|
||||
probe.move_z_after_homing();
|
||||
}
|
||||
#endif
|
||||
|
||||
SECONDARY_AXIS_CODE(
|
||||
if (doI) homeaxis(I_AXIS),
|
||||
if (doJ) homeaxis(J_AXIS),
|
||||
if (doK) homeaxis(K_AXIS),
|
||||
if (doU) homeaxis(U_AXIS),
|
||||
if (doV) homeaxis(V_AXIS),
|
||||
if (doW) homeaxis(W_AXIS)
|
||||
);
|
||||
#endif
|
||||
|
||||
sync_plan_position();
|
||||
@@ -519,34 +578,30 @@ void GcodeSuite::G28() {
|
||||
#if HAS_CURRENT_HOME(K)
|
||||
stepperK.rms_current(tmc_save_current_K);
|
||||
#endif
|
||||
#if HAS_CURRENT_HOME(U)
|
||||
stepperU.rms_current(tmc_save_current_U);
|
||||
#endif
|
||||
#if HAS_CURRENT_HOME(V)
|
||||
stepperV.rms_current(tmc_save_current_V);
|
||||
#endif
|
||||
#if HAS_CURRENT_HOME(W)
|
||||
stepperW.rms_current(tmc_save_current_W);
|
||||
#endif
|
||||
#if SENSORLESS_STALLGUARD_DELAY
|
||||
safe_delay(SENSORLESS_STALLGUARD_DELAY); // Short delay needed to settle
|
||||
#endif
|
||||
#endif // HAS_HOMING_CURRENT
|
||||
|
||||
ui.refresh();
|
||||
|
||||
TERN_(HAS_DWIN_E3V2_BASIC, DWIN_CompletedHoming());
|
||||
TERN_(EXTENSIBLE_UI, ExtUI::onHomingComplete());
|
||||
TERN_(HAS_DWIN_E3V2_BASIC, DWIN_HomingDone());
|
||||
TERN_(EXTENSIBLE_UI, ExtUI::onHomingDone());
|
||||
|
||||
report_current_position();
|
||||
|
||||
if (ENABLED(NANODLP_Z_SYNC) && (doZ || ENABLED(NANODLP_ALL_AXIS)))
|
||||
SERIAL_ECHOLNPGM(STR_Z_MOVE_COMP);
|
||||
|
||||
TERN_(FULL_REPORT_TO_HOST_FEATURE, set_and_report_grblstate(M_IDLE));
|
||||
TERN_(FULL_REPORT_TO_HOST_FEATURE, set_and_report_grblstate(old_grblstate));
|
||||
|
||||
#if HAS_L64XX
|
||||
// Set L6470 absolute position registers to counts
|
||||
// constexpr *might* move this to PROGMEM.
|
||||
// If not, this will need a PROGMEM directive and an accessor.
|
||||
#define _EN_ITEM(N) , E_AXIS
|
||||
static constexpr AxisEnum L64XX_axis_xref[MAX_L64XX] = {
|
||||
LINEAR_AXIS_LIST(X_AXIS, Y_AXIS, Z_AXIS, I_AXIS, J_AXIS, K_AXIS),
|
||||
X_AXIS, Y_AXIS, Z_AXIS, Z_AXIS, Z_AXIS
|
||||
REPEAT(E_STEPPERS, _EN_ITEM)
|
||||
};
|
||||
#undef _EN_ITEM
|
||||
for (uint8_t j = 1; j <= L64XX::chain[0]; j++) {
|
||||
const uint8_t cv = L64XX::chain[j];
|
||||
L64xxManager.set_param((L64XX_axis_t)cv, L6470_ABS_POS, stepper.position(L64XX_axis_xref[cv]));
|
||||
}
|
||||
#endif
|
||||
}
|
||||
|
@@ -27,7 +27,7 @@
|
||||
#include "../gcode.h"
|
||||
#include "../../module/delta.h"
|
||||
#include "../../module/motion.h"
|
||||
#include "../../module/stepper.h"
|
||||
#include "../../module/planner.h"
|
||||
#include "../../module/endstops.h"
|
||||
#include "../../lcd/marlinui.h"
|
||||
|
||||
@@ -69,13 +69,11 @@ enum CalEnum : char { // the 7 main calibration points -
|
||||
|
||||
float lcd_probe_pt(const xy_pos_t &xy);
|
||||
|
||||
float dcr;
|
||||
|
||||
void ac_home() {
|
||||
endstops.enable(true);
|
||||
TERN_(SENSORLESS_HOMING, probe.set_homing_current(true));
|
||||
TERN_(SENSORLESS_HOMING, endstops.set_homing_current(true));
|
||||
home_delta();
|
||||
TERN_(SENSORLESS_HOMING, probe.set_homing_current(false));
|
||||
TERN_(SENSORLESS_HOMING, endstops.set_homing_current(false));
|
||||
endstops.not_homing();
|
||||
}
|
||||
|
||||
@@ -97,12 +95,10 @@ void ac_cleanup(TERN_(HAS_MULTI_HOTEND, const uint8_t old_tool_index)) {
|
||||
TERN_(HAS_MULTI_HOTEND, tool_change(old_tool_index, true));
|
||||
}
|
||||
|
||||
void print_signed_float(PGM_P const prefix, const_float_t f) {
|
||||
void print_signed_float(FSTR_P const prefix, const_float_t f) {
|
||||
SERIAL_ECHOPGM(" ");
|
||||
SERIAL_ECHOPGM_P(prefix);
|
||||
SERIAL_CHAR(':');
|
||||
if (f >= 0) SERIAL_CHAR('+');
|
||||
SERIAL_ECHO_F(f, 2);
|
||||
SERIAL_ECHOF(prefix, AS_CHAR(':'));
|
||||
serial_offset(f);
|
||||
}
|
||||
|
||||
/**
|
||||
@@ -111,24 +107,23 @@ void print_signed_float(PGM_P const prefix, const_float_t f) {
|
||||
static void print_calibration_settings(const bool end_stops, const bool tower_angles) {
|
||||
SERIAL_ECHOPGM(".Height:", delta_height);
|
||||
if (end_stops) {
|
||||
print_signed_float(PSTR("Ex"), delta_endstop_adj.a);
|
||||
print_signed_float(PSTR("Ey"), delta_endstop_adj.b);
|
||||
print_signed_float(PSTR("Ez"), delta_endstop_adj.c);
|
||||
print_signed_float(F("Ex"), delta_endstop_adj.a);
|
||||
print_signed_float(F("Ey"), delta_endstop_adj.b);
|
||||
print_signed_float(F("Ez"), delta_endstop_adj.c);
|
||||
}
|
||||
if (end_stops && tower_angles) {
|
||||
SERIAL_ECHOPGM(" Radius:", delta_radius);
|
||||
SERIAL_EOL();
|
||||
SERIAL_ECHOLNPGM(" Radius:", delta_radius);
|
||||
SERIAL_CHAR('.');
|
||||
SERIAL_ECHO_SP(13);
|
||||
}
|
||||
if (tower_angles) {
|
||||
print_signed_float(PSTR("Tx"), delta_tower_angle_trim.a);
|
||||
print_signed_float(PSTR("Ty"), delta_tower_angle_trim.b);
|
||||
print_signed_float(PSTR("Tz"), delta_tower_angle_trim.c);
|
||||
print_signed_float(F("Tx"), delta_tower_angle_trim.a);
|
||||
print_signed_float(F("Ty"), delta_tower_angle_trim.b);
|
||||
print_signed_float(F("Tz"), delta_tower_angle_trim.c);
|
||||
}
|
||||
if ((!end_stops && tower_angles) || (end_stops && !tower_angles)) { // XOR
|
||||
if (end_stops != tower_angles)
|
||||
SERIAL_ECHOPGM(" Radius:", delta_radius);
|
||||
}
|
||||
|
||||
SERIAL_EOL();
|
||||
}
|
||||
|
||||
@@ -137,11 +132,11 @@ static void print_calibration_settings(const bool end_stops, const bool tower_an
|
||||
*/
|
||||
static void print_calibration_results(const float z_pt[NPP + 1], const bool tower_points, const bool opposite_points) {
|
||||
SERIAL_ECHOPGM(". ");
|
||||
print_signed_float(PSTR("c"), z_pt[CEN]);
|
||||
print_signed_float(F("c"), z_pt[CEN]);
|
||||
if (tower_points) {
|
||||
print_signed_float(PSTR(" x"), z_pt[__A]);
|
||||
print_signed_float(PSTR(" y"), z_pt[__B]);
|
||||
print_signed_float(PSTR(" z"), z_pt[__C]);
|
||||
print_signed_float(F(" x"), z_pt[__A]);
|
||||
print_signed_float(F(" y"), z_pt[__B]);
|
||||
print_signed_float(F(" z"), z_pt[__C]);
|
||||
}
|
||||
if (tower_points && opposite_points) {
|
||||
SERIAL_EOL();
|
||||
@@ -149,9 +144,9 @@ static void print_calibration_results(const float z_pt[NPP + 1], const bool towe
|
||||
SERIAL_ECHO_SP(13);
|
||||
}
|
||||
if (opposite_points) {
|
||||
print_signed_float(PSTR("yz"), z_pt[_BC]);
|
||||
print_signed_float(PSTR("zx"), z_pt[_CA]);
|
||||
print_signed_float(PSTR("xy"), z_pt[_AB]);
|
||||
print_signed_float(F("yz"), z_pt[_BC]);
|
||||
print_signed_float(F("zx"), z_pt[_CA]);
|
||||
print_signed_float(F("xy"), z_pt[_AB]);
|
||||
}
|
||||
SERIAL_EOL();
|
||||
}
|
||||
@@ -179,7 +174,7 @@ static float std_dev_points(float z_pt[NPP + 1], const bool _0p_cal, const bool
|
||||
*/
|
||||
static float calibration_probe(const xy_pos_t &xy, const bool stow, const bool probe_at_offset) {
|
||||
#if HAS_BED_PROBE
|
||||
return probe.probe_at_point(xy, stow ? PROBE_PT_STOW : PROBE_PT_RAISE, 0, true, probe_at_offset);
|
||||
return probe.probe_at_point(xy, stow ? PROBE_PT_STOW : PROBE_PT_RAISE, 0, probe_at_offset, false);
|
||||
#else
|
||||
UNUSED(stow);
|
||||
return lcd_probe_pt(xy);
|
||||
@@ -189,7 +184,7 @@ static float calibration_probe(const xy_pos_t &xy, const bool stow, const bool p
|
||||
/**
|
||||
* - Probe a grid
|
||||
*/
|
||||
static bool probe_calibration_points(float z_pt[NPP + 1], const int8_t probe_points, const bool towers_set, const bool stow_after_each, const bool probe_at_offset) {
|
||||
static bool probe_calibration_points(float z_pt[NPP + 1], const int8_t probe_points, const float dcr, const bool towers_set, const bool stow_after_each, const bool probe_at_offset) {
|
||||
const bool _0p_calibration = probe_points == 0,
|
||||
_1p_calibration = probe_points == 1 || probe_points == -1,
|
||||
_4p_calibration = probe_points == 2,
|
||||
@@ -273,7 +268,7 @@ static bool probe_calibration_points(float z_pt[NPP + 1], const int8_t probe_poi
|
||||
* - formulae for approximative forward kinematics in the end-stop displacement matrix
|
||||
* - definition of the matrix scaling parameters
|
||||
*/
|
||||
static void reverse_kinematics_probe_points(float z_pt[NPP + 1], abc_float_t mm_at_pt_axis[NPP + 1]) {
|
||||
static void reverse_kinematics_probe_points(float z_pt[NPP + 1], abc_float_t mm_at_pt_axis[NPP + 1], const float dcr) {
|
||||
xyz_pos_t pos{0};
|
||||
|
||||
LOOP_CAL_ALL(rad) {
|
||||
@@ -285,7 +280,7 @@ static void reverse_kinematics_probe_points(float z_pt[NPP + 1], abc_float_t mm_
|
||||
}
|
||||
}
|
||||
|
||||
static void forward_kinematics_probe_points(abc_float_t mm_at_pt_axis[NPP + 1], float z_pt[NPP + 1]) {
|
||||
static void forward_kinematics_probe_points(abc_float_t mm_at_pt_axis[NPP + 1], float z_pt[NPP + 1], const float dcr) {
|
||||
const float r_quot = dcr / delta_radius;
|
||||
|
||||
#define ZPP(N,I,A) (((1.0f + r_quot * (N)) / 3.0f) * mm_at_pt_axis[I].A)
|
||||
@@ -304,19 +299,19 @@ static void forward_kinematics_probe_points(abc_float_t mm_at_pt_axis[NPP + 1],
|
||||
z_pt[_AB] = Zp1(_AB, a) + Zp1(_AB, b) + Zm2(_AB, c);
|
||||
}
|
||||
|
||||
static void calc_kinematics_diff_probe_points(float z_pt[NPP + 1], abc_float_t delta_e, const float delta_r, abc_float_t delta_t) {
|
||||
static void calc_kinematics_diff_probe_points(float z_pt[NPP + 1], const float dcr, abc_float_t delta_e, const float delta_r, abc_float_t delta_t) {
|
||||
const float z_center = z_pt[CEN];
|
||||
abc_float_t diff_mm_at_pt_axis[NPP + 1], new_mm_at_pt_axis[NPP + 1];
|
||||
|
||||
reverse_kinematics_probe_points(z_pt, diff_mm_at_pt_axis);
|
||||
reverse_kinematics_probe_points(z_pt, diff_mm_at_pt_axis, dcr);
|
||||
|
||||
delta_radius += delta_r;
|
||||
delta_tower_angle_trim += delta_t;
|
||||
recalc_delta_settings();
|
||||
reverse_kinematics_probe_points(z_pt, new_mm_at_pt_axis);
|
||||
reverse_kinematics_probe_points(z_pt, new_mm_at_pt_axis, dcr);
|
||||
|
||||
LOOP_CAL_ALL(rad) diff_mm_at_pt_axis[rad] -= new_mm_at_pt_axis[rad] + delta_e;
|
||||
forward_kinematics_probe_points(diff_mm_at_pt_axis, z_pt);
|
||||
forward_kinematics_probe_points(diff_mm_at_pt_axis, z_pt, dcr);
|
||||
|
||||
LOOP_CAL_RAD(rad) z_pt[rad] -= z_pt[CEN] - z_center;
|
||||
z_pt[CEN] = z_center;
|
||||
@@ -326,31 +321,31 @@ static void calc_kinematics_diff_probe_points(float z_pt[NPP + 1], abc_float_t d
|
||||
recalc_delta_settings();
|
||||
}
|
||||
|
||||
static float auto_tune_h() {
|
||||
static float auto_tune_h(const float dcr) {
|
||||
const float r_quot = dcr / delta_radius;
|
||||
return RECIPROCAL(r_quot / (2.0f / 3.0f)); // (2/3)/CR
|
||||
}
|
||||
|
||||
static float auto_tune_r() {
|
||||
static float auto_tune_r(const float dcr) {
|
||||
constexpr float diff = 0.01f, delta_r = diff;
|
||||
float r_fac = 0.0f, z_pt[NPP + 1] = { 0.0f };
|
||||
abc_float_t delta_e = { 0.0f }, delta_t = { 0.0f };
|
||||
|
||||
calc_kinematics_diff_probe_points(z_pt, delta_e, delta_r, delta_t);
|
||||
calc_kinematics_diff_probe_points(z_pt, dcr, delta_e, delta_r, delta_t);
|
||||
r_fac = -(z_pt[__A] + z_pt[__B] + z_pt[__C] + z_pt[_BC] + z_pt[_CA] + z_pt[_AB]) / 6.0f;
|
||||
r_fac = diff / r_fac / 3.0f; // 1/(3*delta_Z)
|
||||
return r_fac;
|
||||
}
|
||||
|
||||
static float auto_tune_a() {
|
||||
static float auto_tune_a(const float dcr) {
|
||||
constexpr float diff = 0.01f, delta_r = 0.0f;
|
||||
float a_fac = 0.0f, z_pt[NPP + 1] = { 0.0f };
|
||||
abc_float_t delta_e = { 0.0f }, delta_t = { 0.0f };
|
||||
|
||||
delta_t.reset();
|
||||
LOOP_LINEAR_AXES(axis) {
|
||||
LOOP_NUM_AXES(axis) {
|
||||
delta_t[axis] = diff;
|
||||
calc_kinematics_diff_probe_points(z_pt, delta_e, delta_r, delta_t);
|
||||
calc_kinematics_diff_probe_points(z_pt, dcr, delta_e, delta_r, delta_t);
|
||||
delta_t[axis] = 0;
|
||||
a_fac += z_pt[uint8_t((axis * _4P_STEP) - _7P_STEP + NPP) % NPP + 1] / 6.0f;
|
||||
a_fac -= z_pt[uint8_t((axis * _4P_STEP) + 1 + _7P_STEP)] / 6.0f;
|
||||
@@ -372,7 +367,7 @@ static float auto_tune_a() {
|
||||
* P3 Probe all positions: center, towers and opposite towers. Calibrate all.
|
||||
* P4-P10 Probe all positions at different intermediate locations and average them.
|
||||
*
|
||||
* Rn.nn override default calibration Radius
|
||||
* Rn.nn Temporary reduce the probe grid by the specified amount (mm)
|
||||
*
|
||||
* T Don't calibrate tower angle corrections
|
||||
*
|
||||
@@ -388,13 +383,15 @@ static float auto_tune_a() {
|
||||
*
|
||||
* E Engage the probe for each point
|
||||
*
|
||||
* O Probe at offset points (this is wrong but it seems to work)
|
||||
* O Probe at offsetted probe positions (this is wrong but it seems to work)
|
||||
*
|
||||
* With SENSORLESS_PROBING:
|
||||
* Use these flags to calibrate stall sensitivity: (e.g., `G33 P1 Y Z` to calibrate X only.)
|
||||
* X Don't activate stallguard on X.
|
||||
* Y Don't activate stallguard on Y.
|
||||
* Z Don't activate stallguard on Z.
|
||||
*
|
||||
* S Save offset_sensorless_adj
|
||||
*/
|
||||
void GcodeSuite::G33() {
|
||||
|
||||
@@ -406,27 +403,18 @@ void GcodeSuite::G33() {
|
||||
return;
|
||||
}
|
||||
|
||||
const bool probe_at_offset = TERN0(HAS_PROBE_XY_OFFSET, parser.boolval('O')),
|
||||
const bool probe_at_offset = TERN0(HAS_PROBE_XY_OFFSET, parser.seen_test('O')),
|
||||
towers_set = !parser.seen_test('T');
|
||||
|
||||
float max_dcr = dcr = DELTA_PRINTABLE_RADIUS;
|
||||
// The calibration radius is set to a calculated value
|
||||
float dcr = probe_at_offset ? DELTA_PRINTABLE_RADIUS : DELTA_PRINTABLE_RADIUS - PROBING_MARGIN;
|
||||
#if HAS_PROBE_XY_OFFSET
|
||||
// For offset probes the calibration radius is set to a safe but non-optimal value
|
||||
dcr -= HYPOT(probe.offset_xy.x, probe.offset_xy.y);
|
||||
if (probe_at_offset) {
|
||||
// With probe positions both probe and nozzle need to be within the printable area
|
||||
max_dcr = dcr;
|
||||
}
|
||||
// else with nozzle positions there is a risk of the probe being outside the bed
|
||||
// but as long the nozzle stays within the printable area there is no risk of
|
||||
// the effector crashing into the towers.
|
||||
const float total_offset = HYPOT(probe.offset_xy.x, probe.offset_xy.y);
|
||||
dcr -= probe_at_offset ? _MAX(total_offset, PROBING_MARGIN) : total_offset;
|
||||
#endif
|
||||
|
||||
if (parser.seenval('R')) dcr = parser.value_float();
|
||||
if (!WITHIN(dcr, 0, max_dcr)) {
|
||||
SERIAL_ECHOLNPGM("?calibration (R)adius implausible.");
|
||||
return;
|
||||
}
|
||||
NOMORE(dcr, DELTA_PRINTABLE_RADIUS);
|
||||
if (parser.seenval('R')) dcr -= _MAX(parser.value_float(), 0.0f);
|
||||
TERN_(HAS_DELTA_SENSORLESS_PROBING, dcr *= sensorless_radius_factor);
|
||||
|
||||
const float calibration_precision = parser.floatval('C', 0.0f);
|
||||
if (calibration_precision < 0) {
|
||||
@@ -449,9 +437,8 @@ void GcodeSuite::G33() {
|
||||
const bool stow_after_each = parser.seen_test('E');
|
||||
|
||||
#if HAS_DELTA_SENSORLESS_PROBING
|
||||
probe.test_sensitivity.x = !parser.seen_test('X');
|
||||
TERN_(HAS_Y_AXIS, probe.test_sensitivity.y = !parser.seen_test('Y'));
|
||||
TERN_(HAS_Z_AXIS, probe.test_sensitivity.z = !parser.seen_test('Z'));
|
||||
probe.test_sensitivity = { !parser.seen_test('X'), !parser.seen_test('Y'), !parser.seen_test('Z') };
|
||||
const bool do_save_offset_adj = parser.seen_test('S');
|
||||
#endif
|
||||
|
||||
const bool _0p_calibration = probe_points == 0,
|
||||
@@ -479,9 +466,10 @@ void GcodeSuite::G33() {
|
||||
// Report settings
|
||||
PGM_P const checkingac = PSTR("Checking... AC");
|
||||
SERIAL_ECHOPGM_P(checkingac);
|
||||
SERIAL_ECHOPGM(" at radius:", dcr);
|
||||
if (verbose_level == 0) SERIAL_ECHOPGM(" (DRY-RUN)");
|
||||
SERIAL_EOL();
|
||||
ui.set_status_P(checkingac);
|
||||
ui.set_status(checkingac);
|
||||
|
||||
print_calibration_settings(_endstop_results, _angle_results);
|
||||
|
||||
@@ -489,6 +477,25 @@ void GcodeSuite::G33() {
|
||||
|
||||
if (!_0p_calibration) ac_home();
|
||||
|
||||
#if HAS_DELTA_SENSORLESS_PROBING
|
||||
if (verbose_level > 0 && do_save_offset_adj) {
|
||||
offset_sensorless_adj.reset();
|
||||
|
||||
auto caltower = [&](Probe::sense_bool_t s){
|
||||
float z_at_pt[NPP + 1];
|
||||
LOOP_CAL_ALL(rad) z_at_pt[rad] = 0.0f;
|
||||
probe.test_sensitivity = s;
|
||||
if (probe_calibration_points(z_at_pt, 1, dcr, false, false, probe_at_offset))
|
||||
probe.set_offset_sensorless_adj(z_at_pt[CEN]);
|
||||
};
|
||||
caltower({ true, false, false }); // A
|
||||
caltower({ false, true, false }); // B
|
||||
caltower({ false, false, true }); // C
|
||||
|
||||
probe.test_sensitivity = { true, true, true }; // reset to all
|
||||
}
|
||||
#endif
|
||||
|
||||
do { // start iterations
|
||||
|
||||
float z_at_pt[NPP + 1] = { 0.0f };
|
||||
@@ -498,7 +505,7 @@ void GcodeSuite::G33() {
|
||||
|
||||
// Probe the points
|
||||
zero_std_dev_old = zero_std_dev;
|
||||
if (!probe_calibration_points(z_at_pt, probe_points, towers_set, stow_after_each, probe_at_offset)) {
|
||||
if (!probe_calibration_points(z_at_pt, probe_points, dcr, towers_set, stow_after_each, probe_at_offset)) {
|
||||
SERIAL_ECHOLNPGM("Correct delta settings with M665 and M666");
|
||||
return ac_cleanup(TERN_(HAS_MULTI_HOTEND, old_tool_index));
|
||||
}
|
||||
@@ -538,10 +545,10 @@ void GcodeSuite::G33() {
|
||||
|
||||
// calculate factors
|
||||
if (_7p_9_center) dcr *= 0.9f;
|
||||
h_factor = auto_tune_h();
|
||||
r_factor = auto_tune_r();
|
||||
a_factor = auto_tune_a();
|
||||
dcr /= 0.9f;
|
||||
h_factor = auto_tune_h(dcr);
|
||||
r_factor = auto_tune_r(dcr);
|
||||
a_factor = auto_tune_a(dcr);
|
||||
if (_7p_9_center) dcr /= 0.9f;
|
||||
|
||||
switch (probe_points) {
|
||||
case 0:
|
||||
@@ -550,7 +557,7 @@ void GcodeSuite::G33() {
|
||||
|
||||
case 1:
|
||||
test_precision = 0.0f; // forced end
|
||||
LOOP_LINEAR_AXES(axis) e_delta[axis] = +Z4(CEN);
|
||||
LOOP_NUM_AXES(axis) e_delta[axis] = +Z4(CEN);
|
||||
break;
|
||||
|
||||
case 2:
|
||||
@@ -598,22 +605,31 @@ void GcodeSuite::G33() {
|
||||
// Normalize angles to least-squares
|
||||
if (_angle_results) {
|
||||
float a_sum = 0.0f;
|
||||
LOOP_LINEAR_AXES(axis) a_sum += delta_tower_angle_trim[axis];
|
||||
LOOP_LINEAR_AXES(axis) delta_tower_angle_trim[axis] -= a_sum / 3.0f;
|
||||
LOOP_NUM_AXES(axis) a_sum += delta_tower_angle_trim[axis];
|
||||
LOOP_NUM_AXES(axis) delta_tower_angle_trim[axis] -= a_sum / 3.0f;
|
||||
}
|
||||
|
||||
// adjust delta_height and endstops by the max amount
|
||||
const float z_temp = _MAX(delta_endstop_adj.a, delta_endstop_adj.b, delta_endstop_adj.c);
|
||||
delta_height -= z_temp;
|
||||
LOOP_LINEAR_AXES(axis) delta_endstop_adj[axis] -= z_temp;
|
||||
LOOP_NUM_AXES(axis) delta_endstop_adj[axis] -= z_temp;
|
||||
}
|
||||
recalc_delta_settings();
|
||||
NOMORE(zero_std_dev_min, zero_std_dev);
|
||||
|
||||
// print report
|
||||
|
||||
if (verbose_level == 3 || verbose_level == 0)
|
||||
if (verbose_level == 3 || verbose_level == 0) {
|
||||
print_calibration_results(z_at_pt, _tower_results, _opposite_results);
|
||||
#if HAS_DELTA_SENSORLESS_PROBING
|
||||
if (verbose_level == 0 && probe_points == 1) {
|
||||
if (do_save_offset_adj)
|
||||
probe.set_offset_sensorless_adj(z_at_pt[CEN]);
|
||||
else
|
||||
probe.refresh_largest_sensorless_adj();
|
||||
}
|
||||
#endif
|
||||
}
|
||||
|
||||
if (verbose_level != 0) { // !dry run
|
||||
if ((zero_std_dev >= test_precision && iterations > force_iterations) || zero_std_dev <= calibration_precision) { // end iterations
|
||||
@@ -653,13 +669,13 @@ void GcodeSuite::G33() {
|
||||
}
|
||||
}
|
||||
else { // dry run
|
||||
PGM_P const enddryrun = PSTR("End DRY-RUN");
|
||||
SERIAL_ECHOPGM_P(enddryrun);
|
||||
FSTR_P const enddryrun = F("End DRY-RUN");
|
||||
SERIAL_ECHOF(enddryrun);
|
||||
SERIAL_ECHO_SP(35);
|
||||
SERIAL_ECHOLNPAIR_F("std dev:", zero_std_dev, 3);
|
||||
|
||||
char mess[21];
|
||||
strcpy_P(mess, enddryrun);
|
||||
strcpy_P(mess, FTOP(enddryrun));
|
||||
strcpy_P(&mess[11], PSTR(" sd:"));
|
||||
if (zero_std_dev < 1)
|
||||
sprintf_P(&mess[15], PSTR("0.%03i"), (int)LROUND(zero_std_dev * 1000.0f));
|
||||
@@ -674,6 +690,9 @@ void GcodeSuite::G33() {
|
||||
ac_cleanup(TERN_(HAS_MULTI_HOTEND, old_tool_index));
|
||||
|
||||
TERN_(FULL_REPORT_TO_HOST_FEATURE, set_and_report_grblstate(M_IDLE));
|
||||
#if HAS_DELTA_SENSORLESS_PROBING
|
||||
probe.test_sensitivity = { true, true, true };
|
||||
#endif
|
||||
}
|
||||
|
||||
#endif // DELTA_AUTO_CALIBRATION
|
||||
|
@@ -26,9 +26,12 @@
|
||||
|
||||
#include "../gcode.h"
|
||||
#include "../../module/motion.h"
|
||||
#include "../../module/stepper.h"
|
||||
#include "../../module/endstops.h"
|
||||
|
||||
#if ANY(HAS_MOTOR_CURRENT_SPI, HAS_MOTOR_CURRENT_PWM, HAS_TRINAMIC_CONFIG)
|
||||
#include "../../module/stepper.h"
|
||||
#endif
|
||||
|
||||
#if HAS_LEVELING
|
||||
#include "../../feature/bedlevel/bedlevel.h"
|
||||
#endif
|
||||
@@ -47,7 +50,7 @@ void GcodeSuite::G34() {
|
||||
TemporaryGlobalEndstopsState unlock_z(false);
|
||||
|
||||
#ifdef GANTRY_CALIBRATION_COMMANDS_PRE
|
||||
gcode.process_subcommands_now_P(PSTR(GANTRY_CALIBRATION_COMMANDS_PRE));
|
||||
process_subcommands_now(F(GANTRY_CALIBRATION_COMMANDS_PRE));
|
||||
if (DEBUGGING(LEVELING)) DEBUG_ECHOLNPGM("Sub Commands Processed");
|
||||
#endif
|
||||
|
||||
@@ -79,7 +82,7 @@ void GcodeSuite::G34() {
|
||||
stepper.set_digipot_current(Z_AXIS, target_current);
|
||||
#elif HAS_MOTOR_CURRENT_PWM
|
||||
const uint16_t target_current = parser.intval('S', GANTRY_CALIBRATION_CURRENT);
|
||||
const uint32_t previous_current = stepper.motor_current_setting[Z_AXIS];
|
||||
const uint32_t previous_current = stepper.motor_current_setting[1]; // Z
|
||||
stepper.set_digipot_current(1, target_current);
|
||||
#elif HAS_MOTOR_CURRENT_DAC
|
||||
const float target_current = parser.floatval('S', GANTRY_CALIBRATION_CURRENT);
|
||||
@@ -91,7 +94,7 @@ void GcodeSuite::G34() {
|
||||
digipot_i2c.set_current(Z_AXIS, target_current)
|
||||
#elif HAS_TRINAMIC_CONFIG
|
||||
const uint16_t target_current = parser.intval('S', GANTRY_CALIBRATION_CURRENT);
|
||||
static uint16_t previous_current_arr[NUM_Z_STEPPER_DRIVERS];
|
||||
static uint16_t previous_current_arr[NUM_Z_STEPPERS];
|
||||
#if AXIS_IS_TMC(Z)
|
||||
previous_current_arr[0] = stepperZ.getMilliamps();
|
||||
stepperZ.rms_current(target_current);
|
||||
@@ -114,10 +117,6 @@ void GcodeSuite::G34() {
|
||||
if (DEBUGGING(LEVELING)) DEBUG_ECHOLNPGM("Final Z Move");
|
||||
do_blocking_move_to_z(zgrind, MMM_TO_MMS(GANTRY_CALIBRATION_FEEDRATE));
|
||||
|
||||
// Back off end plate, back to normal motion range
|
||||
if (DEBUGGING(LEVELING)) DEBUG_ECHOLNPGM("Z Backoff");
|
||||
do_blocking_move_to_z(zpounce, MMM_TO_MMS(GANTRY_CALIBRATION_FEEDRATE));
|
||||
|
||||
#if _REDUCE_CURRENT
|
||||
// Reset current to original values
|
||||
if (DEBUGGING(LEVELING)) DEBUG_ECHOLNPGM("Restore Current");
|
||||
@@ -146,9 +145,13 @@ void GcodeSuite::G34() {
|
||||
#endif
|
||||
#endif
|
||||
|
||||
// Back off end plate, back to normal motion range
|
||||
if (DEBUGGING(LEVELING)) DEBUG_ECHOLNPGM("Z Backoff");
|
||||
do_blocking_move_to_z(zpounce, MMM_TO_MMS(GANTRY_CALIBRATION_FEEDRATE));
|
||||
|
||||
#ifdef GANTRY_CALIBRATION_COMMANDS_POST
|
||||
if (DEBUGGING(LEVELING)) DEBUG_ECHOLNPGM("Running Post Commands");
|
||||
gcode.process_subcommands_now_P(PSTR(GANTRY_CALIBRATION_COMMANDS_POST));
|
||||
process_subcommands_now(F(GANTRY_CALIBRATION_COMMANDS_POST));
|
||||
#endif
|
||||
|
||||
SET_SOFT_ENDSTOP_LOOSE(false);
|
||||
|
@@ -31,7 +31,7 @@
|
||||
#include "../../module/stepper.h"
|
||||
#include "../../module/planner.h"
|
||||
#include "../../module/probe.h"
|
||||
#include "../../lcd/marlinui.h" // for LCD_MESSAGEPGM
|
||||
#include "../../lcd/marlinui.h" // for LCD_MESSAGE
|
||||
|
||||
#if HAS_LEVELING
|
||||
#include "../../feature/bedlevel/bedlevel.h"
|
||||
@@ -41,16 +41,20 @@
|
||||
#include "../../module/tool_change.h"
|
||||
#endif
|
||||
|
||||
#if ENABLED(Z_STEPPER_ALIGN_KNOWN_STEPPER_POSITIONS)
|
||||
#if HAS_Z_STEPPER_ALIGN_STEPPER_XY
|
||||
#include "../../libs/least_squares_fit.h"
|
||||
#endif
|
||||
|
||||
#if ENABLED(BLTOUCH)
|
||||
#include "../../feature/bltouch.h"
|
||||
#endif
|
||||
|
||||
#define DEBUG_OUT ENABLED(DEBUG_LEVELING_FEATURE)
|
||||
#include "../../core/debug_out.h"
|
||||
|
||||
#if NUM_Z_STEPPER_DRIVERS >= 3
|
||||
#if NUM_Z_STEPPERS >= 3
|
||||
#define TRIPLE_Z 1
|
||||
#if NUM_Z_STEPPER_DRIVERS >= 4
|
||||
#if NUM_Z_STEPPERS >= 4
|
||||
#define QUAD_Z 1
|
||||
#endif
|
||||
#endif
|
||||
@@ -118,7 +122,7 @@ void GcodeSuite::G34() {
|
||||
break;
|
||||
}
|
||||
|
||||
const float z_auto_align_amplification = TERN(Z_STEPPER_ALIGN_KNOWN_STEPPER_POSITIONS, Z_STEPPER_ALIGN_AMP, parser.floatval('A', Z_STEPPER_ALIGN_AMP));
|
||||
const float z_auto_align_amplification = TERN(HAS_Z_STEPPER_ALIGN_STEPPER_XY, Z_STEPPER_ALIGN_AMP, parser.floatval('A', Z_STEPPER_ALIGN_AMP));
|
||||
if (!WITHIN(ABS(z_auto_align_amplification), 0.5f, 2.0f)) {
|
||||
SERIAL_ECHOLNPGM("?(A)mplification out of bounds (0.5-2.0).");
|
||||
break;
|
||||
@@ -149,7 +153,7 @@ void GcodeSuite::G34() {
|
||||
// In BLTOUCH HS mode, the probe travels in a deployed state.
|
||||
// Users of G34 might have a badly misaligned bed, so raise Z by the
|
||||
// length of the deployed pin (BLTOUCH stroke < 7mm)
|
||||
#define Z_BASIC_CLEARANCE (Z_CLEARANCE_BETWEEN_PROBES + 7.0f * BOTH(BLTOUCH, BLTOUCH_HS_MODE))
|
||||
#define Z_BASIC_CLEARANCE (Z_CLEARANCE_BETWEEN_PROBES + TERN0(BLTOUCH, bltouch.z_extra_clearance()))
|
||||
|
||||
// Compute a worst-case clearance height to probe from. After the first
|
||||
// iteration this will be re-calculated based on the actual bed position
|
||||
@@ -175,16 +179,16 @@ void GcodeSuite::G34() {
|
||||
// Now, the Z origin lies below the build plate. That allows to probe deeper, before run_z_probe throws an error.
|
||||
// This hack is un-done at the end of G34 - either by re-homing, or by using the probed heights of the last iteration.
|
||||
|
||||
#if DISABLED(Z_STEPPER_ALIGN_KNOWN_STEPPER_POSITIONS)
|
||||
float last_z_align_move[NUM_Z_STEPPER_DRIVERS] = ARRAY_N_1(NUM_Z_STEPPER_DRIVERS, 10000.0f);
|
||||
#if !HAS_Z_STEPPER_ALIGN_STEPPER_XY
|
||||
float last_z_align_move[NUM_Z_STEPPERS] = ARRAY_N_1(NUM_Z_STEPPERS, 10000.0f);
|
||||
#else
|
||||
float last_z_align_level_indicator = 10000.0f;
|
||||
#endif
|
||||
float z_measured[NUM_Z_STEPPER_DRIVERS] = { 0 },
|
||||
float z_measured[NUM_Z_STEPPERS] = { 0 },
|
||||
z_maxdiff = 0.0f,
|
||||
amplification = z_auto_align_amplification;
|
||||
|
||||
#if DISABLED(Z_STEPPER_ALIGN_KNOWN_STEPPER_POSITIONS)
|
||||
#if !HAS_Z_STEPPER_ALIGN_STEPPER_XY
|
||||
bool adjustment_reverse = false;
|
||||
#endif
|
||||
|
||||
@@ -213,23 +217,25 @@ void GcodeSuite::G34() {
|
||||
float z_measured_max = -100000.0f;
|
||||
|
||||
// Probe all positions (one per Z-Stepper)
|
||||
LOOP_L_N(i, NUM_Z_STEPPER_DRIVERS) {
|
||||
LOOP_L_N(i, NUM_Z_STEPPERS) {
|
||||
// iteration odd/even --> downward / upward stepper sequence
|
||||
const uint8_t iprobe = (iteration & 1) ? NUM_Z_STEPPER_DRIVERS - 1 - i : i;
|
||||
const uint8_t iprobe = (iteration & 1) ? NUM_Z_STEPPERS - 1 - i : i;
|
||||
|
||||
// Safe clearance even on an incline
|
||||
if ((iteration == 0 || i > 0) && z_probe > current_position.z) do_blocking_move_to_z(z_probe);
|
||||
|
||||
xy_pos_t &ppos = z_stepper_align.xy[iprobe];
|
||||
|
||||
if (DEBUGGING(LEVELING))
|
||||
DEBUG_ECHOLNPGM_P(PSTR("Probing X"), z_stepper_align.xy[iprobe].x, SP_Y_STR, z_stepper_align.xy[iprobe].y);
|
||||
DEBUG_ECHOLNPGM_P(PSTR("Probing X"), ppos.x, SP_Y_STR, ppos.y);
|
||||
|
||||
// Probe a Z height for each stepper.
|
||||
// Probing sanity check is disabled, as it would trigger even in normal cases because
|
||||
// current_position.z has been manually altered in the "dirty trick" above.
|
||||
const float z_probed_height = probe.probe_at_point(z_stepper_align.xy[iprobe], raise_after, 0, true, false);
|
||||
const float z_probed_height = probe.probe_at_point(DIFF_TERN(HAS_HOME_OFFSET, ppos, xy_pos_t(home_offset)), raise_after, 0, true, false);
|
||||
if (isnan(z_probed_height)) {
|
||||
SERIAL_ECHOLNPGM("Probing failed");
|
||||
LCD_MESSAGEPGM(MSG_LCD_PROBING_FAILED);
|
||||
LCD_MESSAGE(MSG_LCD_PROBING_FAILED);
|
||||
err_break = true;
|
||||
break;
|
||||
}
|
||||
@@ -252,7 +258,7 @@ void GcodeSuite::G34() {
|
||||
z_maxdiff = z_measured_max - z_measured_min;
|
||||
z_probe = Z_BASIC_CLEARANCE + z_measured_max + z_maxdiff;
|
||||
|
||||
#if ENABLED(Z_STEPPER_ALIGN_KNOWN_STEPPER_POSITIONS)
|
||||
#if HAS_Z_STEPPER_ALIGN_STEPPER_XY
|
||||
// Replace the initial values in z_measured with calculated heights at
|
||||
// each stepper position. This allows the adjustment algorithm to be
|
||||
// shared between both possible probing mechanisms.
|
||||
@@ -266,20 +272,20 @@ void GcodeSuite::G34() {
|
||||
// This allows the actual adjustment logic to be shared by both algorithms.
|
||||
linear_fit_data lfd;
|
||||
incremental_LSF_reset(&lfd);
|
||||
LOOP_L_N(i, NUM_Z_STEPPER_DRIVERS) {
|
||||
LOOP_L_N(i, NUM_Z_STEPPERS) {
|
||||
SERIAL_ECHOLNPGM("PROBEPT_", i, ": ", z_measured[i]);
|
||||
incremental_LSF(&lfd, z_stepper_align.xy[i], z_measured[i]);
|
||||
}
|
||||
finish_incremental_LSF(&lfd);
|
||||
|
||||
z_measured_min = 100000.0f;
|
||||
LOOP_L_N(i, NUM_Z_STEPPER_DRIVERS) {
|
||||
LOOP_L_N(i, NUM_Z_STEPPERS) {
|
||||
z_measured[i] = -(lfd.A * z_stepper_align.stepper_xy[i].x + lfd.B * z_stepper_align.stepper_xy[i].y + lfd.D);
|
||||
z_measured_min = _MIN(z_measured_min, z_measured[i]);
|
||||
}
|
||||
|
||||
SERIAL_ECHOLNPGM(
|
||||
LIST_N(DOUBLE(NUM_Z_STEPPER_DRIVERS),
|
||||
LIST_N(DOUBLE(NUM_Z_STEPPERS),
|
||||
"Calculated Z1=", z_measured[0],
|
||||
" Z2=", z_measured[1],
|
||||
" Z3=", z_measured[2],
|
||||
@@ -303,7 +309,7 @@ void GcodeSuite::G34() {
|
||||
|
||||
#if HAS_STATUS_MESSAGE
|
||||
char fstr1[10];
|
||||
char msg[6 + (6 + 5) * NUM_Z_STEPPER_DRIVERS + 1]
|
||||
char msg[6 + (6 + 5) * NUM_Z_STEPPERS + 1]
|
||||
#if TRIPLE_Z
|
||||
, fstr2[10], fstr3[10]
|
||||
#if QUAD_Z
|
||||
@@ -328,25 +334,25 @@ void GcodeSuite::G34() {
|
||||
auto decreasing_accuracy = [](const_float_t v1, const_float_t v2) {
|
||||
if (v1 < v2 * 0.7f) {
|
||||
SERIAL_ECHOLNPGM("Decreasing Accuracy Detected.");
|
||||
LCD_MESSAGEPGM(MSG_DECREASING_ACCURACY);
|
||||
LCD_MESSAGE(MSG_DECREASING_ACCURACY);
|
||||
return true;
|
||||
}
|
||||
return false;
|
||||
};
|
||||
|
||||
#if ENABLED(Z_STEPPER_ALIGN_KNOWN_STEPPER_POSITIONS)
|
||||
#if HAS_Z_STEPPER_ALIGN_STEPPER_XY
|
||||
// Check if the applied corrections go in the correct direction.
|
||||
// Calculate the sum of the absolute deviations from the mean of the probe measurements.
|
||||
// Compare to the last iteration to ensure it's getting better.
|
||||
|
||||
// Calculate mean value as a reference
|
||||
float z_measured_mean = 0.0f;
|
||||
LOOP_L_N(zstepper, NUM_Z_STEPPER_DRIVERS) z_measured_mean += z_measured[zstepper];
|
||||
z_measured_mean /= NUM_Z_STEPPER_DRIVERS;
|
||||
LOOP_L_N(zstepper, NUM_Z_STEPPERS) z_measured_mean += z_measured[zstepper];
|
||||
z_measured_mean /= NUM_Z_STEPPERS;
|
||||
|
||||
// Calculate the sum of the absolute deviations from the mean value
|
||||
float z_align_level_indicator = 0.0f;
|
||||
LOOP_L_N(zstepper, NUM_Z_STEPPER_DRIVERS)
|
||||
LOOP_L_N(zstepper, NUM_Z_STEPPERS)
|
||||
z_align_level_indicator += ABS(z_measured[zstepper] - z_measured_mean);
|
||||
|
||||
// If it's getting worse, stop and throw an error
|
||||
@@ -361,12 +367,12 @@ void GcodeSuite::G34() {
|
||||
|
||||
bool success_break = true;
|
||||
// Correct the individual stepper offsets
|
||||
LOOP_L_N(zstepper, NUM_Z_STEPPER_DRIVERS) {
|
||||
LOOP_L_N(zstepper, NUM_Z_STEPPERS) {
|
||||
// Calculate current stepper move
|
||||
float z_align_move = z_measured[zstepper] - z_measured_min;
|
||||
const float z_align_abs = ABS(z_align_move);
|
||||
|
||||
#if DISABLED(Z_STEPPER_ALIGN_KNOWN_STEPPER_POSITIONS)
|
||||
#if !HAS_Z_STEPPER_ALIGN_STEPPER_XY
|
||||
// Optimize one iteration's correction based on the first measurements
|
||||
if (z_align_abs) amplification = (iteration == 1) ? _MIN(last_z_align_move[zstepper] / z_align_abs, 2.0f) : z_auto_align_amplification;
|
||||
|
||||
@@ -390,7 +396,7 @@ void GcodeSuite::G34() {
|
||||
// Lock all steppers except one
|
||||
stepper.set_all_z_lock(true, zstepper);
|
||||
|
||||
#if DISABLED(Z_STEPPER_ALIGN_KNOWN_STEPPER_POSITIONS)
|
||||
#if !HAS_Z_STEPPER_ALIGN_STEPPER_XY
|
||||
// Decreasing accuracy was detected so move was inverted.
|
||||
// Will match reversed Z steppers on dual steppers. Triple will need more work to map.
|
||||
if (adjustment_reverse) {
|
||||
@@ -411,7 +417,7 @@ void GcodeSuite::G34() {
|
||||
|
||||
if (success_break) {
|
||||
SERIAL_ECHOLNPGM("Target accuracy achieved.");
|
||||
LCD_MESSAGEPGM(MSG_ACCURACY_ACHIEVED);
|
||||
LCD_MESSAGE(MSG_ACCURACY_ACHIEVED);
|
||||
break;
|
||||
}
|
||||
|
||||
@@ -433,7 +439,7 @@ void GcodeSuite::G34() {
|
||||
// After this operation the z position needs correction
|
||||
set_axis_never_homed(Z_AXIS);
|
||||
// Home Z after the alignment procedure
|
||||
process_subcommands_now_P(PSTR("G28Z"));
|
||||
process_subcommands_now(F("G28Z"));
|
||||
#else
|
||||
// Use the probed height from the last iteration to determine the Z height.
|
||||
// z_measured_min is used, because all steppers are aligned to z_measured_min.
|
||||
@@ -463,7 +469,7 @@ void GcodeSuite::G34() {
|
||||
*
|
||||
* S<index> : Index of the probe point to set
|
||||
*
|
||||
* With Z_STEPPER_ALIGN_KNOWN_STEPPER_POSITIONS:
|
||||
* With Z_STEPPER_ALIGN_STEPPER_XY:
|
||||
* W<index> : Index of the Z stepper position to set
|
||||
* The W and S parameters may not be combined.
|
||||
*
|
||||
@@ -482,42 +488,43 @@ void GcodeSuite::M422() {
|
||||
return;
|
||||
}
|
||||
|
||||
const bool is_probe_point = parser.seen('S');
|
||||
const bool is_probe_point = parser.seen_test('S');
|
||||
|
||||
if (TERN0(Z_STEPPER_ALIGN_KNOWN_STEPPER_POSITIONS, is_probe_point && parser.seen('W'))) {
|
||||
if (TERN0(HAS_Z_STEPPER_ALIGN_STEPPER_XY, is_probe_point && parser.seen_test('W'))) {
|
||||
SERIAL_ECHOLNPGM("?(S) and (W) may not be combined.");
|
||||
return;
|
||||
}
|
||||
|
||||
xy_pos_t *pos_dest = (
|
||||
TERN_(Z_STEPPER_ALIGN_KNOWN_STEPPER_POSITIONS, !is_probe_point ? z_stepper_align.stepper_xy :)
|
||||
xy_pos_t * const pos_dest = (
|
||||
TERN_(HAS_Z_STEPPER_ALIGN_STEPPER_XY, !is_probe_point ? z_stepper_align.stepper_xy :)
|
||||
z_stepper_align.xy
|
||||
);
|
||||
|
||||
if (!is_probe_point && TERN1(Z_STEPPER_ALIGN_KNOWN_STEPPER_POSITIONS, !parser.seen('W'))) {
|
||||
SERIAL_ECHOLNPGM("?(S)" TERN_(Z_STEPPER_ALIGN_KNOWN_STEPPER_POSITIONS, " or (W)") " is required.");
|
||||
if (!is_probe_point && TERN1(HAS_Z_STEPPER_ALIGN_STEPPER_XY, !parser.seen_test('W'))) {
|
||||
SERIAL_ECHOLNPGM("?(S)" TERN_(HAS_Z_STEPPER_ALIGN_STEPPER_XY, " or (W)") " is required.");
|
||||
return;
|
||||
}
|
||||
|
||||
// Get the Probe Position Index or Z Stepper Index
|
||||
int8_t position_index;
|
||||
if (is_probe_point) {
|
||||
position_index = parser.intval('S') - 1;
|
||||
if (!WITHIN(position_index, 0, int8_t(NUM_Z_STEPPER_DRIVERS) - 1)) {
|
||||
SERIAL_ECHOLNPGM("?(S) Probe-position index invalid.");
|
||||
return;
|
||||
}
|
||||
}
|
||||
int8_t position_index = 1;
|
||||
FSTR_P err_string = F("?(S) Probe-position");
|
||||
if (is_probe_point)
|
||||
position_index = parser.intval('S');
|
||||
else {
|
||||
#if ENABLED(Z_STEPPER_ALIGN_KNOWN_STEPPER_POSITIONS)
|
||||
position_index = parser.intval('W') - 1;
|
||||
if (!WITHIN(position_index, 0, NUM_Z_STEPPER_DRIVERS - 1)) {
|
||||
SERIAL_ECHOLNPGM("?(W) Z-stepper index invalid.");
|
||||
return;
|
||||
}
|
||||
#if HAS_Z_STEPPER_ALIGN_STEPPER_XY
|
||||
err_string = F("?(W) Z-stepper");
|
||||
position_index = parser.intval('W');
|
||||
#endif
|
||||
}
|
||||
|
||||
if (!WITHIN(position_index, 1, NUM_Z_STEPPERS)) {
|
||||
SERIAL_ECHOF(err_string);
|
||||
SERIAL_ECHOLNPGM(" index invalid (1.." STRINGIFY(NUM_Z_STEPPERS) ").");
|
||||
return;
|
||||
}
|
||||
|
||||
--position_index;
|
||||
|
||||
const xy_pos_t pos = {
|
||||
parser.floatval('X', pos_dest[position_index].x),
|
||||
parser.floatval('Y', pos_dest[position_index].y)
|
||||
@@ -538,8 +545,8 @@ void GcodeSuite::M422() {
|
||||
}
|
||||
|
||||
void GcodeSuite::M422_report(const bool forReplay/*=true*/) {
|
||||
report_heading(forReplay, PSTR(STR_Z_AUTO_ALIGN));
|
||||
LOOP_L_N(i, NUM_Z_STEPPER_DRIVERS) {
|
||||
report_heading(forReplay, F(STR_Z_AUTO_ALIGN));
|
||||
LOOP_L_N(i, NUM_Z_STEPPERS) {
|
||||
report_echo_start(forReplay);
|
||||
SERIAL_ECHOLNPGM_P(
|
||||
PSTR(" M422 S"), i + 1,
|
||||
@@ -547,8 +554,8 @@ void GcodeSuite::M422_report(const bool forReplay/*=true*/) {
|
||||
SP_Y_STR, z_stepper_align.xy[i].y
|
||||
);
|
||||
}
|
||||
#if ENABLED(Z_STEPPER_ALIGN_KNOWN_STEPPER_POSITIONS)
|
||||
LOOP_L_N(i, NUM_Z_STEPPER_DRIVERS) {
|
||||
#if HAS_Z_STEPPER_ALIGN_STEPPER_XY
|
||||
LOOP_L_N(i, NUM_Z_STEPPERS) {
|
||||
report_echo_start(forReplay);
|
||||
SERIAL_ECHOLNPGM_P(
|
||||
PSTR(" M422 W"), i + 1,
|
||||
|
@@ -73,22 +73,31 @@
|
||||
#if BOTH(CALIBRATION_MEASURE_LEFT, CALIBRATION_MEASURE_RIGHT)
|
||||
#define HAS_X_CENTER 1
|
||||
#endif
|
||||
#if HAS_Y_AXIS && BOTH(CALIBRATION_MEASURE_FRONT, CALIBRATION_MEASURE_BACK)
|
||||
#if ALL(HAS_Y_AXIS, CALIBRATION_MEASURE_FRONT, CALIBRATION_MEASURE_BACK)
|
||||
#define HAS_Y_CENTER 1
|
||||
#endif
|
||||
#if LINEAR_AXES >= 4 && BOTH(CALIBRATION_MEASURE_IMIN, CALIBRATION_MEASURE_IMAX)
|
||||
#if ALL(HAS_I_AXIS, CALIBRATION_MEASURE_IMIN, CALIBRATION_MEASURE_IMAX)
|
||||
#define HAS_I_CENTER 1
|
||||
#endif
|
||||
#if LINEAR_AXES >= 5 && BOTH(CALIBRATION_MEASURE_JMIN, CALIBRATION_MEASURE_JMAX)
|
||||
#if ALL(HAS_J_AXIS, CALIBRATION_MEASURE_JMIN, CALIBRATION_MEASURE_JMAX)
|
||||
#define HAS_J_CENTER 1
|
||||
#endif
|
||||
#if LINEAR_AXES >= 6 && BOTH(CALIBRATION_MEASURE_KMIN, CALIBRATION_MEASURE_KMAX)
|
||||
#if ALL(HAS_K_AXIS, CALIBRATION_MEASURE_KMIN, CALIBRATION_MEASURE_KMAX)
|
||||
#define HAS_K_CENTER 1
|
||||
#endif
|
||||
#if ALL(HAS_U_AXIS, CALIBRATION_MEASURE_UMIN, CALIBRATION_MEASURE_UMAX)
|
||||
#define HAS_U_CENTER 1
|
||||
#endif
|
||||
#if ALL(HAS_V_AXIS, CALIBRATION_MEASURE_VMIN, CALIBRATION_MEASURE_VMAX)
|
||||
#define HAS_V_CENTER 1
|
||||
#endif
|
||||
#if ALL(HAS_W_AXIS, CALIBRATION_MEASURE_WMIN, CALIBRATION_MEASURE_WMAX)
|
||||
#define HAS_W_CENTER 1
|
||||
#endif
|
||||
|
||||
enum side_t : uint8_t {
|
||||
TOP, RIGHT, FRONT, LEFT, BACK, NUM_SIDES,
|
||||
LIST_N(DOUBLE(SUB3(LINEAR_AXES)), IMINIMUM, IMAXIMUM, JMINIMUM, JMAXIMUM, KMINIMUM, KMAXIMUM)
|
||||
LIST_N(DOUBLE(SECONDARY_AXES), IMINIMUM, IMAXIMUM, JMINIMUM, JMAXIMUM, KMINIMUM, KMAXIMUM, UMINIMUM, UMAXIMUM, VMINIMUM, VMAXIMUM, WMINIMUM, WMAXIMUM)
|
||||
};
|
||||
|
||||
static constexpr xyz_pos_t true_center CALIBRATION_OBJECT_CENTER;
|
||||
@@ -105,13 +114,27 @@ struct measurements_t {
|
||||
};
|
||||
|
||||
#if ENABLED(BACKLASH_GCODE)
|
||||
#define TEMPORARY_BACKLASH_CORRECTION(value) REMEMBER(tbst, backlash.correction, value)
|
||||
class restorer_correction {
|
||||
const uint8_t val_;
|
||||
public:
|
||||
restorer_correction(const uint8_t temp_val) : val_(backlash.get_correction_uint8()) { backlash.set_correction_uint8(temp_val); }
|
||||
~restorer_correction() { backlash.set_correction_uint8(val_); }
|
||||
};
|
||||
|
||||
#define TEMPORARY_BACKLASH_CORRECTION(value) restorer_correction restorer_tbst(value)
|
||||
#else
|
||||
#define TEMPORARY_BACKLASH_CORRECTION(value)
|
||||
#endif
|
||||
|
||||
#if ENABLED(BACKLASH_GCODE) && defined(BACKLASH_SMOOTHING_MM)
|
||||
#define TEMPORARY_BACKLASH_SMOOTHING(value) REMEMBER(tbsm, backlash.smoothing_mm, value)
|
||||
class restorer_smoothing {
|
||||
const float val_;
|
||||
public:
|
||||
restorer_smoothing(const float temp_val) : val_(backlash.get_smoothing_mm()) { backlash.set_smoothing_mm(temp_val); }
|
||||
~restorer_smoothing() { backlash.set_smoothing_mm(val_); }
|
||||
};
|
||||
|
||||
#define TEMPORARY_BACKLASH_SMOOTHING(value) restorer_smoothing restorer_tbsm(value)
|
||||
#else
|
||||
#define TEMPORARY_BACKLASH_SMOOTHING(value)
|
||||
#endif
|
||||
@@ -241,14 +264,15 @@ inline void probe_side(measurements_t &m, const float uncertainty, const side_t
|
||||
|
||||
park_above_object(m, uncertainty);
|
||||
|
||||
#define _ACASE(N,A,B) case A: dir = -1; case B: axis = N##_AXIS; break
|
||||
#define _PCASE(N) _ACASE(N, N##MINIMUM, N##MAXIMUM)
|
||||
|
||||
switch (side) {
|
||||
#if AXIS_CAN_CALIBRATE(X)
|
||||
case RIGHT: dir = -1;
|
||||
case LEFT: axis = X_AXIS; break;
|
||||
_ACASE(X, RIGHT, LEFT);
|
||||
#endif
|
||||
#if LINEAR_AXES >= 2 && AXIS_CAN_CALIBRATE(Y)
|
||||
case BACK: dir = -1;
|
||||
case FRONT: axis = Y_AXIS; break;
|
||||
#if HAS_Y_AXIS && AXIS_CAN_CALIBRATE(Y)
|
||||
_ACASE(Y, BACK, FRONT);
|
||||
#endif
|
||||
#if HAS_Z_AXIS && AXIS_CAN_CALIBRATE(Z)
|
||||
case TOP: {
|
||||
@@ -258,17 +282,23 @@ inline void probe_side(measurements_t &m, const float uncertainty, const side_t
|
||||
return;
|
||||
}
|
||||
#endif
|
||||
#if LINEAR_AXES >= 4 && AXIS_CAN_CALIBRATE(I)
|
||||
case IMINIMUM: dir = -1;
|
||||
case IMAXIMUM: axis = I_AXIS; break;
|
||||
#if HAS_I_AXIS && AXIS_CAN_CALIBRATE(I)
|
||||
_PCASE(I);
|
||||
#endif
|
||||
#if LINEAR_AXES >= 5 && AXIS_CAN_CALIBRATE(J)
|
||||
case JMINIMUM: dir = -1;
|
||||
case JMAXIMUM: axis = J_AXIS; break;
|
||||
#if HAS_J_AXIS && AXIS_CAN_CALIBRATE(J)
|
||||
_PCASE(J);
|
||||
#endif
|
||||
#if LINEAR_AXES >= 6 && AXIS_CAN_CALIBRATE(K)
|
||||
case KMINIMUM: dir = -1;
|
||||
case KMAXIMUM: axis = K_AXIS; break;
|
||||
#if HAS_K_AXIS && AXIS_CAN_CALIBRATE(K)
|
||||
_PCASE(K);
|
||||
#endif
|
||||
#if HAS_U_AXIS && AXIS_CAN_CALIBRATE(U)
|
||||
_PCASE(U);
|
||||
#endif
|
||||
#if HAS_V_AXIS && AXIS_CAN_CALIBRATE(V)
|
||||
_PCASE(V);
|
||||
#endif
|
||||
#if HAS_W_AXIS && AXIS_CAN_CALIBRATE(W)
|
||||
_PCASE(W);
|
||||
#endif
|
||||
default: return;
|
||||
}
|
||||
@@ -323,6 +353,12 @@ inline void probe_sides(measurements_t &m, const float uncertainty) {
|
||||
TERN_(CALIBRATION_MEASURE_JMAX, probe_side(m, uncertainty, JMAXIMUM, probe_top_at_edge));
|
||||
TERN_(CALIBRATION_MEASURE_KMIN, probe_side(m, uncertainty, KMINIMUM, probe_top_at_edge));
|
||||
TERN_(CALIBRATION_MEASURE_KMAX, probe_side(m, uncertainty, KMAXIMUM, probe_top_at_edge));
|
||||
TERN_(CALIBRATION_MEASURE_UMIN, probe_side(m, uncertainty, UMINIMUM, probe_top_at_edge));
|
||||
TERN_(CALIBRATION_MEASURE_UMAX, probe_side(m, uncertainty, UMAXIMUM, probe_top_at_edge));
|
||||
TERN_(CALIBRATION_MEASURE_VMIN, probe_side(m, uncertainty, VMINIMUM, probe_top_at_edge));
|
||||
TERN_(CALIBRATION_MEASURE_VMAX, probe_side(m, uncertainty, VMAXIMUM, probe_top_at_edge));
|
||||
TERN_(CALIBRATION_MEASURE_WMIN, probe_side(m, uncertainty, WMINIMUM, probe_top_at_edge));
|
||||
TERN_(CALIBRATION_MEASURE_WMAX, probe_side(m, uncertainty, WMAXIMUM, probe_top_at_edge));
|
||||
|
||||
// Compute the measured center of the calibration object.
|
||||
TERN_(HAS_X_CENTER, m.obj_center.x = (m.obj_side[LEFT] + m.obj_side[RIGHT]) / 2);
|
||||
@@ -330,6 +366,9 @@ inline void probe_sides(measurements_t &m, const float uncertainty) {
|
||||
TERN_(HAS_I_CENTER, m.obj_center.i = (m.obj_side[IMINIMUM] + m.obj_side[IMAXIMUM]) / 2);
|
||||
TERN_(HAS_J_CENTER, m.obj_center.j = (m.obj_side[JMINIMUM] + m.obj_side[JMAXIMUM]) / 2);
|
||||
TERN_(HAS_K_CENTER, m.obj_center.k = (m.obj_side[KMINIMUM] + m.obj_side[KMAXIMUM]) / 2);
|
||||
TERN_(HAS_U_CENTER, m.obj_center.u = (m.obj_side[UMINIMUM] + m.obj_side[UMAXIMUM]) / 2);
|
||||
TERN_(HAS_V_CENTER, m.obj_center.v = (m.obj_side[VMINIMUM] + m.obj_side[VMAXIMUM]) / 2);
|
||||
TERN_(HAS_W_CENTER, m.obj_center.w = (m.obj_side[WMINIMUM] + m.obj_side[WMAXIMUM]) / 2);
|
||||
|
||||
// Compute the outside diameter of the nozzle at the height
|
||||
// at which it makes contact with the calibration object
|
||||
@@ -340,13 +379,16 @@ inline void probe_sides(measurements_t &m, const float uncertainty) {
|
||||
|
||||
// The difference between the known and the measured location
|
||||
// of the calibration object is the positional error
|
||||
LINEAR_AXIS_CODE(
|
||||
NUM_AXIS_CODE(
|
||||
m.pos_error.x = TERN0(HAS_X_CENTER, true_center.x - m.obj_center.x),
|
||||
m.pos_error.y = TERN0(HAS_Y_CENTER, true_center.y - m.obj_center.y),
|
||||
m.pos_error.z = true_center.z - m.obj_center.z,
|
||||
m.pos_error.i = TERN0(HAS_I_CENTER, true_center.i - m.obj_center.i),
|
||||
m.pos_error.j = TERN0(HAS_J_CENTER, true_center.j - m.obj_center.j),
|
||||
m.pos_error.k = TERN0(HAS_K_CENTER, true_center.k - m.obj_center.k)
|
||||
m.pos_error.k = TERN0(HAS_K_CENTER, true_center.k - m.obj_center.k),
|
||||
m.pos_error.u = TERN0(HAS_U_CENTER, true_center.u - m.obj_center.u),
|
||||
m.pos_error.v = TERN0(HAS_V_CENTER, true_center.v - m.obj_center.v),
|
||||
m.pos_error.w = TERN0(HAS_W_CENTER, true_center.w - m.obj_center.w)
|
||||
);
|
||||
}
|
||||
|
||||
@@ -370,7 +412,7 @@ inline void probe_sides(measurements_t &m, const float uncertainty) {
|
||||
SERIAL_ECHOLNPGM(" Back: ", m.obj_side[BACK]);
|
||||
#endif
|
||||
#endif
|
||||
#if LINEAR_AXES >= 4
|
||||
#if HAS_I_AXIS
|
||||
#if ENABLED(CALIBRATION_MEASURE_IMIN)
|
||||
SERIAL_ECHOLNPGM(" " STR_I_MIN ": ", m.obj_side[IMINIMUM]);
|
||||
#endif
|
||||
@@ -378,7 +420,7 @@ inline void probe_sides(measurements_t &m, const float uncertainty) {
|
||||
SERIAL_ECHOLNPGM(" " STR_I_MAX ": ", m.obj_side[IMAXIMUM]);
|
||||
#endif
|
||||
#endif
|
||||
#if LINEAR_AXES >= 5
|
||||
#if HAS_J_AXIS
|
||||
#if ENABLED(CALIBRATION_MEASURE_JMIN)
|
||||
SERIAL_ECHOLNPGM(" " STR_J_MIN ": ", m.obj_side[JMINIMUM]);
|
||||
#endif
|
||||
@@ -386,7 +428,7 @@ inline void probe_sides(measurements_t &m, const float uncertainty) {
|
||||
SERIAL_ECHOLNPGM(" " STR_J_MAX ": ", m.obj_side[JMAXIMUM]);
|
||||
#endif
|
||||
#endif
|
||||
#if LINEAR_AXES >= 6
|
||||
#if HAS_K_AXIS
|
||||
#if ENABLED(CALIBRATION_MEASURE_KMIN)
|
||||
SERIAL_ECHOLNPGM(" " STR_K_MIN ": ", m.obj_side[KMINIMUM]);
|
||||
#endif
|
||||
@@ -394,6 +436,30 @@ inline void probe_sides(measurements_t &m, const float uncertainty) {
|
||||
SERIAL_ECHOLNPGM(" " STR_K_MAX ": ", m.obj_side[KMAXIMUM]);
|
||||
#endif
|
||||
#endif
|
||||
#if HAS_U_AXIS
|
||||
#if ENABLED(CALIBRATION_MEASURE_UMIN)
|
||||
SERIAL_ECHOLNPGM(" " STR_U_MIN ": ", m.obj_side[UMINIMUM]);
|
||||
#endif
|
||||
#if ENABLED(CALIBRATION_MEASURE_UMAX)
|
||||
SERIAL_ECHOLNPGM(" " STR_U_MAX ": ", m.obj_side[UMAXIMUM]);
|
||||
#endif
|
||||
#endif
|
||||
#if HAS_V_AXIS
|
||||
#if ENABLED(CALIBRATION_MEASURE_VMIN)
|
||||
SERIAL_ECHOLNPGM(" " STR_V_MIN ": ", m.obj_side[VMINIMUM]);
|
||||
#endif
|
||||
#if ENABLED(CALIBRATION_MEASURE_VMAX)
|
||||
SERIAL_ECHOLNPGM(" " STR_V_MAX ": ", m.obj_side[VMAXIMUM]);
|
||||
#endif
|
||||
#endif
|
||||
#if HAS_W_AXIS
|
||||
#if ENABLED(CALIBRATION_MEASURE_WMIN)
|
||||
SERIAL_ECHOLNPGM(" " STR_W_MIN ": ", m.obj_side[WMINIMUM]);
|
||||
#endif
|
||||
#if ENABLED(CALIBRATION_MEASURE_WMAX)
|
||||
SERIAL_ECHOLNPGM(" " STR_W_MAX ": ", m.obj_side[WMAXIMUM]);
|
||||
#endif
|
||||
#endif
|
||||
SERIAL_EOL();
|
||||
}
|
||||
|
||||
@@ -415,6 +481,15 @@ inline void probe_sides(measurements_t &m, const float uncertainty) {
|
||||
#if HAS_K_CENTER
|
||||
SERIAL_ECHOLNPGM_P(SP_K_STR, m.obj_center.k);
|
||||
#endif
|
||||
#if HAS_U_CENTER
|
||||
SERIAL_ECHOLNPGM_P(SP_U_STR, m.obj_center.u);
|
||||
#endif
|
||||
#if HAS_V_CENTER
|
||||
SERIAL_ECHOLNPGM_P(SP_V_STR, m.obj_center.v);
|
||||
#endif
|
||||
#if HAS_W_CENTER
|
||||
SERIAL_ECHOLNPGM_P(SP_W_STR, m.obj_center.w);
|
||||
#endif
|
||||
SERIAL_EOL();
|
||||
}
|
||||
|
||||
@@ -439,7 +514,7 @@ inline void probe_sides(measurements_t &m, const float uncertainty) {
|
||||
#if HAS_Z_AXIS && AXIS_CAN_CALIBRATE(Z)
|
||||
SERIAL_ECHOLNPGM(" Top: ", m.backlash[TOP]);
|
||||
#endif
|
||||
#if LINEAR_AXES >= 4 && AXIS_CAN_CALIBRATE(I)
|
||||
#if HAS_I_AXIS && AXIS_CAN_CALIBRATE(I)
|
||||
#if ENABLED(CALIBRATION_MEASURE_IMIN)
|
||||
SERIAL_ECHOLNPGM(" " STR_I_MIN ": ", m.backlash[IMINIMUM]);
|
||||
#endif
|
||||
@@ -447,7 +522,7 @@ inline void probe_sides(measurements_t &m, const float uncertainty) {
|
||||
SERIAL_ECHOLNPGM(" " STR_I_MAX ": ", m.backlash[IMAXIMUM]);
|
||||
#endif
|
||||
#endif
|
||||
#if LINEAR_AXES >= 5 && AXIS_CAN_CALIBRATE(J)
|
||||
#if HAS_J_AXIS && AXIS_CAN_CALIBRATE(J)
|
||||
#if ENABLED(CALIBRATION_MEASURE_JMIN)
|
||||
SERIAL_ECHOLNPGM(" " STR_J_MIN ": ", m.backlash[JMINIMUM]);
|
||||
#endif
|
||||
@@ -455,7 +530,7 @@ inline void probe_sides(measurements_t &m, const float uncertainty) {
|
||||
SERIAL_ECHOLNPGM(" " STR_J_MAX ": ", m.backlash[JMAXIMUM]);
|
||||
#endif
|
||||
#endif
|
||||
#if LINEAR_AXES >= 6 && AXIS_CAN_CALIBRATE(K)
|
||||
#if HAS_K_AXIS && AXIS_CAN_CALIBRATE(K)
|
||||
#if ENABLED(CALIBRATION_MEASURE_KMIN)
|
||||
SERIAL_ECHOLNPGM(" " STR_K_MIN ": ", m.backlash[KMINIMUM]);
|
||||
#endif
|
||||
@@ -463,6 +538,30 @@ inline void probe_sides(measurements_t &m, const float uncertainty) {
|
||||
SERIAL_ECHOLNPGM(" " STR_K_MAX ": ", m.backlash[KMAXIMUM]);
|
||||
#endif
|
||||
#endif
|
||||
#if HAS_U_AXIS && AXIS_CAN_CALIBRATE(U)
|
||||
#if ENABLED(CALIBRATION_MEASURE_UMIN)
|
||||
SERIAL_ECHOLNPGM(" " STR_U_MIN ": ", m.backlash[UMINIMUM]);
|
||||
#endif
|
||||
#if ENABLED(CALIBRATION_MEASURE_UMAX)
|
||||
SERIAL_ECHOLNPGM(" " STR_U_MAX ": ", m.backlash[UMAXIMUM]);
|
||||
#endif
|
||||
#endif
|
||||
#if HAS_V_AXIS && AXIS_CAN_CALIBRATE(V)
|
||||
#if ENABLED(CALIBRATION_MEASURE_VMIN)
|
||||
SERIAL_ECHOLNPGM(" " STR_V_MIN ": ", m.backlash[VMINIMUM]);
|
||||
#endif
|
||||
#if ENABLED(CALIBRATION_MEASURE_VMAX)
|
||||
SERIAL_ECHOLNPGM(" " STR_V_MAX ": ", m.backlash[VMAXIMUM]);
|
||||
#endif
|
||||
#endif
|
||||
#if HAS_W_AXIS && AXIS_CAN_CALIBRATE(W)
|
||||
#if ENABLED(CALIBRATION_MEASURE_WMIN)
|
||||
SERIAL_ECHOLNPGM(" " STR_W_MIN ": ", m.backlash[WMINIMUM]);
|
||||
#endif
|
||||
#if ENABLED(CALIBRATION_MEASURE_WMAX)
|
||||
SERIAL_ECHOLNPGM(" " STR_W_MAX ": ", m.backlash[WMAXIMUM]);
|
||||
#endif
|
||||
#endif
|
||||
SERIAL_EOL();
|
||||
}
|
||||
|
||||
@@ -486,7 +585,16 @@ inline void probe_sides(measurements_t &m, const float uncertainty) {
|
||||
SERIAL_ECHOLNPGM_P(SP_J_STR, m.pos_error.j);
|
||||
#endif
|
||||
#if HAS_K_CENTER && AXIS_CAN_CALIBRATE(K)
|
||||
SERIAL_ECHOLNPGM_P(SP_Z_STR, m.pos_error.z);
|
||||
SERIAL_ECHOLNPGM_P(SP_K_STR, m.pos_error.k);
|
||||
#endif
|
||||
#if HAS_U_CENTER && AXIS_CAN_CALIBRATE(U)
|
||||
SERIAL_ECHOLNPGM_P(SP_U_STR, m.pos_error.u);
|
||||
#endif
|
||||
#if HAS_V_CENTER && AXIS_CAN_CALIBRATE(V)
|
||||
SERIAL_ECHOLNPGM_P(SP_V_STR, m.pos_error.v);
|
||||
#endif
|
||||
#if HAS_W_CENTER && AXIS_CAN_CALIBRATE(W)
|
||||
SERIAL_ECHOLNPGM_P(SP_W_STR, m.pos_error.w);
|
||||
#endif
|
||||
SERIAL_EOL();
|
||||
}
|
||||
@@ -526,7 +634,7 @@ inline void calibrate_backlash(measurements_t &m, const float uncertainty) {
|
||||
|
||||
{
|
||||
// New scope for TEMPORARY_BACKLASH_CORRECTION
|
||||
TEMPORARY_BACKLASH_CORRECTION(all_off);
|
||||
TEMPORARY_BACKLASH_CORRECTION(backlash.all_off);
|
||||
TEMPORARY_BACKLASH_SMOOTHING(0.0f);
|
||||
|
||||
probe_sides(m, uncertainty);
|
||||
@@ -534,45 +642,69 @@ inline void calibrate_backlash(measurements_t &m, const float uncertainty) {
|
||||
#if ENABLED(BACKLASH_GCODE)
|
||||
|
||||
#if HAS_X_CENTER
|
||||
backlash.distance_mm.x = (m.backlash[LEFT] + m.backlash[RIGHT]) / 2;
|
||||
backlash.set_distance_mm(X_AXIS, (m.backlash[LEFT] + m.backlash[RIGHT]) / 2);
|
||||
#elif ENABLED(CALIBRATION_MEASURE_LEFT)
|
||||
backlash.distance_mm.x = m.backlash[LEFT];
|
||||
backlash.set_distance_mm(X_AXIS, m.backlash[LEFT]);
|
||||
#elif ENABLED(CALIBRATION_MEASURE_RIGHT)
|
||||
backlash.distance_mm.x = m.backlash[RIGHT];
|
||||
backlash.set_distance_mm(X_AXIS, m.backlash[RIGHT]);
|
||||
#endif
|
||||
|
||||
#if HAS_Y_CENTER
|
||||
backlash.distance_mm.y = (m.backlash[FRONT] + m.backlash[BACK]) / 2;
|
||||
backlash.set_distance_mm(Y_AXIS, (m.backlash[FRONT] + m.backlash[BACK]) / 2);
|
||||
#elif ENABLED(CALIBRATION_MEASURE_FRONT)
|
||||
backlash.distance_mm.y = m.backlash[FRONT];
|
||||
backlash.set_distance_mm(Y_AXIS, m.backlash[FRONT]);
|
||||
#elif ENABLED(CALIBRATION_MEASURE_BACK)
|
||||
backlash.distance_mm.y = m.backlash[BACK];
|
||||
backlash.set_distance_mm(Y_AXIS, m.backlash[BACK]);
|
||||
#endif
|
||||
|
||||
TERN_(HAS_Z_AXIS, if (AXIS_CAN_CALIBRATE(Z)) backlash.distance_mm.z = m.backlash[TOP]);
|
||||
TERN_(HAS_Z_AXIS, if (AXIS_CAN_CALIBRATE(Z)) backlash.set_distance_mm(Z_AXIS, m.backlash[TOP]));
|
||||
|
||||
#if HAS_I_CENTER
|
||||
backlash.distance_mm.i = (m.backlash[IMINIMUM] + m.backlash[IMAXIMUM]) / 2;
|
||||
backlash.set_distance_mm(I_AXIS, (m.backlash[IMINIMUM] + m.backlash[IMAXIMUM]) / 2);
|
||||
#elif ENABLED(CALIBRATION_MEASURE_IMIN)
|
||||
backlash.distance_mm.i = m.backlash[IMINIMUM];
|
||||
backlash.set_distance_mm(I_AXIS, m.backlash[IMINIMUM]);
|
||||
#elif ENABLED(CALIBRATION_MEASURE_IMAX)
|
||||
backlash.distance_mm.i = m.backlash[IMAXIMUM];
|
||||
backlash.set_distance_mm(I_AXIS, m.backlash[IMAXIMUM]);
|
||||
#endif
|
||||
|
||||
#if HAS_J_CENTER
|
||||
backlash.distance_mm.j = (m.backlash[JMINIMUM] + m.backlash[JMAXIMUM]) / 2;
|
||||
backlash.set_distance_mm(J_AXIS, (m.backlash[JMINIMUM] + m.backlash[JMAXIMUM]) / 2);
|
||||
#elif ENABLED(CALIBRATION_MEASURE_JMIN)
|
||||
backlash.distance_mm.j = m.backlash[JMINIMUM];
|
||||
backlash.set_distance_mm(J_AXIS, m.backlash[JMINIMUM]);
|
||||
#elif ENABLED(CALIBRATION_MEASURE_JMAX)
|
||||
backlash.distance_mm.j = m.backlash[JMAXIMUM];
|
||||
backlash.set_distance_mm(J_AXIS, m.backlash[JMAXIMUM]);
|
||||
#endif
|
||||
|
||||
#if HAS_K_CENTER
|
||||
backlash.distance_mm.k = (m.backlash[KMINIMUM] + m.backlash[KMAXIMUM]) / 2;
|
||||
backlash.set_distance_mm(K_AXIS, (m.backlash[KMINIMUM] + m.backlash[KMAXIMUM]) / 2);
|
||||
#elif ENABLED(CALIBRATION_MEASURE_KMIN)
|
||||
backlash.distance_mm.k = m.backlash[KMINIMUM];
|
||||
backlash.set_distance_mm(K_AXIS, m.backlash[KMINIMUM]);
|
||||
#elif ENABLED(CALIBRATION_MEASURE_KMAX)
|
||||
backlash.distance_mm.k = m.backlash[KMAXIMUM];
|
||||
backlash.set_distance_mm(K_AXIS, m.backlash[KMAXIMUM]);
|
||||
#endif
|
||||
|
||||
#if HAS_U_CENTER
|
||||
backlash.distance_mm.u = (m.backlash[UMINIMUM] + m.backlash[UMAXIMUM]) / 2;
|
||||
#elif ENABLED(CALIBRATION_MEASURE_UMIN)
|
||||
backlash.distance_mm.u = m.backlash[UMINIMUM];
|
||||
#elif ENABLED(CALIBRATION_MEASURE_UMAX)
|
||||
backlash.distance_mm.u = m.backlash[UMAXIMUM];
|
||||
#endif
|
||||
|
||||
#if HAS_V_CENTER
|
||||
backlash.distance_mm.v = (m.backlash[VMINIMUM] + m.backlash[VMAXIMUM]) / 2;
|
||||
#elif ENABLED(CALIBRATION_MEASURE_VMIN)
|
||||
backlash.distance_mm.v = m.backlash[VMINIMUM];
|
||||
#elif ENABLED(CALIBRATION_MEASURE_UMAX)
|
||||
backlash.distance_mm.v = m.backlash[VMAXIMUM];
|
||||
#endif
|
||||
|
||||
#if HAS_W_CENTER
|
||||
backlash.distance_mm.w = (m.backlash[WMINIMUM] + m.backlash[WMAXIMUM]) / 2;
|
||||
#elif ENABLED(CALIBRATION_MEASURE_WMIN)
|
||||
backlash.distance_mm.w = m.backlash[WMINIMUM];
|
||||
#elif ENABLED(CALIBRATION_MEASURE_WMAX)
|
||||
backlash.distance_mm.w = m.backlash[WMAXIMUM];
|
||||
#endif
|
||||
|
||||
#endif // BACKLASH_GCODE
|
||||
@@ -583,11 +715,12 @@ inline void calibrate_backlash(measurements_t &m, const float uncertainty) {
|
||||
// allowed directions to take up any backlash
|
||||
{
|
||||
// New scope for TEMPORARY_BACKLASH_CORRECTION
|
||||
TEMPORARY_BACKLASH_CORRECTION(all_on);
|
||||
TEMPORARY_BACKLASH_CORRECTION(backlash.all_on);
|
||||
TEMPORARY_BACKLASH_SMOOTHING(0.0f);
|
||||
const xyz_float_t move = LINEAR_AXIS_ARRAY(
|
||||
const xyz_float_t move = NUM_AXIS_ARRAY(
|
||||
AXIS_CAN_CALIBRATE(X) * 3, AXIS_CAN_CALIBRATE(Y) * 3, AXIS_CAN_CALIBRATE(Z) * 3,
|
||||
AXIS_CAN_CALIBRATE(I) * 3, AXIS_CAN_CALIBRATE(J) * 3, AXIS_CAN_CALIBRATE(K) * 3
|
||||
AXIS_CAN_CALIBRATE(I) * 3, AXIS_CAN_CALIBRATE(J) * 3, AXIS_CAN_CALIBRATE(K) * 3,
|
||||
AXIS_CAN_CALIBRATE(U) * 3, AXIS_CAN_CALIBRATE(V) * 3, AXIS_CAN_CALIBRATE(W) * 3
|
||||
);
|
||||
current_position += move; calibration_move();
|
||||
current_position -= move; calibration_move();
|
||||
@@ -613,7 +746,7 @@ inline void update_measurements(measurements_t &m, const AxisEnum axis) {
|
||||
* - Call calibrate_backlash() beforehand for best accuracy
|
||||
*/
|
||||
inline void calibrate_toolhead(measurements_t &m, const float uncertainty, const uint8_t extruder) {
|
||||
TEMPORARY_BACKLASH_CORRECTION(all_on);
|
||||
TEMPORARY_BACKLASH_CORRECTION(backlash.all_on);
|
||||
TEMPORARY_BACKLASH_SMOOTHING(0.0f);
|
||||
|
||||
TERN(HAS_MULTI_HOTEND, set_nozzle(m, extruder), UNUSED(extruder));
|
||||
@@ -638,6 +771,9 @@ inline void calibrate_toolhead(measurements_t &m, const float uncertainty, const
|
||||
TERN_(HAS_I_CENTER, update_measurements(m, I_AXIS));
|
||||
TERN_(HAS_J_CENTER, update_measurements(m, J_AXIS));
|
||||
TERN_(HAS_K_CENTER, update_measurements(m, K_AXIS));
|
||||
TERN_(HAS_U_CENTER, update_measurements(m, U_AXIS));
|
||||
TERN_(HAS_V_CENTER, update_measurements(m, V_AXIS));
|
||||
TERN_(HAS_W_CENTER, update_measurements(m, W_AXIS));
|
||||
|
||||
sync_plan_position();
|
||||
}
|
||||
@@ -650,7 +786,7 @@ inline void calibrate_toolhead(measurements_t &m, const float uncertainty, const
|
||||
* uncertainty in - How far away from the object to begin probing
|
||||
*/
|
||||
inline void calibrate_all_toolheads(measurements_t &m, const float uncertainty) {
|
||||
TEMPORARY_BACKLASH_CORRECTION(all_on);
|
||||
TEMPORARY_BACKLASH_CORRECTION(backlash.all_on);
|
||||
TEMPORARY_BACKLASH_SMOOTHING(0.0f);
|
||||
|
||||
HOTEND_LOOP() calibrate_toolhead(m, uncertainty, e);
|
||||
@@ -666,7 +802,7 @@ inline void calibrate_all_toolheads(measurements_t &m, const float uncertainty)
|
||||
* 1) For each nozzle, touch top and sides of object to determine object position and
|
||||
* nozzle offsets. Do a fast but rough search over a wider area.
|
||||
* 2) With the first nozzle, touch top and sides of object to determine backlash values
|
||||
* for all axis (if BACKLASH_GCODE is enabled)
|
||||
* for all axes (if BACKLASH_GCODE is enabled)
|
||||
* 3) For each nozzle, touch top and sides of object slowly to determine precise
|
||||
* position of object. Adjust coordinate system and nozzle offsets so probed object
|
||||
* location corresponds to known object location with a high degree of precision.
|
||||
@@ -676,7 +812,7 @@ inline void calibrate_all() {
|
||||
|
||||
TERN_(HAS_HOTEND_OFFSET, reset_hotend_offsets());
|
||||
|
||||
TEMPORARY_BACKLASH_CORRECTION(all_on);
|
||||
TEMPORARY_BACKLASH_CORRECTION(backlash.all_on);
|
||||
TEMPORARY_BACKLASH_SMOOTHING(0.0f);
|
||||
|
||||
// Do a fast and rough calibration of the toolheads
|
||||
@@ -709,7 +845,7 @@ inline void calibrate_all() {
|
||||
void GcodeSuite::G425() {
|
||||
|
||||
#ifdef CALIBRATION_SCRIPT_PRE
|
||||
GcodeSuite::process_subcommands_now_P(PSTR(CALIBRATION_SCRIPT_PRE));
|
||||
process_subcommands_now(F(CALIBRATION_SCRIPT_PRE));
|
||||
#endif
|
||||
|
||||
if (homing_needed_error()) return;
|
||||
@@ -745,7 +881,7 @@ void GcodeSuite::G425() {
|
||||
SET_SOFT_ENDSTOP_LOOSE(false);
|
||||
|
||||
#ifdef CALIBRATION_SCRIPT_POST
|
||||
GcodeSuite::process_subcommands_now_P(PSTR(CALIBRATION_SCRIPT_POST));
|
||||
process_subcommands_now(F(CALIBRATION_SCRIPT_POST));
|
||||
#endif
|
||||
}
|
||||
|
||||
|
@@ -1,358 +0,0 @@
|
||||
/**
|
||||
* Marlin 3D Printer Firmware
|
||||
* Copyright (c) 2020 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 <https://www.gnu.org/licenses/>.
|
||||
*
|
||||
*/
|
||||
|
||||
/**
|
||||
* G76_M871.cpp - Temperature calibration/compensation for z-probing
|
||||
*/
|
||||
|
||||
#include "../../inc/MarlinConfig.h"
|
||||
|
||||
#if ENABLED(PROBE_TEMP_COMPENSATION)
|
||||
|
||||
#include "../gcode.h"
|
||||
#include "../../module/motion.h"
|
||||
#include "../../module/planner.h"
|
||||
#include "../../module/probe.h"
|
||||
#include "../../feature/bedlevel/bedlevel.h"
|
||||
#include "../../module/temperature.h"
|
||||
#include "../../module/probe.h"
|
||||
#include "../../feature/probe_temp_comp.h"
|
||||
#include "../../lcd/marlinui.h"
|
||||
|
||||
/**
|
||||
* G76: calibrate probe and/or bed temperature offsets
|
||||
* Notes:
|
||||
* - When calibrating probe, bed temperature is held constant.
|
||||
* Compensation values are deltas to first probe measurement at probe temp. = 30°C.
|
||||
* - When calibrating bed, probe temperature is held constant.
|
||||
* Compensation values are deltas to first probe measurement at bed temp. = 60°C.
|
||||
* - The hotend will not be heated at any time.
|
||||
* - On my Průša MK3S clone I put a piece of paper between the probe and the hotend
|
||||
* so the hotend fan would not cool my probe constantly. Alternatively you could just
|
||||
* make sure the fan is not running while running the calibration process.
|
||||
*
|
||||
* Probe calibration:
|
||||
* - Moves probe to cooldown point.
|
||||
* - Heats up bed to 100°C.
|
||||
* - Moves probe to probing point (1mm above heatbed).
|
||||
* - Waits until probe reaches target temperature (30°C).
|
||||
* - Does a z-probing (=base value) and increases target temperature by 5°C.
|
||||
* - Waits until probe reaches increased target temperature.
|
||||
* - Does a z-probing (delta to base value will be a compensation value) and increases target temperature by 5°C.
|
||||
* - Repeats last two steps until max. temperature reached or timeout (i.e. probe does not heat up any further).
|
||||
* - Compensation values of higher temperatures will be extrapolated (using linear regression first).
|
||||
* While this is not exact by any means it is still better than simply using the last compensation value.
|
||||
*
|
||||
* Bed calibration:
|
||||
* - Moves probe to cooldown point.
|
||||
* - Heats up bed to 60°C.
|
||||
* - Moves probe to probing point (1mm above heatbed).
|
||||
* - Waits until probe reaches target temperature (30°C).
|
||||
* - Does a z-probing (=base value) and increases bed temperature by 5°C.
|
||||
* - Moves probe to cooldown point.
|
||||
* - Waits until probe is below 30°C and bed has reached target temperature.
|
||||
* - Moves probe to probing point and waits until it reaches target temperature (30°C).
|
||||
* - Does a z-probing (delta to base value will be a compensation value) and increases bed temperature by 5°C.
|
||||
* - Repeats last four points until max. bed temperature reached (110°C) or timeout.
|
||||
* - Compensation values of higher temperatures will be extrapolated (using linear regression first).
|
||||
* While this is not exact by any means it is still better than simply using the last compensation value.
|
||||
*
|
||||
* G76 [B | P]
|
||||
* - no flag - Both calibration procedures will be run.
|
||||
* - `B` - Run bed temperature calibration.
|
||||
* - `P` - Run probe temperature calibration.
|
||||
*/
|
||||
|
||||
static void say_waiting_for() { SERIAL_ECHOPGM("Waiting for "); }
|
||||
static void say_waiting_for_probe_heating() { say_waiting_for(); SERIAL_ECHOLNPGM("probe heating."); }
|
||||
static void say_successfully_calibrated() { SERIAL_ECHOPGM("Successfully calibrated"); }
|
||||
static void say_failed_to_calibrate() { SERIAL_ECHOPGM("!Failed to calibrate"); }
|
||||
|
||||
void GcodeSuite::G76() {
|
||||
// Check if heated bed is available and z-homing is done with probe
|
||||
#if TEMP_SENSOR_BED == 0 || !(HOMING_Z_WITH_PROBE)
|
||||
return;
|
||||
#endif
|
||||
|
||||
auto report_temps = [](millis_t &ntr, millis_t timeout=0) {
|
||||
idle_no_sleep();
|
||||
const millis_t ms = millis();
|
||||
if (ELAPSED(ms, ntr)) {
|
||||
ntr = ms + 1000;
|
||||
thermalManager.print_heater_states(active_extruder);
|
||||
}
|
||||
return (timeout && ELAPSED(ms, timeout));
|
||||
};
|
||||
|
||||
auto wait_for_temps = [&](const celsius_t tb, const celsius_t tp, millis_t &ntr, const millis_t timeout=0) {
|
||||
say_waiting_for(); SERIAL_ECHOLNPGM("bed and probe temperature.");
|
||||
while (thermalManager.wholeDegBed() != tb || thermalManager.wholeDegProbe() > tp)
|
||||
if (report_temps(ntr, timeout)) return true;
|
||||
return false;
|
||||
};
|
||||
|
||||
auto g76_probe = [](const TempSensorID sid, celsius_t &targ, const xy_pos_t &nozpos) {
|
||||
do_z_clearance(5.0); // Raise nozzle before probing
|
||||
const float measured_z = probe.probe_at_point(nozpos, PROBE_PT_STOW, 0, false); // verbose=0, probe_relative=false
|
||||
if (isnan(measured_z))
|
||||
SERIAL_ECHOLNPGM("!Received NAN. Aborting.");
|
||||
else {
|
||||
SERIAL_ECHOLNPAIR_F("Measured: ", measured_z);
|
||||
if (targ == cali_info_init[sid].start_temp)
|
||||
temp_comp.prepare_new_calibration(measured_z);
|
||||
else
|
||||
temp_comp.push_back_new_measurement(sid, measured_z);
|
||||
targ += cali_info_init[sid].temp_res;
|
||||
}
|
||||
return measured_z;
|
||||
};
|
||||
|
||||
#if ENABLED(BLTOUCH)
|
||||
// Make sure any BLTouch error condition is cleared
|
||||
bltouch_command(BLTOUCH_RESET, BLTOUCH_RESET_DELAY);
|
||||
set_bltouch_deployed(false);
|
||||
#endif
|
||||
|
||||
bool do_bed_cal = parser.boolval('B'), do_probe_cal = parser.boolval('P');
|
||||
if (!do_bed_cal && !do_probe_cal) do_bed_cal = do_probe_cal = true;
|
||||
|
||||
// Synchronize with planner
|
||||
planner.synchronize();
|
||||
|
||||
const xyz_pos_t parkpos = temp_comp.park_point,
|
||||
probe_pos_xyz = xyz_pos_t(temp_comp.measure_point) + xyz_pos_t({ 0.0f, 0.0f, PTC_PROBE_HEATING_OFFSET }),
|
||||
noz_pos_xyz = probe_pos_xyz - probe.offset_xy; // Nozzle position based on probe position
|
||||
|
||||
if (do_bed_cal || do_probe_cal) {
|
||||
// Ensure park position is reachable
|
||||
bool reachable = position_is_reachable(parkpos) || WITHIN(parkpos.z, Z_MIN_POS - fslop, Z_MAX_POS + fslop);
|
||||
if (!reachable)
|
||||
SERIAL_ECHOLNPGM("!Park");
|
||||
else {
|
||||
// Ensure probe position is reachable
|
||||
reachable = probe.can_reach(probe_pos_xyz);
|
||||
if (!reachable) SERIAL_ECHOLNPGM("!Probe");
|
||||
}
|
||||
|
||||
if (!reachable) {
|
||||
SERIAL_ECHOLNPGM(" position unreachable - aborting.");
|
||||
return;
|
||||
}
|
||||
|
||||
process_subcommands_now_P(G28_STR);
|
||||
}
|
||||
|
||||
remember_feedrate_scaling_off();
|
||||
|
||||
/******************************************
|
||||
* Calibrate bed temperature offsets
|
||||
******************************************/
|
||||
|
||||
// Report temperatures every second and handle heating timeouts
|
||||
millis_t next_temp_report = millis() + 1000;
|
||||
|
||||
auto report_targets = [&](const celsius_t tb, const celsius_t tp) {
|
||||
SERIAL_ECHOLNPGM("Target Bed:", tb, " Probe:", tp);
|
||||
};
|
||||
|
||||
if (do_bed_cal) {
|
||||
|
||||
celsius_t target_bed = cali_info_init[TSI_BED].start_temp,
|
||||
target_probe = temp_comp.bed_calib_probe_temp;
|
||||
|
||||
say_waiting_for(); SERIAL_ECHOLNPGM(" cooling.");
|
||||
while (thermalManager.wholeDegBed() > target_bed || thermalManager.wholeDegProbe() > target_probe)
|
||||
report_temps(next_temp_report);
|
||||
|
||||
// Disable leveling so it won't mess with us
|
||||
TERN_(HAS_LEVELING, set_bed_leveling_enabled(false));
|
||||
|
||||
for (;;) {
|
||||
thermalManager.setTargetBed(target_bed);
|
||||
|
||||
report_targets(target_bed, target_probe);
|
||||
|
||||
// Park nozzle
|
||||
do_blocking_move_to(parkpos);
|
||||
|
||||
// Wait for heatbed to reach target temp and probe to cool below target temp
|
||||
if (wait_for_temps(target_bed, target_probe, next_temp_report, millis() + MIN_TO_MS(15))) {
|
||||
SERIAL_ECHOLNPGM("!Bed heating timeout.");
|
||||
break;
|
||||
}
|
||||
|
||||
// Move the nozzle to the probing point and wait for the probe to reach target temp
|
||||
do_blocking_move_to(noz_pos_xyz);
|
||||
say_waiting_for_probe_heating();
|
||||
SERIAL_EOL();
|
||||
while (thermalManager.wholeDegProbe() < target_probe)
|
||||
report_temps(next_temp_report);
|
||||
|
||||
const float measured_z = g76_probe(TSI_BED, target_bed, noz_pos_xyz);
|
||||
if (isnan(measured_z) || target_bed > (BED_MAX_TARGET)) break;
|
||||
}
|
||||
|
||||
SERIAL_ECHOLNPGM("Retrieved measurements: ", temp_comp.get_index());
|
||||
if (temp_comp.finish_calibration(TSI_BED)) {
|
||||
say_successfully_calibrated();
|
||||
SERIAL_ECHOLNPGM(" bed.");
|
||||
}
|
||||
else {
|
||||
say_failed_to_calibrate();
|
||||
SERIAL_ECHOLNPGM(" bed. Values reset.");
|
||||
}
|
||||
|
||||
// Cleanup
|
||||
thermalManager.setTargetBed(0);
|
||||
TERN_(HAS_LEVELING, set_bed_leveling_enabled(true));
|
||||
} // do_bed_cal
|
||||
|
||||
/********************************************
|
||||
* Calibrate probe temperature offsets
|
||||
********************************************/
|
||||
|
||||
if (do_probe_cal) {
|
||||
|
||||
// Park nozzle
|
||||
do_blocking_move_to(parkpos);
|
||||
|
||||
// Initialize temperatures
|
||||
const celsius_t target_bed = temp_comp.probe_calib_bed_temp;
|
||||
thermalManager.setTargetBed(target_bed);
|
||||
|
||||
celsius_t target_probe = cali_info_init[TSI_PROBE].start_temp;
|
||||
|
||||
report_targets(target_bed, target_probe);
|
||||
|
||||
// Wait for heatbed to reach target temp and probe to cool below target temp
|
||||
wait_for_temps(target_bed, target_probe, next_temp_report);
|
||||
|
||||
// Disable leveling so it won't mess with us
|
||||
TERN_(HAS_LEVELING, set_bed_leveling_enabled(false));
|
||||
|
||||
bool timeout = false;
|
||||
for (;;) {
|
||||
// Move probe to probing point and wait for it to reach target temperature
|
||||
do_blocking_move_to(noz_pos_xyz);
|
||||
|
||||
say_waiting_for_probe_heating();
|
||||
SERIAL_ECHOLNPGM(" Bed:", target_bed, " Probe:", target_probe);
|
||||
const millis_t probe_timeout_ms = millis() + SEC_TO_MS(900UL);
|
||||
while (thermalManager.degProbe() < target_probe) {
|
||||
if (report_temps(next_temp_report, probe_timeout_ms)) {
|
||||
SERIAL_ECHOLNPGM("!Probe heating timed out.");
|
||||
timeout = true;
|
||||
break;
|
||||
}
|
||||
}
|
||||
if (timeout) break;
|
||||
|
||||
const float measured_z = g76_probe(TSI_PROBE, target_probe, noz_pos_xyz);
|
||||
if (isnan(measured_z) || target_probe > cali_info_init[TSI_PROBE].end_temp) break;
|
||||
}
|
||||
|
||||
SERIAL_ECHOLNPGM("Retrieved measurements: ", temp_comp.get_index());
|
||||
if (temp_comp.finish_calibration(TSI_PROBE))
|
||||
say_successfully_calibrated();
|
||||
else
|
||||
say_failed_to_calibrate();
|
||||
SERIAL_ECHOLNPGM(" probe.");
|
||||
|
||||
// Cleanup
|
||||
thermalManager.setTargetBed(0);
|
||||
TERN_(HAS_LEVELING, set_bed_leveling_enabled(true));
|
||||
|
||||
SERIAL_ECHOLNPGM("Final compensation values:");
|
||||
temp_comp.print_offsets();
|
||||
} // do_probe_cal
|
||||
|
||||
restore_feedrate_and_scaling();
|
||||
}
|
||||
|
||||
/**
|
||||
* M871: Report / reset temperature compensation offsets.
|
||||
* Note: This does not affect values in EEPROM until M500.
|
||||
*
|
||||
* M871 [ R | B | P | E ]
|
||||
*
|
||||
* No Parameters - Print current offset values.
|
||||
*
|
||||
* Select only one of these flags:
|
||||
* R - Reset all offsets to zero (i.e., disable compensation).
|
||||
* B - Manually set offset for bed
|
||||
* P - Manually set offset for probe
|
||||
* E - Manually set offset for extruder
|
||||
*
|
||||
* With B, P, or E:
|
||||
* I[index] - Index in the array
|
||||
* V[value] - Adjustment in µm
|
||||
*/
|
||||
void GcodeSuite::M871() {
|
||||
|
||||
if (parser.seen('R')) {
|
||||
// Reset z-probe offsets to factory defaults
|
||||
temp_comp.clear_all_offsets();
|
||||
SERIAL_ECHOLNPGM("Offsets reset to default.");
|
||||
}
|
||||
else if (parser.seen("BPE")) {
|
||||
if (!parser.seenval('V')) return;
|
||||
const int16_t offset_val = parser.value_int();
|
||||
if (!parser.seenval('I')) return;
|
||||
const int16_t idx = parser.value_int();
|
||||
const TempSensorID mod = (parser.seen('B') ? TSI_BED :
|
||||
#if ENABLED(USE_TEMP_EXT_COMPENSATION)
|
||||
parser.seen('E') ? TSI_EXT :
|
||||
#endif
|
||||
TSI_PROBE
|
||||
);
|
||||
if (idx > 0 && temp_comp.set_offset(mod, idx - 1, offset_val))
|
||||
SERIAL_ECHOLNPGM("Set value: ", offset_val);
|
||||
else
|
||||
SERIAL_ECHOLNPGM("!Invalid index. Failed to set value (note: value at index 0 is constant).");
|
||||
|
||||
}
|
||||
else // Print current Z-probe adjustments. Note: Values in EEPROM might differ.
|
||||
temp_comp.print_offsets();
|
||||
}
|
||||
|
||||
/**
|
||||
* M192: Wait for probe temperature sensor to reach a target
|
||||
*
|
||||
* Select only one of these flags:
|
||||
* R - Wait for heating or cooling
|
||||
* S - Wait only for heating
|
||||
*/
|
||||
void GcodeSuite::M192() {
|
||||
if (DEBUGGING(DRYRUN)) return;
|
||||
|
||||
const bool no_wait_for_cooling = parser.seenval('S');
|
||||
if (!no_wait_for_cooling && ! parser.seenval('R')) {
|
||||
SERIAL_ERROR_MSG("No target temperature set.");
|
||||
return;
|
||||
}
|
||||
|
||||
const celsius_t target_temp = parser.value_celsius();
|
||||
ui.set_status_P(thermalManager.isProbeBelowTemp(target_temp) ? GET_TEXT(MSG_PROBE_HEATING) : GET_TEXT(MSG_PROBE_COOLING));
|
||||
thermalManager.wait_for_probe(target_temp, no_wait_for_cooling);
|
||||
}
|
||||
|
||||
#endif // PROBE_TEMP_COMPENSATION
|
339
Marlin/src/gcode/calibrate/G76_M871.cpp
Normal file
339
Marlin/src/gcode/calibrate/G76_M871.cpp
Normal file
@@ -0,0 +1,339 @@
|
||||
/**
|
||||
* Marlin 3D Printer Firmware
|
||||
* Copyright (c) 2020 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 <https://www.gnu.org/licenses/>.
|
||||
*
|
||||
*/
|
||||
|
||||
/**
|
||||
* G76_M871.cpp - Temperature calibration/compensation for z-probing
|
||||
*/
|
||||
|
||||
#include "../../inc/MarlinConfig.h"
|
||||
|
||||
#if HAS_PTC
|
||||
|
||||
#include "../gcode.h"
|
||||
#include "../../module/motion.h"
|
||||
#include "../../module/planner.h"
|
||||
#include "../../module/probe.h"
|
||||
#include "../../feature/bedlevel/bedlevel.h"
|
||||
#include "../../module/temperature.h"
|
||||
#include "../../module/probe.h"
|
||||
#include "../../feature/probe_temp_comp.h"
|
||||
#include "../../lcd/marlinui.h"
|
||||
|
||||
/**
|
||||
* G76: calibrate probe and/or bed temperature offsets
|
||||
* Notes:
|
||||
* - When calibrating probe, bed temperature is held constant.
|
||||
* Compensation values are deltas to first probe measurement at probe temp. = 30°C.
|
||||
* - When calibrating bed, probe temperature is held constant.
|
||||
* Compensation values are deltas to first probe measurement at bed temp. = 60°C.
|
||||
* - The hotend will not be heated at any time.
|
||||
* - On my Průša MK3S clone I put a piece of paper between the probe and the hotend
|
||||
* so the hotend fan would not cool my probe constantly. Alternatively you could just
|
||||
* make sure the fan is not running while running the calibration process.
|
||||
*
|
||||
* Probe calibration:
|
||||
* - Moves probe to cooldown point.
|
||||
* - Heats up bed to 100°C.
|
||||
* - Moves probe to probing point (1mm above heatbed).
|
||||
* - Waits until probe reaches target temperature (30°C).
|
||||
* - Does a z-probing (=base value) and increases target temperature by 5°C.
|
||||
* - Waits until probe reaches increased target temperature.
|
||||
* - Does a z-probing (delta to base value will be a compensation value) and increases target temperature by 5°C.
|
||||
* - Repeats last two steps until max. temperature reached or timeout (i.e. probe does not heat up any further).
|
||||
* - Compensation values of higher temperatures will be extrapolated (using linear regression first).
|
||||
* While this is not exact by any means it is still better than simply using the last compensation value.
|
||||
*
|
||||
* Bed calibration:
|
||||
* - Moves probe to cooldown point.
|
||||
* - Heats up bed to 60°C.
|
||||
* - Moves probe to probing point (1mm above heatbed).
|
||||
* - Waits until probe reaches target temperature (30°C).
|
||||
* - Does a z-probing (=base value) and increases bed temperature by 5°C.
|
||||
* - Moves probe to cooldown point.
|
||||
* - Waits until probe is below 30°C and bed has reached target temperature.
|
||||
* - Moves probe to probing point and waits until it reaches target temperature (30°C).
|
||||
* - Does a z-probing (delta to base value will be a compensation value) and increases bed temperature by 5°C.
|
||||
* - Repeats last four points until max. bed temperature reached (110°C) or timeout.
|
||||
* - Compensation values of higher temperatures will be extrapolated (using linear regression first).
|
||||
* While this is not exact by any means it is still better than simply using the last compensation value.
|
||||
*
|
||||
* G76 [B | P]
|
||||
* - no flag - Both calibration procedures will be run.
|
||||
* - `B` - Run bed temperature calibration.
|
||||
* - `P` - Run probe temperature calibration.
|
||||
*/
|
||||
|
||||
#if BOTH(PTC_PROBE, PTC_BED)
|
||||
|
||||
static void say_waiting_for() { SERIAL_ECHOPGM("Waiting for "); }
|
||||
static void say_waiting_for_probe_heating() { say_waiting_for(); SERIAL_ECHOLNPGM("probe heating."); }
|
||||
static void say_successfully_calibrated() { SERIAL_ECHOPGM("Successfully calibrated"); }
|
||||
static void say_failed_to_calibrate() { SERIAL_ECHOPGM("!Failed to calibrate"); }
|
||||
|
||||
void GcodeSuite::G76() {
|
||||
auto report_temps = [](millis_t &ntr, millis_t timeout=0) {
|
||||
idle_no_sleep();
|
||||
const millis_t ms = millis();
|
||||
if (ELAPSED(ms, ntr)) {
|
||||
ntr = ms + 1000;
|
||||
thermalManager.print_heater_states(active_extruder);
|
||||
}
|
||||
return (timeout && ELAPSED(ms, timeout));
|
||||
};
|
||||
|
||||
auto wait_for_temps = [&](const celsius_t tb, const celsius_t tp, millis_t &ntr, const millis_t timeout=0) {
|
||||
say_waiting_for(); SERIAL_ECHOLNPGM("bed and probe temperature.");
|
||||
while (thermalManager.wholeDegBed() != tb || thermalManager.wholeDegProbe() > tp)
|
||||
if (report_temps(ntr, timeout)) return true;
|
||||
return false;
|
||||
};
|
||||
|
||||
auto g76_probe = [](const TempSensorID sid, celsius_t &targ, const xy_pos_t &nozpos) {
|
||||
do_z_clearance(5.0); // Raise nozzle before probing
|
||||
ptc.set_enabled(false);
|
||||
const float measured_z = probe.probe_at_point(nozpos, PROBE_PT_STOW, 0, false); // verbose=0, probe_relative=false
|
||||
ptc.set_enabled(true);
|
||||
if (isnan(measured_z))
|
||||
SERIAL_ECHOLNPGM("!Received NAN. Aborting.");
|
||||
else {
|
||||
SERIAL_ECHOLNPAIR_F("Measured: ", measured_z);
|
||||
if (targ == ProbeTempComp::cali_info[sid].start_temp)
|
||||
ptc.prepare_new_calibration(measured_z);
|
||||
else
|
||||
ptc.push_back_new_measurement(sid, measured_z);
|
||||
targ += ProbeTempComp::cali_info[sid].temp_resolution;
|
||||
}
|
||||
return measured_z;
|
||||
};
|
||||
|
||||
#if ENABLED(BLTOUCH)
|
||||
// Make sure any BLTouch error condition is cleared
|
||||
bltouch_command(BLTOUCH_RESET, BLTOUCH_RESET_DELAY);
|
||||
set_bltouch_deployed(false);
|
||||
#endif
|
||||
|
||||
bool do_bed_cal = parser.boolval('B'), do_probe_cal = parser.boolval('P');
|
||||
if (!do_bed_cal && !do_probe_cal) do_bed_cal = do_probe_cal = true;
|
||||
|
||||
// Synchronize with planner
|
||||
planner.synchronize();
|
||||
|
||||
#ifndef PTC_PROBE_HEATING_OFFSET
|
||||
#define PTC_PROBE_HEATING_OFFSET 0
|
||||
#endif
|
||||
const xyz_pos_t parkpos = PTC_PARK_POS,
|
||||
probe_pos_xyz = xyz_pos_t(PTC_PROBE_POS) + xyz_pos_t({ 0.0f, 0.0f, PTC_PROBE_HEATING_OFFSET }),
|
||||
noz_pos_xyz = probe_pos_xyz - probe.offset_xy; // Nozzle position based on probe position
|
||||
|
||||
if (do_bed_cal || do_probe_cal) {
|
||||
// Ensure park position is reachable
|
||||
bool reachable = position_is_reachable(parkpos) || WITHIN(parkpos.z, Z_MIN_POS - fslop, Z_MAX_POS + fslop);
|
||||
if (!reachable)
|
||||
SERIAL_ECHOLNPGM("!Park");
|
||||
else {
|
||||
// Ensure probe position is reachable
|
||||
reachable = probe.can_reach(probe_pos_xyz);
|
||||
if (!reachable) SERIAL_ECHOLNPGM("!Probe");
|
||||
}
|
||||
|
||||
if (!reachable) {
|
||||
SERIAL_ECHOLNPGM(" position unreachable - aborting.");
|
||||
return;
|
||||
}
|
||||
|
||||
process_subcommands_now(FPSTR(G28_STR));
|
||||
}
|
||||
|
||||
remember_feedrate_scaling_off();
|
||||
|
||||
/******************************************
|
||||
* Calibrate bed temperature offsets
|
||||
******************************************/
|
||||
|
||||
// Report temperatures every second and handle heating timeouts
|
||||
millis_t next_temp_report = millis() + 1000;
|
||||
|
||||
auto report_targets = [&](const celsius_t tb, const celsius_t tp) {
|
||||
SERIAL_ECHOLNPGM("Target Bed:", tb, " Probe:", tp);
|
||||
};
|
||||
|
||||
if (do_bed_cal) {
|
||||
|
||||
celsius_t target_bed = PTC_BED_START,
|
||||
target_probe = PTC_PROBE_TEMP;
|
||||
|
||||
say_waiting_for(); SERIAL_ECHOLNPGM(" cooling.");
|
||||
while (thermalManager.wholeDegBed() > target_bed || thermalManager.wholeDegProbe() > target_probe)
|
||||
report_temps(next_temp_report);
|
||||
|
||||
// Disable leveling so it won't mess with us
|
||||
TERN_(HAS_LEVELING, set_bed_leveling_enabled(false));
|
||||
|
||||
for (uint8_t idx = 0; idx <= PTC_BED_COUNT; idx++) {
|
||||
thermalManager.setTargetBed(target_bed);
|
||||
|
||||
report_targets(target_bed, target_probe);
|
||||
|
||||
// Park nozzle
|
||||
do_blocking_move_to(parkpos);
|
||||
|
||||
// Wait for heatbed to reach target temp and probe to cool below target temp
|
||||
if (wait_for_temps(target_bed, target_probe, next_temp_report, millis() + MIN_TO_MS(15))) {
|
||||
SERIAL_ECHOLNPGM("!Bed heating timeout.");
|
||||
break;
|
||||
}
|
||||
|
||||
// Move the nozzle to the probing point and wait for the probe to reach target temp
|
||||
do_blocking_move_to(noz_pos_xyz);
|
||||
say_waiting_for_probe_heating();
|
||||
SERIAL_EOL();
|
||||
while (thermalManager.wholeDegProbe() < target_probe)
|
||||
report_temps(next_temp_report);
|
||||
|
||||
const float measured_z = g76_probe(TSI_BED, target_bed, noz_pos_xyz);
|
||||
if (isnan(measured_z) || target_bed > (BED_MAX_TARGET)) break;
|
||||
}
|
||||
|
||||
SERIAL_ECHOLNPGM("Retrieved measurements: ", ptc.get_index());
|
||||
if (ptc.finish_calibration(TSI_BED)) {
|
||||
say_successfully_calibrated();
|
||||
SERIAL_ECHOLNPGM(" bed.");
|
||||
}
|
||||
else {
|
||||
say_failed_to_calibrate();
|
||||
SERIAL_ECHOLNPGM(" bed. Values reset.");
|
||||
}
|
||||
|
||||
// Cleanup
|
||||
thermalManager.setTargetBed(0);
|
||||
TERN_(HAS_LEVELING, set_bed_leveling_enabled(true));
|
||||
} // do_bed_cal
|
||||
|
||||
/********************************************
|
||||
* Calibrate probe temperature offsets
|
||||
********************************************/
|
||||
|
||||
if (do_probe_cal) {
|
||||
|
||||
// Park nozzle
|
||||
do_blocking_move_to(parkpos);
|
||||
|
||||
// Initialize temperatures
|
||||
const celsius_t target_bed = BED_MAX_TARGET;
|
||||
thermalManager.setTargetBed(target_bed);
|
||||
|
||||
celsius_t target_probe = PTC_PROBE_START;
|
||||
|
||||
report_targets(target_bed, target_probe);
|
||||
|
||||
// Wait for heatbed to reach target temp and probe to cool below target temp
|
||||
wait_for_temps(target_bed, target_probe, next_temp_report);
|
||||
|
||||
// Disable leveling so it won't mess with us
|
||||
TERN_(HAS_LEVELING, set_bed_leveling_enabled(false));
|
||||
|
||||
bool timeout = false;
|
||||
for (uint8_t idx = 0; idx <= PTC_PROBE_COUNT; idx++) {
|
||||
// Move probe to probing point and wait for it to reach target temperature
|
||||
do_blocking_move_to(noz_pos_xyz);
|
||||
|
||||
say_waiting_for_probe_heating();
|
||||
SERIAL_ECHOLNPGM(" Bed:", target_bed, " Probe:", target_probe);
|
||||
const millis_t probe_timeout_ms = millis() + SEC_TO_MS(900UL);
|
||||
while (thermalManager.degProbe() < target_probe) {
|
||||
if (report_temps(next_temp_report, probe_timeout_ms)) {
|
||||
SERIAL_ECHOLNPGM("!Probe heating timed out.");
|
||||
timeout = true;
|
||||
break;
|
||||
}
|
||||
}
|
||||
if (timeout) break;
|
||||
|
||||
const float measured_z = g76_probe(TSI_PROBE, target_probe, noz_pos_xyz);
|
||||
if (isnan(measured_z)) break;
|
||||
}
|
||||
|
||||
SERIAL_ECHOLNPGM("Retrieved measurements: ", ptc.get_index());
|
||||
if (ptc.finish_calibration(TSI_PROBE))
|
||||
say_successfully_calibrated();
|
||||
else
|
||||
say_failed_to_calibrate();
|
||||
SERIAL_ECHOLNPGM(" probe.");
|
||||
|
||||
// Cleanup
|
||||
thermalManager.setTargetBed(0);
|
||||
TERN_(HAS_LEVELING, set_bed_leveling_enabled(true));
|
||||
|
||||
SERIAL_ECHOLNPGM("Final compensation values:");
|
||||
ptc.print_offsets();
|
||||
} // do_probe_cal
|
||||
|
||||
restore_feedrate_and_scaling();
|
||||
}
|
||||
|
||||
#endif // PTC_PROBE && PTC_BED
|
||||
|
||||
/**
|
||||
* M871: Report / reset temperature compensation offsets.
|
||||
* Note: This does not affect values in EEPROM until M500.
|
||||
*
|
||||
* M871 [ R | B | P | E ]
|
||||
*
|
||||
* No Parameters - Print current offset values.
|
||||
*
|
||||
* Select only one of these flags:
|
||||
* R - Reset all offsets to zero (i.e., disable compensation).
|
||||
* B - Manually set offset for bed
|
||||
* P - Manually set offset for probe
|
||||
* E - Manually set offset for extruder
|
||||
*
|
||||
* With B, P, or E:
|
||||
* I[index] - Index in the array
|
||||
* V[value] - Adjustment in µm
|
||||
*/
|
||||
void GcodeSuite::M871() {
|
||||
|
||||
if (parser.seen('R')) {
|
||||
// Reset z-probe offsets to factory defaults
|
||||
ptc.clear_all_offsets();
|
||||
SERIAL_ECHOLNPGM("Offsets reset to default.");
|
||||
}
|
||||
else if (parser.seen("BPE")) {
|
||||
if (!parser.seenval('V')) return;
|
||||
const int16_t offset_val = parser.value_int();
|
||||
if (!parser.seenval('I')) return;
|
||||
const int16_t idx = parser.value_int();
|
||||
const TempSensorID mod = TERN_(PTC_BED, parser.seen_test('B') ? TSI_BED :)
|
||||
TERN_(PTC_HOTEND, parser.seen_test('E') ? TSI_EXT :)
|
||||
TERN_(PTC_PROBE, parser.seen_test('P') ? TSI_PROBE :) TSI_COUNT;
|
||||
if (mod == TSI_COUNT)
|
||||
SERIAL_ECHOLNPGM("!Invalid sensor.");
|
||||
else if (idx > 0 && ptc.set_offset(mod, idx - 1, offset_val))
|
||||
SERIAL_ECHOLNPGM("Set value: ", offset_val);
|
||||
else
|
||||
SERIAL_ECHOLNPGM("!Invalid index. Failed to set value (note: value at index 0 is constant).");
|
||||
}
|
||||
else // Print current Z-probe adjustments. Note: Values in EEPROM might differ.
|
||||
ptc.print_offsets();
|
||||
}
|
||||
|
||||
#endif // HAS_PTC
|
@@ -51,7 +51,7 @@
|
||||
* Also, there are two support functions that can be called from a developer's C code.
|
||||
*
|
||||
* uint16_t check_for_free_memory_corruption(PGM_P const free_memory_start);
|
||||
* void M100_dump_routine(PGM_P const title, const char * const start, const uintptr_t size);
|
||||
* void M100_dump_routine(FSTR_P const title, const char * const start, const uintptr_t size);
|
||||
*
|
||||
* Initial version by Roxy-3D
|
||||
*/
|
||||
@@ -182,8 +182,8 @@ inline int32_t count_test_bytes(const char * const start_free_memory) {
|
||||
}
|
||||
}
|
||||
|
||||
void M100_dump_routine(PGM_P const title, const char * const start, const uintptr_t size) {
|
||||
SERIAL_ECHOLNPGM_P(title);
|
||||
void M100_dump_routine(FSTR_P const title, const char * const start, const uintptr_t size) {
|
||||
SERIAL_ECHOLNF(title);
|
||||
//
|
||||
// Round the start and end locations to produce full lines of output
|
||||
//
|
||||
@@ -196,8 +196,8 @@ inline int32_t count_test_bytes(const char * const start_free_memory) {
|
||||
|
||||
#endif // M100_FREE_MEMORY_DUMPER
|
||||
|
||||
inline int check_for_free_memory_corruption(PGM_P const title) {
|
||||
SERIAL_ECHOPGM_P(title);
|
||||
inline int check_for_free_memory_corruption(FSTR_P const title) {
|
||||
SERIAL_ECHOF(title);
|
||||
|
||||
char *start_free_memory = free_memory_start, *end_free_memory = free_memory_end;
|
||||
int n = end_free_memory - start_free_memory;
|
||||
@@ -217,7 +217,7 @@ inline int check_for_free_memory_corruption(PGM_P const title) {
|
||||
// idle();
|
||||
serial_delay(20);
|
||||
#if ENABLED(M100_FREE_MEMORY_DUMPER)
|
||||
M100_dump_routine(PSTR(" Memory corruption detected with end_free_memory<Heap\n"), (const char*)0x1B80, 0x0680);
|
||||
M100_dump_routine(F(" Memory corruption detected with end_free_memory<Heap\n"), (const char*)0x1B80, 0x0680);
|
||||
#endif
|
||||
}
|
||||
|
||||
@@ -281,7 +281,7 @@ inline void free_memory_pool_report(char * const start_free_memory, const int32_
|
||||
"\nMemory Corruption detected in free memory area."
|
||||
"\nLargest free block is ", max_cnt, " bytes at ", hex_address(max_addr)
|
||||
);
|
||||
SERIAL_ECHOLNPGM("check_for_free_memory_corruption() = ", check_for_free_memory_corruption(PSTR("M100 F ")));
|
||||
SERIAL_ECHOLNPGM("check_for_free_memory_corruption() = ", check_for_free_memory_corruption(F("M100 F ")));
|
||||
}
|
||||
|
||||
#if ENABLED(M100_FREE_MEMORY_CORRUPTOR)
|
||||
|
@@ -47,23 +47,17 @@ void GcodeSuite::M425() {
|
||||
bool noArgs = true;
|
||||
|
||||
auto axis_can_calibrate = [](const uint8_t a) {
|
||||
#define _CAN_CASE(N) case N##_AXIS: return AXIS_CAN_CALIBRATE(N);
|
||||
switch (a) {
|
||||
default: return false;
|
||||
LINEAR_AXIS_CODE(
|
||||
case X_AXIS: return AXIS_CAN_CALIBRATE(X),
|
||||
case Y_AXIS: return AXIS_CAN_CALIBRATE(Y),
|
||||
case Z_AXIS: return AXIS_CAN_CALIBRATE(Z),
|
||||
case I_AXIS: return AXIS_CAN_CALIBRATE(I),
|
||||
case J_AXIS: return AXIS_CAN_CALIBRATE(J),
|
||||
case K_AXIS: return AXIS_CAN_CALIBRATE(K),
|
||||
);
|
||||
MAIN_AXIS_MAP(_CAN_CASE)
|
||||
}
|
||||
};
|
||||
|
||||
LOOP_LINEAR_AXES(a) {
|
||||
LOOP_NUM_AXES(a) {
|
||||
if (axis_can_calibrate(a) && parser.seen(AXIS_CHAR(a))) {
|
||||
planner.synchronize();
|
||||
backlash.distance_mm[a] = parser.has_value() ? parser.value_linear_units() : backlash.get_measurement(AxisEnum(a));
|
||||
backlash.set_distance_mm((AxisEnum)a, parser.has_value() ? parser.value_axis_units((AxisEnum)a) : backlash.get_measurement((AxisEnum)a));
|
||||
noArgs = false;
|
||||
}
|
||||
}
|
||||
@@ -77,33 +71,30 @@ void GcodeSuite::M425() {
|
||||
#ifdef BACKLASH_SMOOTHING_MM
|
||||
if (parser.seen('S')) {
|
||||
planner.synchronize();
|
||||
backlash.smoothing_mm = parser.value_linear_units();
|
||||
backlash.set_smoothing_mm(parser.value_linear_units());
|
||||
noArgs = false;
|
||||
}
|
||||
#endif
|
||||
|
||||
if (noArgs) {
|
||||
SERIAL_ECHOPGM("Backlash Correction ");
|
||||
if (!backlash.correction) SERIAL_ECHOPGM("in");
|
||||
if (!backlash.get_correction_uint8()) SERIAL_ECHOPGM("in");
|
||||
SERIAL_ECHOLNPGM("active:");
|
||||
SERIAL_ECHOLNPGM(" Correction Amount/Fade-out: F", backlash.get_correction(), " (F1.0 = full, F0.0 = none)");
|
||||
SERIAL_ECHOPGM(" Backlash Distance (mm): ");
|
||||
LOOP_LINEAR_AXES(a) if (axis_can_calibrate(a)) {
|
||||
SERIAL_CHAR(' ', AXIS_CHAR(a));
|
||||
SERIAL_ECHO(backlash.distance_mm[a]);
|
||||
SERIAL_EOL();
|
||||
LOOP_NUM_AXES(a) if (axis_can_calibrate(a)) {
|
||||
SERIAL_ECHOLNPGM_P((PGM_P)pgm_read_ptr(&SP_AXIS_STR[a]), backlash.get_distance_mm((AxisEnum)a));
|
||||
}
|
||||
|
||||
#ifdef BACKLASH_SMOOTHING_MM
|
||||
SERIAL_ECHOLNPGM(" Smoothing (mm): S", backlash.smoothing_mm);
|
||||
SERIAL_ECHOLNPGM(" Smoothing (mm): S", backlash.get_smoothing_mm());
|
||||
#endif
|
||||
|
||||
#if ENABLED(MEASURE_BACKLASH_WHEN_PROBING)
|
||||
SERIAL_ECHOPGM(" Average measured backlash (mm):");
|
||||
if (backlash.has_any_measurement()) {
|
||||
LOOP_LINEAR_AXES(a) if (axis_can_calibrate(a) && backlash.has_measurement(AxisEnum(a))) {
|
||||
SERIAL_CHAR(' ', AXIS_CHAR(a));
|
||||
SERIAL_ECHO(backlash.get_measurement(AxisEnum(a)));
|
||||
LOOP_NUM_AXES(a) if (axis_can_calibrate(a) && backlash.has_measurement(AxisEnum(a))) {
|
||||
SERIAL_ECHOPGM_P((PGM_P)pgm_read_ptr(&SP_AXIS_STR[a]), backlash.get_measurement((AxisEnum)a));
|
||||
}
|
||||
}
|
||||
else
|
||||
@@ -114,19 +105,22 @@ void GcodeSuite::M425() {
|
||||
}
|
||||
|
||||
void GcodeSuite::M425_report(const bool forReplay/*=true*/) {
|
||||
report_heading_etc(forReplay, PSTR(STR_BACKLASH_COMPENSATION));
|
||||
report_heading_etc(forReplay, F(STR_BACKLASH_COMPENSATION));
|
||||
SERIAL_ECHOLNPGM_P(
|
||||
PSTR(" M425 F"), backlash.get_correction()
|
||||
#ifdef BACKLASH_SMOOTHING_MM
|
||||
, PSTR(" S"), LINEAR_UNIT(backlash.smoothing_mm)
|
||||
, PSTR(" S"), LINEAR_UNIT(backlash.get_smoothing_mm())
|
||||
#endif
|
||||
, LIST_N(DOUBLE(LINEAR_AXES),
|
||||
SP_X_STR, LINEAR_UNIT(backlash.distance_mm.x),
|
||||
SP_Y_STR, LINEAR_UNIT(backlash.distance_mm.y),
|
||||
SP_Z_STR, LINEAR_UNIT(backlash.distance_mm.z),
|
||||
SP_I_STR, LINEAR_UNIT(backlash.distance_mm.i),
|
||||
SP_J_STR, LINEAR_UNIT(backlash.distance_mm.j),
|
||||
SP_K_STR, LINEAR_UNIT(backlash.distance_mm.k)
|
||||
, LIST_N(DOUBLE(NUM_AXES),
|
||||
SP_X_STR, LINEAR_UNIT(backlash.get_distance_mm(X_AXIS)),
|
||||
SP_Y_STR, LINEAR_UNIT(backlash.get_distance_mm(Y_AXIS)),
|
||||
SP_Z_STR, LINEAR_UNIT(backlash.get_distance_mm(Z_AXIS)),
|
||||
SP_I_STR, I_AXIS_UNIT(backlash.get_distance_mm(I_AXIS)),
|
||||
SP_J_STR, J_AXIS_UNIT(backlash.get_distance_mm(J_AXIS)),
|
||||
SP_K_STR, K_AXIS_UNIT(backlash.get_distance_mm(K_AXIS)),
|
||||
SP_U_STR, U_AXIS_UNIT(backlash.get_distance_mm(U_AXIS)),
|
||||
SP_V_STR, V_AXIS_UNIT(backlash.get_distance_mm(V_AXIS)),
|
||||
SP_W_STR, W_AXIS_UNIT(backlash.get_distance_mm(W_AXIS))
|
||||
)
|
||||
);
|
||||
}
|
||||
|
@@ -35,11 +35,15 @@
|
||||
#include "../../module/planner.h"
|
||||
#endif
|
||||
|
||||
#if HAS_PTC
|
||||
#include "../../feature/probe_temp_comp.h"
|
||||
#endif
|
||||
|
||||
/**
|
||||
* M48: Z probe repeatability measurement function.
|
||||
*
|
||||
* Usage:
|
||||
* M48 <P#> <X#> <Y#> <V#> <E> <L#> <S>
|
||||
* M48 <P#> <X#> <Y#> <V#> <E> <L#> <S> <C#>
|
||||
* P = Number of sampled points (4-50, default 10)
|
||||
* X = Sample X position
|
||||
* Y = Sample Y position
|
||||
@@ -47,6 +51,7 @@
|
||||
* E = Engage Z probe for each reading
|
||||
* L = Number of legs of movement before probe
|
||||
* S = Schizoid (Or Star if you prefer)
|
||||
* C = Enable probe temperature compensation (0 or 1, default 1)
|
||||
*
|
||||
* This function requires the machine to be homed before invocation.
|
||||
*/
|
||||
@@ -79,7 +84,7 @@ void GcodeSuite::M48() {
|
||||
};
|
||||
|
||||
if (!probe.can_reach(test_position)) {
|
||||
ui.set_status_P(GET_TEXT(MSG_M48_OUT_OF_BOUNDS), 99);
|
||||
ui.set_status(GET_TEXT_F(MSG_M48_OUT_OF_BOUNDS), 99);
|
||||
SERIAL_ECHOLNPGM("? (X,Y) out of bounds.");
|
||||
return;
|
||||
}
|
||||
@@ -107,6 +112,8 @@ void GcodeSuite::M48() {
|
||||
set_bed_leveling_enabled(false);
|
||||
#endif
|
||||
|
||||
TERN_(HAS_PTC, ptc.set_enabled(!parser.seen('C') || parser.value_bool()));
|
||||
|
||||
// Work with reasonable feedrates
|
||||
remember_feedrate_scaling_off();
|
||||
|
||||
@@ -144,7 +151,7 @@ void GcodeSuite::M48() {
|
||||
LOOP_L_N(n, n_samples) {
|
||||
#if HAS_STATUS_MESSAGE
|
||||
// Display M48 progress in the status bar
|
||||
ui.status_printf_P(0, PSTR(S_FMT ": %d/%d"), GET_TEXT(MSG_M48_POINT), int(n + 1), int(n_samples));
|
||||
ui.status_printf(0, F(S_FMT ": %d/%d"), GET_TEXT(MSG_M48_POINT), int(n + 1), int(n_samples));
|
||||
#endif
|
||||
|
||||
// When there are "legs" of movement move around the point before probing
|
||||
@@ -260,7 +267,7 @@ void GcodeSuite::M48() {
|
||||
#if HAS_STATUS_MESSAGE
|
||||
// Display M48 results in the status bar
|
||||
char sigma_str[8];
|
||||
ui.status_printf_P(0, PSTR(S_FMT ": %s"), GET_TEXT(MSG_M48_DEVIATION), dtostrf(sigma, 2, 6, sigma_str));
|
||||
ui.status_printf(0, F(S_FMT ": %s"), GET_TEXT(MSG_M48_DEVIATION), dtostrf(sigma, 2, 6, sigma_str));
|
||||
#endif
|
||||
}
|
||||
|
||||
@@ -269,6 +276,9 @@ void GcodeSuite::M48() {
|
||||
// Re-enable bed level correction if it had been on
|
||||
TERN_(HAS_LEVELING, set_bed_leveling_enabled(was_enabled));
|
||||
|
||||
// Re-enable probe temperature correction
|
||||
TERN_(HAS_PTC, ptc.set_enabled(true));
|
||||
|
||||
report_current_position();
|
||||
}
|
||||
|
||||
|
@@ -62,7 +62,7 @@
|
||||
}
|
||||
|
||||
void GcodeSuite::M665_report(const bool forReplay/*=true*/) {
|
||||
report_heading_etc(forReplay, PSTR(STR_DELTA_SETTINGS));
|
||||
report_heading_etc(forReplay, F(STR_DELTA_SETTINGS));
|
||||
SERIAL_ECHOLNPGM_P(
|
||||
PSTR(" M665 L"), LINEAR_UNIT(delta_diagonal_rod)
|
||||
, PSTR(" R"), LINEAR_UNIT(delta_radius)
|
||||
@@ -86,13 +86,13 @@
|
||||
*
|
||||
* Parameters:
|
||||
*
|
||||
* S[segments-per-second] - Segments-per-second
|
||||
* S[segments] - Segments-per-second
|
||||
*
|
||||
* Without NO_WORKSPACE_OFFSETS:
|
||||
*
|
||||
* P[theta-psi-offset] - Theta-Psi offset, added to the shoulder (A/X) angle
|
||||
* T[theta-offset] - Theta offset, added to the elbow (B/Y) angle
|
||||
* Z[z-offset] - Z offset, added to Z
|
||||
* P[theta-psi-offset] - Theta-Psi offset, added to the shoulder (A/X) angle
|
||||
* T[theta-offset] - Theta offset, added to the elbow (B/Y) angle
|
||||
* Z[z-offset] - Z offset, added to Z
|
||||
*
|
||||
* A, P, and X are all aliases for the shoulder angle
|
||||
* B, T, and Y are all aliases for the elbow angle
|
||||
@@ -132,7 +132,7 @@
|
||||
}
|
||||
|
||||
void GcodeSuite::M665_report(const bool forReplay/*=true*/) {
|
||||
report_heading_etc(forReplay, PSTR(STR_SCARA_SETTINGS " (" STR_S_SEG_PER_SEC TERN_(HAS_SCARA_OFFSET, " " STR_SCARA_P_T_Z) ")"));
|
||||
report_heading_etc(forReplay, F(STR_SCARA_SETTINGS " (" STR_S_SEG_PER_SEC TERN_(HAS_SCARA_OFFSET, " " STR_SCARA_P_T_Z) ")"));
|
||||
SERIAL_ECHOLNPGM_P(
|
||||
PSTR(" M665 S"), segments_per_second
|
||||
#if HAS_SCARA_OFFSET
|
||||
@@ -152,18 +152,35 @@
|
||||
*
|
||||
* Parameters:
|
||||
*
|
||||
* S[segments-per-second] - Segments-per-second
|
||||
* S[segments] - Segments-per-second
|
||||
* L[left] - Work area minimum X
|
||||
* R[right] - Work area maximum X
|
||||
* T[top] - Work area maximum Y
|
||||
* B[bottom] - Work area minimum Y
|
||||
* H[length] - Maximum belt length
|
||||
*/
|
||||
void GcodeSuite::M665() {
|
||||
if (parser.seenval('S'))
|
||||
segments_per_second = parser.value_float();
|
||||
else
|
||||
M665_report();
|
||||
if (!parser.seen_any()) return M665_report();
|
||||
if (parser.seenval('S')) segments_per_second = parser.value_float();
|
||||
if (parser.seenval('L')) draw_area_min.x = parser.value_linear_units();
|
||||
if (parser.seenval('R')) draw_area_max.x = parser.value_linear_units();
|
||||
if (parser.seenval('T')) draw_area_max.y = parser.value_linear_units();
|
||||
if (parser.seenval('B')) draw_area_min.y = parser.value_linear_units();
|
||||
if (parser.seenval('H')) polargraph_max_belt_len = parser.value_linear_units();
|
||||
draw_area_size.x = draw_area_max.x - draw_area_min.x;
|
||||
draw_area_size.y = draw_area_max.y - draw_area_min.y;
|
||||
}
|
||||
|
||||
void GcodeSuite::M665_report(const bool forReplay/*=true*/) {
|
||||
report_heading_etc(forReplay, PSTR(STR_POLARGRAPH_SETTINGS " (" STR_S_SEG_PER_SEC ")"));
|
||||
SERIAL_ECHOLNPGM(" M665 S", segments_per_second);
|
||||
report_heading_etc(forReplay, F(STR_POLARGRAPH_SETTINGS));
|
||||
SERIAL_ECHOLNPGM_P(
|
||||
PSTR(" M665 S"), LINEAR_UNIT(segments_per_second),
|
||||
PSTR(" L"), LINEAR_UNIT(draw_area_min.x),
|
||||
PSTR(" R"), LINEAR_UNIT(draw_area_max.x),
|
||||
SP_T_STR, LINEAR_UNIT(draw_area_max.y),
|
||||
SP_B_STR, LINEAR_UNIT(draw_area_min.y),
|
||||
PSTR(" H"), LINEAR_UNIT(polargraph_max_belt_len)
|
||||
);
|
||||
}
|
||||
|
||||
#endif
|
||||
|
@@ -44,8 +44,8 @@
|
||||
void GcodeSuite::M666() {
|
||||
DEBUG_SECTION(log_M666, "M666", DEBUGGING(LEVELING));
|
||||
bool is_err = false, is_set = false;
|
||||
LOOP_LINEAR_AXES(i) {
|
||||
if (parser.seen(AXIS_CHAR(i))) {
|
||||
LOOP_NUM_AXES(i) {
|
||||
if (parser.seenval(AXIS_CHAR(i))) {
|
||||
is_set = true;
|
||||
const float v = parser.value_linear_units();
|
||||
if (v > 0)
|
||||
@@ -61,7 +61,7 @@
|
||||
}
|
||||
|
||||
void GcodeSuite::M666_report(const bool forReplay/*=true*/) {
|
||||
report_heading_etc(forReplay, PSTR(STR_ENDSTOP_ADJUSTMENT));
|
||||
report_heading_etc(forReplay, F(STR_ENDSTOP_ADJUSTMENT));
|
||||
SERIAL_ECHOLNPGM_P(
|
||||
PSTR(" M666 X"), LINEAR_UNIT(delta_endstop_adj.a)
|
||||
, SP_Y_STR, LINEAR_UNIT(delta_endstop_adj.b)
|
||||
@@ -93,19 +93,19 @@
|
||||
#if ENABLED(Z_MULTI_ENDSTOPS)
|
||||
if (parser.seenval('Z')) {
|
||||
const float z_adj = parser.value_linear_units();
|
||||
#if NUM_Z_STEPPER_DRIVERS == 2
|
||||
#if NUM_Z_STEPPERS == 2
|
||||
endstops.z2_endstop_adj = z_adj;
|
||||
#else
|
||||
const int ind = parser.intval('S');
|
||||
#define _SET_ZADJ(N) if (!ind || ind == N) endstops.z##N##_endstop_adj = z_adj;
|
||||
REPEAT_S(2, INCREMENT(NUM_Z_STEPPER_DRIVERS), _SET_ZADJ)
|
||||
REPEAT_S(2, INCREMENT(NUM_Z_STEPPERS), _SET_ZADJ)
|
||||
#endif
|
||||
}
|
||||
#endif
|
||||
}
|
||||
|
||||
void GcodeSuite::M666_report(const bool forReplay/*=true*/) {
|
||||
report_heading_etc(forReplay, PSTR(STR_ENDSTOP_ADJUSTMENT));
|
||||
report_heading_etc(forReplay, F(STR_ENDSTOP_ADJUSTMENT));
|
||||
SERIAL_ECHOPGM(" M666");
|
||||
#if ENABLED(X_DUAL_ENDSTOPS)
|
||||
SERIAL_ECHOLNPGM_P(SP_X_STR, LINEAR_UNIT(endstops.x2_endstop_adj));
|
||||
@@ -114,11 +114,11 @@
|
||||
SERIAL_ECHOLNPGM_P(SP_Y_STR, LINEAR_UNIT(endstops.y2_endstop_adj));
|
||||
#endif
|
||||
#if ENABLED(Z_MULTI_ENDSTOPS)
|
||||
#if NUM_Z_STEPPER_DRIVERS >= 3
|
||||
#if NUM_Z_STEPPERS >= 3
|
||||
SERIAL_ECHOPGM(" S2 Z", LINEAR_UNIT(endstops.z3_endstop_adj));
|
||||
report_echo_start(forReplay);
|
||||
SERIAL_ECHOPGM(" M666 S3 Z", LINEAR_UNIT(endstops.z3_endstop_adj));
|
||||
#if NUM_Z_STEPPER_DRIVERS >= 4
|
||||
#if NUM_Z_STEPPERS >= 4
|
||||
report_echo_start(forReplay);
|
||||
SERIAL_ECHOPGM(" M666 S4 Z", LINEAR_UNIT(endstops.z4_endstop_adj));
|
||||
#endif
|
||||
|
@@ -92,8 +92,8 @@ void GcodeSuite::M852() {
|
||||
}
|
||||
|
||||
void GcodeSuite::M852_report(const bool forReplay/*=true*/) {
|
||||
report_heading_etc(forReplay, PSTR(STR_SKEW_FACTOR));
|
||||
SERIAL_ECHOPAIR_F(" M851 I", planner.skew_factor.xy, 6);
|
||||
report_heading_etc(forReplay, F(STR_SKEW_FACTOR));
|
||||
SERIAL_ECHOPAIR_F(" M852 I", planner.skew_factor.xy, 6);
|
||||
#if ENABLED(SKEW_CORRECTION_FOR_Z)
|
||||
SERIAL_ECHOPAIR_F(" J", planner.skew_factor.xz, 6);
|
||||
SERIAL_ECHOPAIR_F(" K", planner.skew_factor.yz, 6);
|
||||
|
@@ -76,7 +76,7 @@
|
||||
|
||||
void GcodeSuite::M200_report(const bool forReplay/*=true*/) {
|
||||
if (!forReplay) {
|
||||
report_heading(forReplay, PSTR(STR_FILAMENT_SETTINGS), false);
|
||||
report_heading(forReplay, F(STR_FILAMENT_SETTINGS), false);
|
||||
if (!parser.volumetric_enabled) SERIAL_ECHOPGM(" (Disabled):");
|
||||
SERIAL_EOL();
|
||||
report_echo_start(forReplay);
|
||||
@@ -93,12 +93,12 @@
|
||||
}
|
||||
#else
|
||||
SERIAL_ECHOLNPGM(" M200 S", parser.volumetric_enabled);
|
||||
LOOP_L_N(i, EXTRUDERS) {
|
||||
EXTRUDER_LOOP() {
|
||||
report_echo_start(forReplay);
|
||||
SERIAL_ECHOLNPGM(
|
||||
" M200 T", i, " D", LINEAR_UNIT(planner.filament_size[i])
|
||||
" M200 T", e, " D", LINEAR_UNIT(planner.filament_size[e])
|
||||
#if ENABLED(VOLUMETRIC_EXTRUDER_LIMIT)
|
||||
, " L", LINEAR_UNIT(planner.volumetric_extruder_limit[i])
|
||||
, " L", LINEAR_UNIT(planner.volumetric_extruder_limit[e])
|
||||
#endif
|
||||
);
|
||||
}
|
||||
@@ -108,12 +108,21 @@
|
||||
#endif // !NO_VOLUMETRICS
|
||||
|
||||
/**
|
||||
* M201: Set max acceleration in units/s^2 for print moves (M201 X1000 Y1000)
|
||||
* M201: Set max acceleration in units/s^2 for print moves.
|
||||
*
|
||||
* With multiple extruders use T to specify which one.
|
||||
* X<accel> : Max Acceleration for X
|
||||
* Y<accel> : Max Acceleration for Y
|
||||
* Z<accel> : Max Acceleration for Z
|
||||
* ... : etc
|
||||
* E<accel> : Max Acceleration for Extruder
|
||||
* T<index> : Extruder index to set
|
||||
*
|
||||
* With XY_FREQUENCY_LIMIT:
|
||||
* F<Hz> : Frequency limit for XY...IJKUVW
|
||||
* S<percent> : Speed factor percentage.
|
||||
*/
|
||||
void GcodeSuite::M201() {
|
||||
if (!parser.seen("T" LOGICAL_AXES_STRING))
|
||||
if (!parser.seen("T" STR_AXES_LOGICAL TERN_(XY_FREQUENCY_LIMIT, "FS")))
|
||||
return M201_report();
|
||||
|
||||
const int8_t target_extruder = get_target_extruder_from_command();
|
||||
@@ -121,27 +130,30 @@ void GcodeSuite::M201() {
|
||||
|
||||
#ifdef XY_FREQUENCY_LIMIT
|
||||
if (parser.seenval('F')) planner.set_frequency_limit(parser.value_byte());
|
||||
if (parser.seenval('G')) planner.xy_freq_min_speed_factor = constrain(parser.value_float(), 1, 100) / 100;
|
||||
if (parser.seenval('S')) planner.xy_freq_min_speed_factor = constrain(parser.value_float(), 1, 100) / 100;
|
||||
#endif
|
||||
|
||||
LOOP_LOGICAL_AXES(i) {
|
||||
if (parser.seenval(axis_codes[i])) {
|
||||
const uint8_t a = TERN(HAS_EXTRUDERS, (i == E_AXIS ? uint8_t(E_AXIS_N(target_extruder)) : i), i);
|
||||
planner.set_max_acceleration(a, parser.value_axis_units((AxisEnum)a));
|
||||
if (parser.seenval(AXIS_CHAR(i))) {
|
||||
const AxisEnum a = TERN(HAS_EXTRUDERS, (i == E_AXIS ? E_AXIS_N(target_extruder) : (AxisEnum)i), (AxisEnum)i);
|
||||
planner.set_max_acceleration(a, parser.value_axis_units(a));
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
void GcodeSuite::M201_report(const bool forReplay/*=true*/) {
|
||||
report_heading_etc(forReplay, PSTR(STR_MAX_ACCELERATION));
|
||||
report_heading_etc(forReplay, F(STR_MAX_ACCELERATION));
|
||||
SERIAL_ECHOLNPGM_P(
|
||||
LIST_N(DOUBLE(LINEAR_AXES),
|
||||
LIST_N(DOUBLE(NUM_AXES),
|
||||
PSTR(" M201 X"), LINEAR_UNIT(planner.settings.max_acceleration_mm_per_s2[X_AXIS]),
|
||||
SP_Y_STR, LINEAR_UNIT(planner.settings.max_acceleration_mm_per_s2[Y_AXIS]),
|
||||
SP_Z_STR, LINEAR_UNIT(planner.settings.max_acceleration_mm_per_s2[Z_AXIS]),
|
||||
SP_I_STR, LINEAR_UNIT(planner.settings.max_acceleration_mm_per_s2[I_AXIS]),
|
||||
SP_J_STR, LINEAR_UNIT(planner.settings.max_acceleration_mm_per_s2[J_AXIS]),
|
||||
SP_K_STR, LINEAR_UNIT(planner.settings.max_acceleration_mm_per_s2[K_AXIS])
|
||||
SP_I_STR, I_AXIS_UNIT(planner.settings.max_acceleration_mm_per_s2[I_AXIS]),
|
||||
SP_J_STR, J_AXIS_UNIT(planner.settings.max_acceleration_mm_per_s2[J_AXIS]),
|
||||
SP_K_STR, K_AXIS_UNIT(planner.settings.max_acceleration_mm_per_s2[K_AXIS]),
|
||||
SP_U_STR, U_AXIS_UNIT(planner.settings.max_acceleration_mm_per_s2[U_AXIS]),
|
||||
SP_V_STR, V_AXIS_UNIT(planner.settings.max_acceleration_mm_per_s2[V_AXIS]),
|
||||
SP_W_STR, W_AXIS_UNIT(planner.settings.max_acceleration_mm_per_s2[W_AXIS])
|
||||
)
|
||||
#if HAS_EXTRUDERS && DISABLED(DISTINCT_E_FACTORS)
|
||||
, SP_E_STR, VOLUMETRIC_UNIT(planner.settings.max_acceleration_mm_per_s2[E_AXIS])
|
||||
@@ -164,29 +176,32 @@ void GcodeSuite::M201_report(const bool forReplay/*=true*/) {
|
||||
* With multiple extruders use T to specify which one.
|
||||
*/
|
||||
void GcodeSuite::M203() {
|
||||
if (!parser.seen("T" LOGICAL_AXES_STRING))
|
||||
if (!parser.seen("T" STR_AXES_LOGICAL))
|
||||
return M203_report();
|
||||
|
||||
const int8_t target_extruder = get_target_extruder_from_command();
|
||||
if (target_extruder < 0) return;
|
||||
|
||||
LOOP_LOGICAL_AXES(i)
|
||||
if (parser.seenval(axis_codes[i])) {
|
||||
const uint8_t a = TERN(HAS_EXTRUDERS, (i == E_AXIS ? uint8_t(E_AXIS_N(target_extruder)) : i), i);
|
||||
planner.set_max_feedrate(a, parser.value_axis_units((AxisEnum)a));
|
||||
if (parser.seenval(AXIS_CHAR(i))) {
|
||||
const AxisEnum a = TERN(HAS_EXTRUDERS, (i == E_AXIS ? E_AXIS_N(target_extruder) : (AxisEnum)i), (AxisEnum)i);
|
||||
planner.set_max_feedrate(a, parser.value_axis_units(a));
|
||||
}
|
||||
}
|
||||
|
||||
void GcodeSuite::M203_report(const bool forReplay/*=true*/) {
|
||||
report_heading_etc(forReplay, PSTR(STR_MAX_FEEDRATES));
|
||||
report_heading_etc(forReplay, F(STR_MAX_FEEDRATES));
|
||||
SERIAL_ECHOLNPGM_P(
|
||||
LIST_N(DOUBLE(LINEAR_AXES),
|
||||
LIST_N(DOUBLE(NUM_AXES),
|
||||
PSTR(" M203 X"), LINEAR_UNIT(planner.settings.max_feedrate_mm_s[X_AXIS]),
|
||||
SP_Y_STR, LINEAR_UNIT(planner.settings.max_feedrate_mm_s[Y_AXIS]),
|
||||
SP_Z_STR, LINEAR_UNIT(planner.settings.max_feedrate_mm_s[Z_AXIS]),
|
||||
SP_I_STR, LINEAR_UNIT(planner.settings.max_feedrate_mm_s[I_AXIS]),
|
||||
SP_J_STR, LINEAR_UNIT(planner.settings.max_feedrate_mm_s[J_AXIS]),
|
||||
SP_K_STR, LINEAR_UNIT(planner.settings.max_feedrate_mm_s[K_AXIS])
|
||||
SP_K_STR, LINEAR_UNIT(planner.settings.max_feedrate_mm_s[K_AXIS]),
|
||||
SP_U_STR, LINEAR_UNIT(planner.settings.max_feedrate_mm_s[U_AXIS]),
|
||||
SP_V_STR, LINEAR_UNIT(planner.settings.max_feedrate_mm_s[V_AXIS]),
|
||||
SP_W_STR, LINEAR_UNIT(planner.settings.max_feedrate_mm_s[W_AXIS])
|
||||
)
|
||||
#if HAS_EXTRUDERS && DISABLED(DISTINCT_E_FACTORS)
|
||||
, SP_E_STR, VOLUMETRIC_UNIT(planner.settings.max_feedrate_mm_s[E_AXIS])
|
||||
@@ -194,7 +209,7 @@ void GcodeSuite::M203_report(const bool forReplay/*=true*/) {
|
||||
);
|
||||
#if ENABLED(DISTINCT_E_FACTORS)
|
||||
LOOP_L_N(i, E_STEPPERS) {
|
||||
SERIAL_ECHO_START();
|
||||
if (!forReplay) SERIAL_ECHO_START();
|
||||
SERIAL_ECHOLNPGM_P(
|
||||
PSTR(" M203 T"), i
|
||||
, SP_E_STR, VOLUMETRIC_UNIT(planner.settings.max_feedrate_mm_s[E_AXIS_N(i)])
|
||||
@@ -224,7 +239,7 @@ void GcodeSuite::M204() {
|
||||
}
|
||||
|
||||
void GcodeSuite::M204_report(const bool forReplay/*=true*/) {
|
||||
report_heading_etc(forReplay, PSTR(STR_ACCELERATION_P_R_T));
|
||||
report_heading_etc(forReplay, F(STR_ACCELERATION_P_R_T));
|
||||
SERIAL_ECHOLNPGM_P(
|
||||
PSTR(" M204 P"), LINEAR_UNIT(planner.settings.acceleration)
|
||||
, PSTR(" R"), LINEAR_UNIT(planner.settings.retract_acceleration)
|
||||
@@ -253,7 +268,7 @@ void GcodeSuite::M205() {
|
||||
if (parser.seenval('S')) planner.settings.min_feedrate_mm_s = parser.value_linear_units();
|
||||
if (parser.seenval('T')) planner.settings.min_travel_feedrate_mm_s = parser.value_linear_units();
|
||||
#if HAS_JUNCTION_DEVIATION
|
||||
#if HAS_CLASSIC_JERK && (AXIS4_NAME == 'J' || AXIS5_NAME == 'J' || AXIS6_NAME == 'J')
|
||||
#if HAS_CLASSIC_JERK && AXIS_COLLISION('J')
|
||||
#error "Can't set_max_jerk for 'J' axis because 'J' is used for Junction Deviation."
|
||||
#endif
|
||||
if (parser.seenval('J')) {
|
||||
@@ -273,9 +288,12 @@ void GcodeSuite::M205() {
|
||||
if (parser.seenval('X')) planner.set_max_jerk(X_AXIS, parser.value_linear_units()),
|
||||
if (parser.seenval('Y')) planner.set_max_jerk(Y_AXIS, parser.value_linear_units()),
|
||||
if ((seenZ = parser.seenval('Z'))) planner.set_max_jerk(Z_AXIS, parser.value_linear_units()),
|
||||
if (parser.seenval(AXIS4_NAME)) planner.set_max_jerk(I_AXIS, parser.value_linear_units()),
|
||||
if (parser.seenval(AXIS5_NAME)) planner.set_max_jerk(J_AXIS, parser.value_linear_units()),
|
||||
if (parser.seenval(AXIS6_NAME)) planner.set_max_jerk(K_AXIS, parser.value_linear_units())
|
||||
if (parser.seenval(AXIS4_NAME)) planner.set_max_jerk(I_AXIS, parser.TERN(AXIS4_ROTATES, value_float, value_linear_units)()),
|
||||
if (parser.seenval(AXIS5_NAME)) planner.set_max_jerk(J_AXIS, parser.TERN(AXIS5_ROTATES, value_float, value_linear_units)()),
|
||||
if (parser.seenval(AXIS6_NAME)) planner.set_max_jerk(K_AXIS, parser.TERN(AXIS6_ROTATES, value_float, value_linear_units)()),
|
||||
if (parser.seenval(AXIS7_NAME)) planner.set_max_jerk(U_AXIS, parser.TERN(AXIS7_ROTATES, value_float, value_linear_units)()),
|
||||
if (parser.seenval(AXIS8_NAME)) planner.set_max_jerk(V_AXIS, parser.TERN(AXIS8_ROTATES, value_float, value_linear_units)()),
|
||||
if (parser.seenval(AXIS9_NAME)) planner.set_max_jerk(W_AXIS, parser.TERN(AXIS9_ROTATES, value_float, value_linear_units)())
|
||||
);
|
||||
#if HAS_MESH && DISABLED(LIMITED_JERK_EDITING)
|
||||
if (seenZ && planner.max_jerk.z <= 0.1f)
|
||||
@@ -285,11 +303,17 @@ void GcodeSuite::M205() {
|
||||
}
|
||||
|
||||
void GcodeSuite::M205_report(const bool forReplay/*=true*/) {
|
||||
report_heading_etc(forReplay, PSTR(
|
||||
report_heading_etc(forReplay, F(
|
||||
"Advanced (B<min_segment_time_us> S<min_feedrate> T<min_travel_feedrate>"
|
||||
TERN_(HAS_JUNCTION_DEVIATION, " J<junc_dev>")
|
||||
TERN_(HAS_CLASSIC_JERK, " X<max_x_jerk> Y<max_y_jerk> Z<max_z_jerk>")
|
||||
TERN_(HAS_CLASSIC_E_JERK, " E<max_e_jerk>")
|
||||
#if HAS_CLASSIC_JERK
|
||||
NUM_AXIS_GANG(
|
||||
" X<max_jerk>", " Y<max_jerk>", " Z<max_jerk>",
|
||||
" " STR_I "<max_jerk>", " " STR_J "<max_jerk>", " " STR_K "<max_jerk>",
|
||||
" " STR_U "<max_jerk>", " " STR_V "<max_jerk>", " " STR_W "<max_jerk>"
|
||||
)
|
||||
#endif
|
||||
TERN_(HAS_CLASSIC_E_JERK, " E<max_jerk>")
|
||||
")"
|
||||
));
|
||||
SERIAL_ECHOLNPGM_P(
|
||||
@@ -300,13 +324,16 @@ void GcodeSuite::M205_report(const bool forReplay/*=true*/) {
|
||||
, PSTR(" J"), LINEAR_UNIT(planner.junction_deviation_mm)
|
||||
#endif
|
||||
#if HAS_CLASSIC_JERK
|
||||
, LIST_N(DOUBLE(LINEAR_AXES),
|
||||
, LIST_N(DOUBLE(NUM_AXES),
|
||||
SP_X_STR, LINEAR_UNIT(planner.max_jerk.x),
|
||||
SP_Y_STR, LINEAR_UNIT(planner.max_jerk.y),
|
||||
SP_Z_STR, LINEAR_UNIT(planner.max_jerk.z),
|
||||
SP_I_STR, LINEAR_UNIT(planner.max_jerk.i),
|
||||
SP_J_STR, LINEAR_UNIT(planner.max_jerk.j),
|
||||
SP_K_STR, LINEAR_UNIT(planner.max_jerk.k)
|
||||
SP_I_STR, I_AXIS_UNIT(planner.max_jerk.i),
|
||||
SP_J_STR, J_AXIS_UNIT(planner.max_jerk.j),
|
||||
SP_K_STR, K_AXIS_UNIT(planner.max_jerk.k),
|
||||
SP_U_STR, U_AXIS_UNIT(planner.max_jerk.u),
|
||||
SP_V_STR, V_AXIS_UNIT(planner.max_jerk.v),
|
||||
SP_W_STR, W_AXIS_UNIT(planner.max_jerk.w)
|
||||
)
|
||||
#if HAS_CLASSIC_E_JERK
|
||||
, SP_E_STR, LINEAR_UNIT(planner.max_jerk.e)
|
||||
|
@@ -34,25 +34,31 @@
|
||||
#include "../../MarlinCore.h" // for SP_X_STR, etc.
|
||||
|
||||
/**
|
||||
* M217 - Set SINGLENOZZLE toolchange parameters
|
||||
* M217 - Set toolchange parameters
|
||||
*
|
||||
* // Tool change command
|
||||
* Q Prime active tool and exit
|
||||
*
|
||||
* // Tool change settings
|
||||
* S[linear] Swap length
|
||||
* B[linear] Extra Swap length
|
||||
* E[linear] Prime length
|
||||
* P[linear/m] Prime speed
|
||||
* R[linear/m] Retract speed
|
||||
* U[linear/m] UnRetract speed
|
||||
* V[linear] 0/1 Enable auto prime first extruder used
|
||||
* W[linear] 0/1 Enable park & Z Raise
|
||||
* X[linear] Park X (Requires TOOLCHANGE_PARK)
|
||||
* Y[linear] Park Y (Requires TOOLCHANGE_PARK)
|
||||
* Z[linear] Z Raise
|
||||
* F[linear] Fan Speed 0-255
|
||||
* G[linear/s] Fan time
|
||||
* S[linear] Swap length
|
||||
* B[linear] Extra Swap resume length
|
||||
* E[linear] Extra Prime length (as used by M217 Q)
|
||||
* P[linear/min] Prime speed
|
||||
* R[linear/min] Retract speed
|
||||
* U[linear/min] UnRetract speed
|
||||
* V[linear] 0/1 Enable auto prime first extruder used
|
||||
* W[linear] 0/1 Enable park & Z Raise
|
||||
* X[linear] Park X (Requires TOOLCHANGE_PARK)
|
||||
* Y[linear] Park Y (Requires TOOLCHANGE_PARK)
|
||||
* I[linear] Park I (Requires TOOLCHANGE_PARK and NUM_AXES >= 4)
|
||||
* J[linear] Park J (Requires TOOLCHANGE_PARK and NUM_AXES >= 5)
|
||||
* K[linear] Park K (Requires TOOLCHANGE_PARK and NUM_AXES >= 6)
|
||||
* C[linear] Park U (Requires TOOLCHANGE_PARK and NUM_AXES >= 7)
|
||||
* H[linear] Park V (Requires TOOLCHANGE_PARK and NUM_AXES >= 8)
|
||||
* O[linear] Park W (Requires TOOLCHANGE_PARK and NUM_AXES >= 9)
|
||||
* Z[linear] Z Raise
|
||||
* F[speed] Fan Speed 0-255
|
||||
* D[seconds] Fan time
|
||||
*
|
||||
* Tool migration settings
|
||||
* A[0|1] Enable auto-migration on runout
|
||||
@@ -76,8 +82,8 @@ void GcodeSuite::M217() {
|
||||
if (parser.seenval('R')) { const int16_t v = parser.value_linear_units(); toolchange_settings.retract_speed = constrain(v, 10, 5400); }
|
||||
if (parser.seenval('U')) { const int16_t v = parser.value_linear_units(); toolchange_settings.unretract_speed = constrain(v, 10, 5400); }
|
||||
#if TOOLCHANGE_FS_FAN >= 0 && HAS_FAN
|
||||
if (parser.seenval('F')) { const int16_t v = parser.value_linear_units(); toolchange_settings.fan_speed = constrain(v, 0, 255); }
|
||||
if (parser.seenval('G')) { const int16_t v = parser.value_linear_units(); toolchange_settings.fan_time = constrain(v, 1, 30); }
|
||||
if (parser.seenval('F')) { const uint16_t v = parser.value_ushort(); toolchange_settings.fan_speed = constrain(v, 0, 255); }
|
||||
if (parser.seenval('D')) { const uint16_t v = parser.value_ushort(); toolchange_settings.fan_time = constrain(v, 1, 30); }
|
||||
#endif
|
||||
#endif
|
||||
|
||||
@@ -88,10 +94,32 @@ void GcodeSuite::M217() {
|
||||
#if ENABLED(TOOLCHANGE_PARK)
|
||||
if (parser.seenval('W')) { toolchange_settings.enable_park = parser.value_linear_units(); }
|
||||
if (parser.seenval('X')) { const int16_t v = parser.value_linear_units(); toolchange_settings.change_point.x = constrain(v, X_MIN_POS, X_MAX_POS); }
|
||||
if (parser.seenval('Y')) { const int16_t v = parser.value_linear_units(); toolchange_settings.change_point.y = constrain(v, Y_MIN_POS, Y_MAX_POS); }
|
||||
#if HAS_Y_AXIS
|
||||
if (parser.seenval('Y')) { const int16_t v = parser.value_linear_units(); toolchange_settings.change_point.y = constrain(v, Y_MIN_POS, Y_MAX_POS); }
|
||||
#endif
|
||||
#if HAS_I_AXIS
|
||||
if (parser.seenval('I')) { const int16_t v = parser.TERN(AXIS4_ROTATES, value_int, value_linear_units)(); toolchange_settings.change_point.i = constrain(v, I_MIN_POS, I_MAX_POS); }
|
||||
#endif
|
||||
#if HAS_J_AXIS
|
||||
if (parser.seenval('J')) { const int16_t v = parser.TERN(AXIS5_ROTATES, value_int, value_linear_units)(); toolchange_settings.change_point.j = constrain(v, J_MIN_POS, J_MAX_POS); }
|
||||
#endif
|
||||
#if HAS_K_AXIS
|
||||
if (parser.seenval('K')) { const int16_t v = parser.TERN(AXIS6_ROTATES, value_int, value_linear_units)(); toolchange_settings.change_point.k = constrain(v, K_MIN_POS, K_MAX_POS); }
|
||||
#endif
|
||||
#if HAS_U_AXIS
|
||||
if (parser.seenval('C')) { const int16_t v = parser.TERN(AXIS7_ROTATES, value_int, value_linear_units)(); toolchange_settings.change_point.u = constrain(v, U_MIN_POS, U_MAX_POS); }
|
||||
#endif
|
||||
#if HAS_V_AXIS
|
||||
if (parser.seenval('H')) { const int16_t v = parser.TERN(AXIS8_ROTATES, value_int, value_linear_units)(); toolchange_settings.change_point.v = constrain(v, V_MIN_POS, V_MAX_POS); }
|
||||
#endif
|
||||
#if HAS_W_AXIS
|
||||
if (parser.seenval('O')) { const int16_t v = parser.TERN(AXIS9_ROTATES, value_int, value_linear_units)(); toolchange_settings.change_point.w = constrain(v, W_MIN_POS, W_MAX_POS); }
|
||||
#endif
|
||||
#endif
|
||||
|
||||
if (parser.seenval('Z')) { toolchange_settings.z_raise = parser.value_linear_units(); }
|
||||
#if HAS_Z_AXIS
|
||||
if (parser.seenval('Z')) { toolchange_settings.z_raise = parser.value_linear_units(); }
|
||||
#endif
|
||||
|
||||
#if ENABLED(TOOLCHANGE_MIGRATION_FEATURE)
|
||||
migration.target = 0; // 0 = disabled
|
||||
@@ -131,19 +159,19 @@ void GcodeSuite::M217() {
|
||||
}
|
||||
|
||||
void GcodeSuite::M217_report(const bool forReplay/*=true*/) {
|
||||
report_heading_etc(forReplay, PSTR(STR_TOOL_CHANGING));
|
||||
report_heading_etc(forReplay, F(STR_TOOL_CHANGING));
|
||||
|
||||
SERIAL_ECHOPGM(" M217");
|
||||
|
||||
#if ENABLED(TOOLCHANGE_FILAMENT_SWAP)
|
||||
SERIAL_ECHOPGM(" S", LINEAR_UNIT(toolchange_settings.swap_length));
|
||||
SERIAL_ECHOPGM_P(SP_B_STR, LINEAR_UNIT(toolchange_settings.extra_resume),
|
||||
SP_E_STR, LINEAR_UNIT(toolchange_settings.extra_prime),
|
||||
SP_P_STR, LINEAR_UNIT(toolchange_settings.prime_speed));
|
||||
SP_E_STR, LINEAR_UNIT(toolchange_settings.extra_prime),
|
||||
SP_P_STR, LINEAR_UNIT(toolchange_settings.prime_speed));
|
||||
SERIAL_ECHOPGM(" R", LINEAR_UNIT(toolchange_settings.retract_speed),
|
||||
" U", LINEAR_UNIT(toolchange_settings.unretract_speed),
|
||||
" F", toolchange_settings.fan_speed,
|
||||
" G", toolchange_settings.fan_time);
|
||||
" D", toolchange_settings.fan_time);
|
||||
|
||||
#if ENABLED(TOOLCHANGE_MIGRATION_FEATURE)
|
||||
SERIAL_ECHOPGM(" A", migration.automode);
|
||||
@@ -152,8 +180,22 @@ void GcodeSuite::M217_report(const bool forReplay/*=true*/) {
|
||||
|
||||
#if ENABLED(TOOLCHANGE_PARK)
|
||||
SERIAL_ECHOPGM(" W", LINEAR_UNIT(toolchange_settings.enable_park));
|
||||
SERIAL_ECHOPGM_P(SP_X_STR, LINEAR_UNIT(toolchange_settings.change_point.x));
|
||||
SERIAL_ECHOPGM_P(SP_Y_STR, LINEAR_UNIT(toolchange_settings.change_point.y));
|
||||
SERIAL_ECHOPGM_P(
|
||||
SP_X_STR, LINEAR_UNIT(toolchange_settings.change_point.x)
|
||||
#if HAS_Y_AXIS
|
||||
, SP_Y_STR, LINEAR_UNIT(toolchange_settings.change_point.y)
|
||||
#endif
|
||||
#if SECONDARY_AXES >= 1
|
||||
, LIST_N(DOUBLE(SECONDARY_AXES)
|
||||
, SP_I_STR, I_AXIS_UNIT(toolchange_settings.change_point.i)
|
||||
, SP_J_STR, J_AXIS_UNIT(toolchange_settings.change_point.j)
|
||||
, SP_K_STR, K_AXIS_UNIT(toolchange_settings.change_point.k)
|
||||
, SP_C_STR, U_AXIS_UNIT(toolchange_settings.change_point.u)
|
||||
, PSTR(" H"), V_AXIS_UNIT(toolchange_settings.change_point.v)
|
||||
, PSTR(" O"), W_AXIS_UNIT(toolchange_settings.change_point.w)
|
||||
)
|
||||
#endif
|
||||
);
|
||||
#endif
|
||||
|
||||
#if ENABLED(TOOLCHANGE_FS_PRIME_FIRST_USED)
|
||||
|
@@ -57,7 +57,7 @@ void GcodeSuite::M218() {
|
||||
}
|
||||
|
||||
void GcodeSuite::M218_report(const bool forReplay/*=true*/) {
|
||||
report_heading_etc(forReplay, PSTR(STR_HOTEND_OFFSETS));
|
||||
report_heading_etc(forReplay, F(STR_HOTEND_OFFSETS));
|
||||
LOOP_S_L_N(e, 1, HOTENDS) {
|
||||
report_echo_start(forReplay);
|
||||
SERIAL_ECHOPGM_P(
|
||||
|
@@ -47,15 +47,15 @@ void GcodeSuite::M281() {
|
||||
return;
|
||||
}
|
||||
#endif
|
||||
if (parser.seen('L')) servo_angles[servo_index][0] = parser.value_int();
|
||||
if (parser.seen('U')) servo_angles[servo_index][1] = parser.value_int();
|
||||
if (parser.seenval('L')) servo_angles[servo_index][0] = parser.value_int();
|
||||
if (parser.seenval('U')) servo_angles[servo_index][1] = parser.value_int();
|
||||
}
|
||||
else
|
||||
SERIAL_ERROR_MSG("Servo ", servo_index, " out of range");
|
||||
}
|
||||
|
||||
void GcodeSuite::M281_report(const bool forReplay/*=true*/) {
|
||||
report_heading_etc(forReplay, PSTR(STR_SERVO_ANGLES));
|
||||
report_heading_etc(forReplay, F(STR_SERVO_ANGLES));
|
||||
LOOP_L_N(i, NUM_SERVOS) {
|
||||
switch (i) {
|
||||
default: break;
|
||||
|
@@ -79,7 +79,7 @@ void GcodeSuite::M301() {
|
||||
}
|
||||
|
||||
void GcodeSuite::M301_report(const bool forReplay/*=true*/ E_OPTARG(const int8_t eindex/*=-1*/)) {
|
||||
report_heading(forReplay, PSTR(STR_HOTEND_PID));
|
||||
report_heading(forReplay, F(STR_HOTEND_PID));
|
||||
IF_DISABLED(HAS_MULTI_EXTRUDER, constexpr int8_t eindex = -1);
|
||||
HOTEND_LOOP() {
|
||||
if (e == eindex || eindex == -1) {
|
||||
|
@@ -27,6 +27,10 @@
|
||||
#include "../gcode.h"
|
||||
#include "../../module/temperature.h"
|
||||
|
||||
#if ENABLED(DWIN_LCD_PROUI)
|
||||
#include "../../lcd/e3v2/proui/dwin_defines.h"
|
||||
#endif
|
||||
|
||||
/**
|
||||
* M302: Allow cold extrudes, or set the minimum extrude temperature
|
||||
*
|
||||
@@ -47,6 +51,7 @@ void GcodeSuite::M302() {
|
||||
if (seen_S) {
|
||||
thermalManager.extrude_min_temp = parser.value_celsius();
|
||||
thermalManager.allow_cold_extrude = (thermalManager.extrude_min_temp == 0);
|
||||
TERN_(DWIN_LCD_PROUI, HMI_data.ExtMinT = thermalManager.extrude_min_temp);
|
||||
}
|
||||
|
||||
if (parser.seen('P'))
|
||||
@@ -55,7 +60,7 @@ void GcodeSuite::M302() {
|
||||
// Report current state
|
||||
SERIAL_ECHO_START();
|
||||
SERIAL_ECHOPGM("Cold extrudes are ");
|
||||
SERIAL_ECHOPGM_P(thermalManager.allow_cold_extrude ? PSTR("en") : PSTR("dis"));
|
||||
SERIAL_ECHOF(thermalManager.allow_cold_extrude ? F("en") : F("dis"));
|
||||
SERIAL_ECHOLNPGM("abled (min temp ", thermalManager.extrude_min_temp, "C)");
|
||||
}
|
||||
}
|
||||
|
@@ -36,14 +36,14 @@
|
||||
*/
|
||||
void GcodeSuite::M304() {
|
||||
if (!parser.seen("PID")) return M304_report();
|
||||
if (parser.seen('P')) thermalManager.temp_bed.pid.Kp = parser.value_float();
|
||||
if (parser.seen('I')) thermalManager.temp_bed.pid.Ki = scalePID_i(parser.value_float());
|
||||
if (parser.seen('D')) thermalManager.temp_bed.pid.Kd = scalePID_d(parser.value_float());
|
||||
if (parser.seenval('P')) thermalManager.temp_bed.pid.Kp = parser.value_float();
|
||||
if (parser.seenval('I')) thermalManager.temp_bed.pid.Ki = scalePID_i(parser.value_float());
|
||||
if (parser.seenval('D')) thermalManager.temp_bed.pid.Kd = scalePID_d(parser.value_float());
|
||||
}
|
||||
|
||||
void GcodeSuite::M304_report(const bool forReplay/*=true*/) {
|
||||
report_heading_etc(forReplay, PSTR(STR_BED_PID));
|
||||
SERIAL_ECHO_MSG(
|
||||
report_heading_etc(forReplay, F(STR_BED_PID));
|
||||
SERIAL_ECHOLNPGM(
|
||||
" M304 P", thermalManager.temp_bed.pid.Kp
|
||||
, " I", unscalePID_i(thermalManager.temp_bed.pid.Ki)
|
||||
, " D", unscalePID_d(thermalManager.temp_bed.pid.Kd)
|
||||
|
@@ -52,19 +52,19 @@ void GcodeSuite::M305() {
|
||||
if (t_index >= (USER_THERMISTORS) || (do_set && t_index < 0))
|
||||
SERIAL_ECHO_MSG("!Invalid index. (0 <= P <= ", USER_THERMISTORS - 1, ")");
|
||||
else if (do_set) {
|
||||
if (parser.seen('R')) // Pullup resistor value
|
||||
if (parser.seenval('R')) // Pullup resistor value
|
||||
if (!thermalManager.set_pull_up_res(t_index, parser.value_float()))
|
||||
SERIAL_ECHO_MSG("!Invalid series resistance. (0 < R < 1000000)");
|
||||
|
||||
if (parser.seen('T')) // Resistance at 25C
|
||||
if (parser.seenval('T')) // Resistance at 25C
|
||||
if (!thermalManager.set_res25(t_index, parser.value_float()))
|
||||
SERIAL_ECHO_MSG("!Invalid 25C resistance. (0 < T < 10000000)");
|
||||
|
||||
if (parser.seen('B')) // Beta value
|
||||
if (parser.seenval('B')) // Beta value
|
||||
if (!thermalManager.set_beta(t_index, parser.value_float()))
|
||||
SERIAL_ECHO_MSG("!Invalid beta. (0 < B < 1000000)");
|
||||
|
||||
if (parser.seen('C')) // Steinhart-Hart C coefficient
|
||||
if (parser.seenval('C')) // Steinhart-Hart C coefficient
|
||||
if (!thermalManager.set_sh_coeff(t_index, parser.value_float()))
|
||||
SERIAL_ECHO_MSG("!Invalid Steinhart-Hart C coeff. (-0.01 < C < +0.01)");
|
||||
} // If not setting then report parameters
|
||||
|
@@ -42,7 +42,7 @@ void GcodeSuite::M309() {
|
||||
}
|
||||
|
||||
void GcodeSuite::M309_report(const bool forReplay/*=true*/) {
|
||||
report_heading_etc(forReplay, PSTR(STR_CHAMBER_PID));
|
||||
report_heading_etc(forReplay, F(STR_CHAMBER_PID));
|
||||
SERIAL_ECHOLNPGM(
|
||||
" M309 P", thermalManager.temp_chamber.pid.Kp
|
||||
, " I", unscalePID_i(thermalManager.temp_chamber.pid.Ki)
|
||||
|
@@ -65,12 +65,12 @@ inline void toggle_pins() {
|
||||
pin_t pin = GET_PIN_MAP_PIN_M43(i);
|
||||
if (!VALID_PIN(pin)) continue;
|
||||
if (M43_NEVER_TOUCH(i) || (!ignore_protection && pin_is_protected(pin))) {
|
||||
report_pin_state_extended(pin, ignore_protection, true, PSTR("Untouched "));
|
||||
report_pin_state_extended(pin, ignore_protection, true, F("Untouched "));
|
||||
SERIAL_EOL();
|
||||
}
|
||||
else {
|
||||
watchdog_refresh();
|
||||
report_pin_state_extended(pin, ignore_protection, true, PSTR("Pulsing "));
|
||||
hal.watchdog_refresh();
|
||||
report_pin_state_extended(pin, ignore_protection, true, F("Pulsing "));
|
||||
#ifdef __STM32F1__
|
||||
const auto prior_mode = _GET_MODE(i);
|
||||
#else
|
||||
@@ -98,10 +98,10 @@ inline void toggle_pins() {
|
||||
{
|
||||
pinMode(pin, OUTPUT);
|
||||
for (int16_t j = 0; j < repeat; j++) {
|
||||
watchdog_refresh(); extDigitalWrite(pin, 0); safe_delay(wait);
|
||||
watchdog_refresh(); extDigitalWrite(pin, 1); safe_delay(wait);
|
||||
watchdog_refresh(); extDigitalWrite(pin, 0); safe_delay(wait);
|
||||
watchdog_refresh();
|
||||
hal.watchdog_refresh(); extDigitalWrite(pin, 0); safe_delay(wait);
|
||||
hal.watchdog_refresh(); extDigitalWrite(pin, 1); safe_delay(wait);
|
||||
hal.watchdog_refresh(); extDigitalWrite(pin, 0); safe_delay(wait);
|
||||
hal.watchdog_refresh();
|
||||
}
|
||||
}
|
||||
#ifdef __STM32F1__
|
||||
@@ -198,10 +198,10 @@ inline void servo_probe_test() {
|
||||
uint8_t i = 0;
|
||||
SERIAL_ECHOLNPGM(". Deploy & stow 4 times");
|
||||
do {
|
||||
MOVE_SERVO(probe_index, servo_angles[Z_PROBE_SERVO_NR][0]); // Deploy
|
||||
servo[probe_index].move(servo_angles[Z_PROBE_SERVO_NR][0]); // Deploy
|
||||
safe_delay(500);
|
||||
deploy_state = READ(PROBE_TEST_PIN);
|
||||
MOVE_SERVO(probe_index, servo_angles[Z_PROBE_SERVO_NR][1]); // Stow
|
||||
servo[probe_index].move(servo_angles[Z_PROBE_SERVO_NR][1]); // Stow
|
||||
safe_delay(500);
|
||||
stow_state = READ(PROBE_TEST_PIN);
|
||||
} while (++i < 4);
|
||||
@@ -226,7 +226,7 @@ inline void servo_probe_test() {
|
||||
}
|
||||
|
||||
// Ask the user for a trigger event and measure the pulse width.
|
||||
MOVE_SERVO(probe_index, servo_angles[Z_PROBE_SERVO_NR][0]); // Deploy
|
||||
servo[probe_index].move(servo_angles[Z_PROBE_SERVO_NR][0]); // Deploy
|
||||
safe_delay(500);
|
||||
SERIAL_ECHOLNPGM("** Please trigger probe within 30 sec **");
|
||||
uint16_t probe_counter = 0;
|
||||
@@ -256,7 +256,7 @@ inline void servo_probe_test() {
|
||||
}
|
||||
else SERIAL_ECHOLNPGM("FAIL: Noise detected - please re-run test");
|
||||
|
||||
MOVE_SERVO(probe_index, servo_angles[Z_PROBE_SERVO_NR][1]); // Stow
|
||||
servo[probe_index].move(servo_angles[Z_PROBE_SERVO_NR][1]); // Stow
|
||||
return;
|
||||
}
|
||||
}
|
||||
@@ -303,7 +303,7 @@ void GcodeSuite::M43() {
|
||||
if (parser.seen('E')) {
|
||||
endstops.monitor_flag = parser.value_bool();
|
||||
SERIAL_ECHOPGM("endstop monitor ");
|
||||
SERIAL_ECHOPGM_P(endstops.monitor_flag ? PSTR("en") : PSTR("dis"));
|
||||
SERIAL_ECHOF(endstops.monitor_flag ? F("en") : F("dis"));
|
||||
SERIAL_ECHOLNPGM("abled");
|
||||
return;
|
||||
}
|
||||
@@ -313,7 +313,7 @@ void GcodeSuite::M43() {
|
||||
|
||||
// 'P' Get the range of pins to test or watch
|
||||
uint8_t first_pin = PARSED_PIN_INDEX('P', 0),
|
||||
last_pin = parser.seenval('P') ? first_pin : NUMBER_PINS_TOTAL - 1;
|
||||
last_pin = parser.seenval('P') ? first_pin : TERN(HAS_HIGH_ANALOG_PINS, NUM_DIGITAL_PINS, NUMBER_PINS_TOTAL) - 1;
|
||||
|
||||
if (first_pin > last_pin) return;
|
||||
|
||||
@@ -333,19 +333,19 @@ void GcodeSuite::M43() {
|
||||
if (M43_NEVER_TOUCH(i) || (!ignore_protection && pin_is_protected(pin))) continue;
|
||||
pinMode(pin, INPUT_PULLUP);
|
||||
delay(1);
|
||||
/*
|
||||
if (IS_ANALOG(pin))
|
||||
pin_state[pin - first_pin] = analogRead(DIGITAL_PIN_TO_ANALOG_PIN(pin)); // int16_t pin_state[...]
|
||||
else
|
||||
//*/
|
||||
pin_state[i - first_pin] = extDigitalRead(pin);
|
||||
/*
|
||||
if (IS_ANALOG(pin))
|
||||
pin_state[pin - first_pin] = analogRead(DIGITAL_PIN_TO_ANALOG_PIN(pin)); // int16_t pin_state[...]
|
||||
else
|
||||
//*/
|
||||
pin_state[i - first_pin] = extDigitalRead(pin);
|
||||
}
|
||||
|
||||
#if HAS_RESUME_CONTINUE
|
||||
KEEPALIVE_STATE(PAUSED_FOR_USER);
|
||||
wait_for_user = true;
|
||||
TERN_(HOST_PROMPT_SUPPORT, host_prompt_do(PROMPT_USER_CONTINUE, PSTR("M43 Wait Called"), CONTINUE_STR));
|
||||
TERN_(EXTENSIBLE_UI, ExtUI::onUserConfirmRequired_P(PSTR("M43 Wait Called")));
|
||||
TERN_(HOST_PROMPT_SUPPORT, hostui.prompt_do(PROMPT_USER_CONTINUE, F("M43 Wait Called"), FPSTR(CONTINUE_STR)));
|
||||
TERN_(EXTENSIBLE_UI, ExtUI::onUserConfirmRequired(F("M43 Wait Called")));
|
||||
#endif
|
||||
|
||||
for (;;) {
|
||||
|
@@ -25,7 +25,7 @@
|
||||
#if ENABLED(SD_ABORT_ON_ENDSTOP_HIT)
|
||||
|
||||
#include "../gcode.h"
|
||||
#include "../../module/stepper.h"
|
||||
#include "../../module/planner.h"
|
||||
|
||||
/**
|
||||
* M540: Set whether SD card print should abort on endstop hit (M540 S<0|1>)
|
||||
|
@@ -53,7 +53,7 @@
|
||||
// b7 b6 b5 b4 ~b4 ... hi bits, NOT last bit
|
||||
// b3 b2 b1 b0 ~b0 ... lo bits, NOT last bit
|
||||
//
|
||||
void M672_send(uint8_t b) { // bit rate requirement: 1KHz +/- 30%
|
||||
void M672_send(uint8_t b) { // bit rate requirement: 1kHz +/- 30%
|
||||
LOOP_L_N(bits, 14) {
|
||||
switch (bits) {
|
||||
default: { OUT_WRITE(SMART_EFFECTOR_MOD_PIN, !!(b & 0x80)); b <<= 1; break; } // send bit, shift next into place
|
||||
|
@@ -24,7 +24,7 @@
|
||||
#include "../../module/planner.h"
|
||||
|
||||
/**
|
||||
* M92: Set axis steps-per-unit for one or more axes, X, Y, Z, and E.
|
||||
* M92: Set axis steps-per-unit for one or more axes, X, Y, Z, [I, [J, [K, [U, [V, [W,]]]]]] and E.
|
||||
* (Follows the same syntax as G92)
|
||||
*
|
||||
* With multiple extruders use T to specify which one.
|
||||
@@ -43,11 +43,11 @@ void GcodeSuite::M92() {
|
||||
if (target_extruder < 0) return;
|
||||
|
||||
// No arguments? Show M92 report.
|
||||
if (!parser.seen(LOGICAL_AXES_STRING TERN_(MAGIC_NUMBERS_GCODE, "HL")))
|
||||
if (!parser.seen(STR_AXES_LOGICAL TERN_(MAGIC_NUMBERS_GCODE, "HL")))
|
||||
return M92_report(true, target_extruder);
|
||||
|
||||
LOOP_LOGICAL_AXES(i) {
|
||||
if (parser.seenval(axis_codes[i])) {
|
||||
if (parser.seenval(AXIS_CHAR(i))) {
|
||||
if (TERN1(HAS_EXTRUDERS, i != E_AXIS))
|
||||
planner.settings.axis_steps_per_mm[i] = parser.value_per_axis_units((AxisEnum)i);
|
||||
else {
|
||||
@@ -91,15 +91,18 @@ void GcodeSuite::M92() {
|
||||
}
|
||||
|
||||
void GcodeSuite::M92_report(const bool forReplay/*=true*/, const int8_t e/*=-1*/) {
|
||||
report_heading_etc(forReplay, PSTR(STR_STEPS_PER_UNIT));
|
||||
SERIAL_ECHOPGM_P(LIST_N(DOUBLE(LINEAR_AXES),
|
||||
report_heading_etc(forReplay, F(STR_STEPS_PER_UNIT));
|
||||
SERIAL_ECHOPGM_P(LIST_N(DOUBLE(NUM_AXES),
|
||||
PSTR(" M92 X"), LINEAR_UNIT(planner.settings.axis_steps_per_mm[X_AXIS]),
|
||||
SP_Y_STR, LINEAR_UNIT(planner.settings.axis_steps_per_mm[Y_AXIS]),
|
||||
SP_Z_STR, LINEAR_UNIT(planner.settings.axis_steps_per_mm[Z_AXIS]),
|
||||
SP_I_STR, LINEAR_UNIT(planner.settings.axis_steps_per_mm[I_AXIS]),
|
||||
SP_J_STR, LINEAR_UNIT(planner.settings.axis_steps_per_mm[J_AXIS]),
|
||||
SP_K_STR, LINEAR_UNIT(planner.settings.axis_steps_per_mm[K_AXIS]))
|
||||
);
|
||||
SP_I_STR, I_AXIS_UNIT(planner.settings.axis_steps_per_mm[I_AXIS]),
|
||||
SP_J_STR, J_AXIS_UNIT(planner.settings.axis_steps_per_mm[J_AXIS]),
|
||||
SP_K_STR, K_AXIS_UNIT(planner.settings.axis_steps_per_mm[K_AXIS]),
|
||||
SP_U_STR, U_AXIS_UNIT(planner.settings.axis_steps_per_mm[U_AXIS]),
|
||||
SP_V_STR, V_AXIS_UNIT(planner.settings.axis_steps_per_mm[V_AXIS]),
|
||||
SP_W_STR, W_AXIS_UNIT(planner.settings.axis_steps_per_mm[W_AXIS])
|
||||
));
|
||||
#if HAS_EXTRUDERS && DISABLED(DISTINCT_E_FACTORS)
|
||||
SERIAL_ECHOPGM_P(SP_E_STR, VOLUMETRIC_UNIT(planner.settings.axis_steps_per_mm[E_AXIS]));
|
||||
#endif
|
||||
|
@@ -40,7 +40,7 @@ void GcodeSuite::M108() {
|
||||
* M112: Full Shutdown
|
||||
*/
|
||||
void GcodeSuite::M112() {
|
||||
kill(M112_KILL_STR, nullptr, true);
|
||||
kill(FPSTR(M112_KILL_STR), nullptr, true);
|
||||
}
|
||||
|
||||
/**
|
||||
|
@@ -26,7 +26,7 @@
|
||||
* M111: Set the debug level
|
||||
*/
|
||||
void GcodeSuite::M111() {
|
||||
if (parser.seen('S')) marlin_debug_flags = parser.byteval('S');
|
||||
if (parser.seenval('S')) marlin_debug_flags = parser.value_byte();
|
||||
|
||||
static PGMSTR(str_debug_1, STR_DEBUG_ECHO);
|
||||
static PGMSTR(str_debug_2, STR_DEBUG_INFO);
|
||||
@@ -34,12 +34,12 @@ void GcodeSuite::M111() {
|
||||
static PGMSTR(str_debug_8, STR_DEBUG_DRYRUN);
|
||||
static PGMSTR(str_debug_16, STR_DEBUG_COMMUNICATION);
|
||||
#if ENABLED(DEBUG_LEVELING_FEATURE)
|
||||
static PGMSTR(str_debug_lvl, STR_DEBUG_LEVELING);
|
||||
static PGMSTR(str_debug_detail, STR_DEBUG_DETAIL);
|
||||
#endif
|
||||
|
||||
static PGM_P const debug_strings[] PROGMEM = {
|
||||
str_debug_1, str_debug_2, str_debug_4, str_debug_8, str_debug_16,
|
||||
TERN_(DEBUG_LEVELING_FEATURE, str_debug_lvl)
|
||||
TERN_(DEBUG_LEVELING_FEATURE, str_debug_detail)
|
||||
};
|
||||
|
||||
SERIAL_ECHO_START();
|
||||
@@ -49,7 +49,7 @@ void GcodeSuite::M111() {
|
||||
LOOP_L_N(i, COUNT(debug_strings)) {
|
||||
if (TEST(marlin_debug_flags, i)) {
|
||||
if (comma++) SERIAL_CHAR(',');
|
||||
SERIAL_ECHOPGM_P((char*)pgm_read_ptr(&debug_strings[i]));
|
||||
SERIAL_ECHOPGM_P((PGM_P)pgm_read_ptr(&debug_strings[i]));
|
||||
}
|
||||
}
|
||||
}
|
||||
|
@@ -23,6 +23,8 @@
|
||||
#include "../gcode.h"
|
||||
#include "../../MarlinCore.h" // for stepper_inactive_time, disable_e_steppers
|
||||
#include "../../lcd/marlinui.h"
|
||||
#include "../../module/motion.h" // for e_axis_mask
|
||||
#include "../../module/planner.h"
|
||||
#include "../../module/stepper.h"
|
||||
|
||||
#if ENABLED(AUTO_BED_LEVELING_UBL)
|
||||
@@ -33,8 +35,8 @@
|
||||
#include "../../core/debug_out.h"
|
||||
#include "../../libs/hex_print.h"
|
||||
|
||||
inline axis_flags_t selected_axis_bits() {
|
||||
axis_flags_t selected{0};
|
||||
inline stepper_flags_t selected_axis_bits() {
|
||||
stepper_flags_t selected{0};
|
||||
#if HAS_EXTRUDERS
|
||||
if (parser.seen('E')) {
|
||||
if (E_TERN0(parser.has_value())) {
|
||||
@@ -43,22 +45,25 @@ inline axis_flags_t selected_axis_bits() {
|
||||
selected.bits = _BV(INDEX_OF_AXIS(E_AXIS, e));
|
||||
}
|
||||
else
|
||||
selected.bits = selected.e_bits();
|
||||
selected.bits = e_axis_mask;
|
||||
}
|
||||
#endif
|
||||
selected.bits |= LINEAR_AXIS_GANG(
|
||||
selected.bits |= NUM_AXIS_GANG(
|
||||
(parser.seen_test('X') << X_AXIS),
|
||||
| (parser.seen_test('Y') << Y_AXIS),
|
||||
| (parser.seen_test('Z') << Z_AXIS),
|
||||
| (parser.seen_test(AXIS4_NAME) << I_AXIS),
|
||||
| (parser.seen_test(AXIS5_NAME) << J_AXIS),
|
||||
| (parser.seen_test(AXIS6_NAME) << K_AXIS)
|
||||
| (parser.seen_test(AXIS6_NAME) << K_AXIS),
|
||||
| (parser.seen_test(AXIS7_NAME) << U_AXIS),
|
||||
| (parser.seen_test(AXIS8_NAME) << V_AXIS),
|
||||
| (parser.seen_test(AXIS9_NAME) << W_AXIS)
|
||||
);
|
||||
return selected;
|
||||
}
|
||||
|
||||
// Enable specified axes and warn about other affected axes
|
||||
void do_enable(const axis_flags_t to_enable) {
|
||||
void do_enable(const stepper_flags_t to_enable) {
|
||||
const ena_mask_t was_enabled = stepper.axis_enabled.bits,
|
||||
shall_enable = to_enable.bits & ~was_enabled;
|
||||
|
||||
@@ -69,15 +74,15 @@ void do_enable(const axis_flags_t to_enable) {
|
||||
ena_mask_t also_enabled = 0; // Track steppers enabled due to overlap
|
||||
|
||||
// Enable all flagged axes
|
||||
LOOP_LINEAR_AXES(a) {
|
||||
LOOP_NUM_AXES(a) {
|
||||
if (TEST(shall_enable, a)) {
|
||||
stepper.enable_axis(AxisEnum(a)); // Mark and enable the requested axis
|
||||
DEBUG_ECHOLNPGM("Enabled ", axis_codes[a], " (", a, ") with overlap ", hex_word(enable_overlap[a]), " ... Enabled: ", hex_word(stepper.axis_enabled.bits));
|
||||
DEBUG_ECHOLNPGM("Enabled ", AXIS_CHAR(a), " (", a, ") with overlap ", hex_word(enable_overlap[a]), " ... Enabled: ", hex_word(stepper.axis_enabled.bits));
|
||||
also_enabled |= enable_overlap[a];
|
||||
}
|
||||
}
|
||||
#if HAS_EXTRUDERS
|
||||
LOOP_L_N(e, EXTRUDERS) {
|
||||
EXTRUDER_LOOP() {
|
||||
const uint8_t a = INDEX_OF_AXIS(E_AXIS, e);
|
||||
if (TEST(shall_enable, a)) {
|
||||
stepper.ENABLE_EXTRUDER(e);
|
||||
@@ -89,7 +94,7 @@ void do_enable(const axis_flags_t to_enable) {
|
||||
|
||||
if ((also_enabled &= ~(shall_enable | was_enabled))) {
|
||||
SERIAL_CHAR('(');
|
||||
LOOP_LINEAR_AXES(a) if (TEST(also_enabled, a)) SERIAL_CHAR(axis_codes[a], ' ');
|
||||
LOOP_NUM_AXES(a) if (TEST(also_enabled, a)) SERIAL_CHAR(AXIS_CHAR(a), ' ');
|
||||
#if HAS_EXTRUDERS
|
||||
#define _EN_ALSO(N) if (TEST(also_enabled, INDEX_OF_AXIS(E_AXIS, N))) SERIAL_CHAR('E', '0' + N, ' ');
|
||||
REPEAT(EXTRUDERS, _EN_ALSO)
|
||||
@@ -125,23 +130,17 @@ void GcodeSuite::M17() {
|
||||
stepper.enable_e_steppers();
|
||||
}
|
||||
#endif
|
||||
LINEAR_AXIS_CODE(
|
||||
if (parser.seen_test('X')) stepper.enable_axis(X_AXIS),
|
||||
if (parser.seen_test('Y')) stepper.enable_axis(Y_AXIS),
|
||||
if (parser.seen_test('Z')) stepper.enable_axis(Z_AXIS),
|
||||
if (parser.seen_test(AXIS4_NAME)) stepper.enable_axis(I_AXIS),
|
||||
if (parser.seen_test(AXIS5_NAME)) stepper.enable_axis(J_AXIS),
|
||||
if (parser.seen_test(AXIS6_NAME)) stepper.enable_axis(K_AXIS)
|
||||
);
|
||||
LOOP_NUM_AXES(a)
|
||||
if (parser.seen_test(AXIS_CHAR(a))) stepper.enable_axis((AxisEnum)a);
|
||||
}
|
||||
}
|
||||
else {
|
||||
LCD_MESSAGEPGM(MSG_NO_MOVE);
|
||||
LCD_MESSAGE(MSG_NO_MOVE);
|
||||
stepper.enable_all_steppers();
|
||||
}
|
||||
}
|
||||
|
||||
void try_to_disable(const axis_flags_t to_disable) {
|
||||
void try_to_disable(const stepper_flags_t to_disable) {
|
||||
ena_mask_t still_enabled = to_disable.bits & stepper.axis_enabled.bits;
|
||||
|
||||
DEBUG_ECHOLNPGM("Enabled: ", hex_word(stepper.axis_enabled.bits), " To Disable: ", hex_word(to_disable.bits), " | ", hex_word(still_enabled));
|
||||
@@ -149,9 +148,9 @@ void try_to_disable(const axis_flags_t to_disable) {
|
||||
if (!still_enabled) return;
|
||||
|
||||
// Attempt to disable all flagged axes
|
||||
LOOP_LINEAR_AXES(a)
|
||||
LOOP_NUM_AXES(a)
|
||||
if (TEST(to_disable.bits, a)) {
|
||||
DEBUG_ECHOPGM("Try to disable ", axis_codes[a], " (", a, ") with overlap ", hex_word(enable_overlap[a]), " ... ");
|
||||
DEBUG_ECHOPGM("Try to disable ", AXIS_CHAR(a), " (", a, ") with overlap ", hex_word(enable_overlap[a]), " ... ");
|
||||
if (stepper.disable_axis(AxisEnum(a))) { // Mark the requested axis and request to disable
|
||||
DEBUG_ECHOPGM("OK");
|
||||
still_enabled &= ~(_BV(a) | enable_overlap[a]); // If actually disabled, clear one or more tracked bits
|
||||
@@ -161,7 +160,7 @@ void try_to_disable(const axis_flags_t to_disable) {
|
||||
DEBUG_ECHOLNPGM(" ... still_enabled=", hex_word(still_enabled));
|
||||
}
|
||||
#if HAS_EXTRUDERS
|
||||
LOOP_L_N(e, EXTRUDERS) {
|
||||
EXTRUDER_LOOP() {
|
||||
const uint8_t a = INDEX_OF_AXIS(E_AXIS, e);
|
||||
if (TEST(to_disable.bits, a)) {
|
||||
DEBUG_ECHOPGM("Try to disable E", AS_DIGIT(e), " (", a, ") with overlap ", hex_word(enable_overlap[a]), " ... ");
|
||||
@@ -178,7 +177,7 @@ void try_to_disable(const axis_flags_t to_disable) {
|
||||
|
||||
auto overlap_warning = [](const ena_mask_t axis_bits) {
|
||||
SERIAL_ECHOPGM(" not disabled. Shared with");
|
||||
LOOP_LINEAR_AXES(a) if (TEST(axis_bits, a)) SERIAL_CHAR(' ', axis_codes[a]);
|
||||
LOOP_NUM_AXES(a) if (TEST(axis_bits, a)) SERIAL_ECHOPGM_P((PGM_P)pgm_read_ptr(&SP_AXIS_STR[a]));
|
||||
#if HAS_EXTRUDERS
|
||||
#define _EN_STILLON(N) if (TEST(axis_bits, INDEX_OF_AXIS(E_AXIS, N))) SERIAL_CHAR(' ', 'E', '0' + N);
|
||||
REPEAT(EXTRUDERS, _EN_STILLON)
|
||||
@@ -187,14 +186,14 @@ void try_to_disable(const axis_flags_t to_disable) {
|
||||
};
|
||||
|
||||
// If any of the requested axes are still enabled, give a warning
|
||||
LOOP_LINEAR_AXES(a) {
|
||||
LOOP_NUM_AXES(a) {
|
||||
if (TEST(still_enabled, a)) {
|
||||
SERIAL_CHAR(axis_codes[a]);
|
||||
SERIAL_CHAR(AXIS_CHAR(a));
|
||||
overlap_warning(stepper.axis_enabled.bits & enable_overlap[a]);
|
||||
}
|
||||
}
|
||||
#if HAS_EXTRUDERS
|
||||
LOOP_L_N(e, EXTRUDERS) {
|
||||
EXTRUDER_LOOP() {
|
||||
const uint8_t a = INDEX_OF_AXIS(E_AXIS, e);
|
||||
if (TEST(still_enabled, a)) {
|
||||
SERIAL_CHAR('E', '0' + e);
|
||||
@@ -213,7 +212,16 @@ void try_to_disable(const axis_flags_t to_disable) {
|
||||
void GcodeSuite::M18_M84() {
|
||||
if (parser.seenval('S')) {
|
||||
reset_stepper_timeout();
|
||||
stepper_inactive_time = parser.value_millis_from_seconds();
|
||||
#if HAS_DISABLE_INACTIVE_AXIS
|
||||
const millis_t ms = parser.value_millis_from_seconds();
|
||||
#if LASER_SAFETY_TIMEOUT_MS > 0
|
||||
if (ms && ms <= LASER_SAFETY_TIMEOUT_MS) {
|
||||
SERIAL_ECHO_MSG("M18 timeout must be > ", MS_TO_SEC(LASER_SAFETY_TIMEOUT_MS + 999), " s for laser safety.");
|
||||
return;
|
||||
}
|
||||
#endif
|
||||
stepper_inactive_time = ms;
|
||||
#endif
|
||||
}
|
||||
else {
|
||||
if (parser.seen_axis()) {
|
||||
@@ -229,19 +237,13 @@ void GcodeSuite::M18_M84() {
|
||||
stepper.disable_e_steppers();
|
||||
}
|
||||
#endif
|
||||
LINEAR_AXIS_CODE(
|
||||
if (parser.seen_test('X')) stepper.disable_axis(X_AXIS),
|
||||
if (parser.seen_test('Y')) stepper.disable_axis(Y_AXIS),
|
||||
if (parser.seen_test('Z')) stepper.disable_axis(Z_AXIS),
|
||||
if (parser.seen_test(AXIS4_NAME)) stepper.disable_axis(I_AXIS),
|
||||
if (parser.seen_test(AXIS5_NAME)) stepper.disable_axis(J_AXIS),
|
||||
if (parser.seen_test(AXIS6_NAME)) stepper.disable_axis(K_AXIS)
|
||||
);
|
||||
LOOP_NUM_AXES(a)
|
||||
if (parser.seen_test(AXIS_CHAR(a))) stepper.disable_axis((AxisEnum)a);
|
||||
}
|
||||
}
|
||||
else
|
||||
planner.finish_and_disable();
|
||||
|
||||
TERN_(AUTO_BED_LEVELING_UBL, ubl.steppers_were_disabled());
|
||||
TERN_(AUTO_BED_LEVELING_UBL, bedlevel.steppers_were_disabled());
|
||||
}
|
||||
}
|
||||
|
@@ -40,15 +40,15 @@ void GcodeSuite::M211() {
|
||||
}
|
||||
|
||||
void GcodeSuite::M211_report(const bool forReplay/*=true*/) {
|
||||
report_heading_etc(forReplay, PSTR(STR_SOFT_ENDSTOPS));
|
||||
report_heading_etc(forReplay, F(STR_SOFT_ENDSTOPS));
|
||||
SERIAL_ECHOPGM(" M211 S", AS_DIGIT(soft_endstop._enabled), " ; ");
|
||||
serialprintln_onoff(soft_endstop._enabled);
|
||||
|
||||
report_echo_start(forReplay);
|
||||
const xyz_pos_t l_soft_min = soft_endstop.min.asLogical(),
|
||||
l_soft_max = soft_endstop.max.asLogical();
|
||||
print_pos(l_soft_min, PSTR(STR_SOFT_MIN), PSTR(" "));
|
||||
print_pos(l_soft_max, PSTR(STR_SOFT_MAX));
|
||||
print_pos(l_soft_min, F(STR_SOFT_MIN), F(" "));
|
||||
print_pos(l_soft_max, F(STR_SOFT_MAX));
|
||||
}
|
||||
|
||||
#endif // HAS_SOFTWARE_ENDSTOPS
|
||||
|
@@ -26,7 +26,7 @@
|
||||
|
||||
#include "../gcode.h"
|
||||
#include "../../MarlinCore.h" // for pin_is_protected and idle()
|
||||
#include "../../module/stepper.h"
|
||||
#include "../../module/planner.h"
|
||||
|
||||
void protected_pin_err();
|
||||
|
||||
|
@@ -48,7 +48,7 @@ void GcodeSuite::M280() {
|
||||
const int anew = parser.value_int();
|
||||
if (anew >= 0) {
|
||||
#if ENABLED(POLARGRAPH)
|
||||
if (parser.seen('T')) { // (ms) Total duration of servo move
|
||||
if (parser.seenval('T')) { // (ms) Total duration of servo move
|
||||
const int16_t t = constrain(parser.value_int(), 0, 10000);
|
||||
const int aold = servo[servo_index].read();
|
||||
millis_t now = millis();
|
||||
@@ -56,14 +56,14 @@ void GcodeSuite::M280() {
|
||||
while (PENDING(now, end)) {
|
||||
safe_delay(50);
|
||||
now = _MIN(millis(), end);
|
||||
MOVE_SERVO(servo_index, LROUND(aold + (anew - aold) * (float(now - start) / t)));
|
||||
servo[servo_index].move(LROUND(aold + (anew - aold) * (float(now - start) / t)));
|
||||
}
|
||||
}
|
||||
#endif // POLARGRAPH
|
||||
MOVE_SERVO(servo_index, anew);
|
||||
servo[servo_index].move(anew);
|
||||
}
|
||||
else
|
||||
DETACH_SERVO(servo_index);
|
||||
servo[servo_index].detach();
|
||||
}
|
||||
else
|
||||
SERIAL_ECHO_MSG(" Servo ", servo_index, ": ", servo[servo_index].read());
|
||||
|
@@ -36,7 +36,7 @@ void GcodeSuite::M282() {
|
||||
|
||||
const int servo_index = parser.value_int();
|
||||
if (WITHIN(servo_index, 0, NUM_SERVOS - 1))
|
||||
DETACH_SERVO(servo_index);
|
||||
servo[servo_index].detach();
|
||||
else
|
||||
SERIAL_ECHO_MSG("Servo ", servo_index, " out of range");
|
||||
|
||||
|
@@ -26,24 +26,34 @@
|
||||
|
||||
#include "../gcode.h"
|
||||
#include "../../feature/spindle_laser.h"
|
||||
#include "../../module/stepper.h"
|
||||
#include "../../module/planner.h"
|
||||
|
||||
/**
|
||||
* Laser:
|
||||
* M3 - Laser ON/Power (Ramped power)
|
||||
* M4 - Laser ON/Power (Continuous power)
|
||||
* M4 - Laser ON/Power (Ramped power)
|
||||
* M5 - Set power output to 0 (leaving inline mode unchanged).
|
||||
*
|
||||
* M3I - Enable continuous inline power to be processed by the planner, with power
|
||||
* calculated and set in the planner blocks, processed inline during stepping.
|
||||
* Within inline mode M3 S-Values will set the power for the next moves e.g. G1 X10 Y10 powers on with the last S-Value.
|
||||
* M3I must be set before using planner-synced M3 inline S-Values (LASER_POWER_SYNC).
|
||||
*
|
||||
* M4I - Set dynamic mode which calculates laser power OCR based on the current feedrate.
|
||||
*
|
||||
* M5I - Clear inline mode and set power to 0.
|
||||
*
|
||||
* Spindle:
|
||||
* M3 - Spindle ON (Clockwise)
|
||||
* M4 - Spindle ON (Counter-clockwise)
|
||||
* M5 - Spindle OFF
|
||||
*
|
||||
* Parameters:
|
||||
* S<power> - Set power. S0 will turn the spindle/laser off, except in relative mode.
|
||||
* O<ocr> - Set power and OCR (oscillator count register)
|
||||
* S<power> - Set power. S0 will turn the spindle/laser off.
|
||||
*
|
||||
* If no PWM pin is defined then M3/M4 just turns it on.
|
||||
* If no PWM pin is defined then M3/M4 just turns it on or off.
|
||||
*
|
||||
* At least 12.8KHz (50Hz * 256) is needed for Spindle PWM.
|
||||
* At least 12.8kHz (50Hz * 256) is needed for Spindle PWM.
|
||||
* Hardware PWM is required on AVR. ISRs are too slow.
|
||||
*
|
||||
* NOTE: WGM for timers 3, 4, and 5 must be either Mode 1 or Mode 5.
|
||||
@@ -66,75 +76,81 @@
|
||||
* PWM duty cycle goes from 0 (off) to 255 (always on).
|
||||
*/
|
||||
void GcodeSuite::M3_M4(const bool is_M4) {
|
||||
auto get_s_power = [] {
|
||||
if (parser.seenval('S')) {
|
||||
const float spwr = parser.value_float();
|
||||
#if ENABLED(SPINDLE_SERVO)
|
||||
cutter.unitPower = spwr;
|
||||
#else
|
||||
cutter.unitPower = TERN(SPINDLE_LASER_USE_PWM,
|
||||
cutter.power_to_range(cutter_power_t(round(spwr))),
|
||||
spwr > 0 ? 255 : 0);
|
||||
#endif
|
||||
#if LASER_SAFETY_TIMEOUT_MS > 0
|
||||
reset_stepper_timeout(); // Reset timeout to allow subsequent G-code to power the laser (imm.)
|
||||
#endif
|
||||
|
||||
if (cutter.cutter_mode == CUTTER_MODE_STANDARD)
|
||||
planner.synchronize(); // Wait for previous movement commands (G0/G1/G2/G3) to complete before changing power
|
||||
|
||||
#if ENABLED(LASER_FEATURE)
|
||||
if (parser.seen_test('I')) {
|
||||
cutter.cutter_mode = is_M4 ? CUTTER_MODE_DYNAMIC : CUTTER_MODE_CONTINUOUS;
|
||||
cutter.inline_power(0);
|
||||
cutter.set_enabled(true);
|
||||
}
|
||||
else
|
||||
cutter.unitPower = cutter.cpwr_to_upwr(SPEED_POWER_STARTUP);
|
||||
return cutter.unitPower;
|
||||
#endif
|
||||
|
||||
auto get_s_power = [] {
|
||||
float u;
|
||||
if (parser.seenval('S')) {
|
||||
const float v = parser.value_float();
|
||||
u = TERN(LASER_POWER_TRAP, v, cutter.power_to_range(v));
|
||||
}
|
||||
else if (cutter.cutter_mode == CUTTER_MODE_STANDARD)
|
||||
u = cutter.cpwr_to_upwr(SPEED_POWER_STARTUP);
|
||||
|
||||
cutter.menuPower = cutter.unitPower = u;
|
||||
|
||||
// PWM not implied, power converted to OCR from unit definition and on/off if not PWM.
|
||||
cutter.power = TERN(SPINDLE_LASER_USE_PWM, cutter.upower_to_ocr(u), u > 0 ? 255 : 0);
|
||||
return u;
|
||||
};
|
||||
|
||||
#if ENABLED(LASER_POWER_INLINE)
|
||||
if (parser.seen('I') == DISABLED(LASER_POWER_INLINE_INVERT)) {
|
||||
// Laser power in inline mode
|
||||
cutter.inline_direction(is_M4); // Should always be unused
|
||||
#if ENABLED(SPINDLE_LASER_USE_PWM)
|
||||
if (parser.seen('O')) {
|
||||
cutter.unitPower = cutter.power_to_range(parser.value_byte(), 0);
|
||||
cutter.inline_ocr_power(cutter.unitPower); // The OCR is a value from 0 to 255 (uint8_t)
|
||||
}
|
||||
else
|
||||
cutter.inline_power(cutter.upower_to_ocr(get_s_power()));
|
||||
if (cutter.cutter_mode == CUTTER_MODE_CONTINUOUS || cutter.cutter_mode == CUTTER_MODE_DYNAMIC) { // Laser power in inline mode
|
||||
#if ENABLED(LASER_FEATURE)
|
||||
planner.laser_inline.status.isPowered = true; // M3 or M4 is powered either way
|
||||
get_s_power(); // Update cutter.power if seen
|
||||
#if ENABLED(LASER_POWER_SYNC)
|
||||
// With power sync we only set power so it does not effect queued inline power sets
|
||||
planner.buffer_sync_block(BLOCK_BIT_LASER_PWR); // Send the flag, queueing inline power
|
||||
#else
|
||||
cutter.set_inline_enabled(true);
|
||||
planner.synchronize();
|
||||
cutter.inline_power(cutter.power);
|
||||
#endif
|
||||
return;
|
||||
}
|
||||
// Non-inline, standard case
|
||||
cutter.inline_disable(); // Prevent future blocks re-setting the power
|
||||
#endif
|
||||
|
||||
planner.synchronize(); // Wait for previous movement commands (G0/G0/G2/G3) to complete before changing power
|
||||
cutter.set_reverse(is_M4);
|
||||
|
||||
#if ENABLED(SPINDLE_LASER_USE_PWM)
|
||||
if (parser.seenval('O')) {
|
||||
cutter.unitPower = cutter.power_to_range(parser.value_byte(), 0);
|
||||
cutter.ocr_set_power(cutter.unitPower); // The OCR is a value from 0 to 255 (uint8_t)
|
||||
}
|
||||
else
|
||||
cutter.set_power(cutter.upower_to_ocr(get_s_power()));
|
||||
#elif ENABLED(SPINDLE_SERVO)
|
||||
cutter.set_power(get_s_power());
|
||||
#else
|
||||
#endif
|
||||
}
|
||||
else {
|
||||
cutter.set_enabled(true);
|
||||
#endif
|
||||
cutter.menuPower = cutter.unitPower;
|
||||
get_s_power();
|
||||
cutter.apply_power(
|
||||
#if ENABLED(SPINDLE_SERVO)
|
||||
cutter.unitPower
|
||||
#elif ENABLED(SPINDLE_LASER_USE_PWM)
|
||||
cutter.upower_to_ocr(cutter.unitPower)
|
||||
#else
|
||||
cutter.unitPower > 0 ? 255 : 0
|
||||
#endif
|
||||
);
|
||||
TERN_(SPINDLE_CHANGE_DIR, cutter.set_reverse(is_M4));
|
||||
}
|
||||
}
|
||||
|
||||
/**
|
||||
* M5 - Cutter OFF (when moves are complete)
|
||||
*/
|
||||
void GcodeSuite::M5() {
|
||||
#if ENABLED(LASER_POWER_INLINE)
|
||||
if (parser.seen('I') == DISABLED(LASER_POWER_INLINE_INVERT)) {
|
||||
cutter.set_inline_enabled(false); // Laser power in inline mode
|
||||
return;
|
||||
}
|
||||
// Non-inline, standard case
|
||||
cutter.inline_disable(); // Prevent future blocks re-setting the power
|
||||
#endif
|
||||
planner.synchronize();
|
||||
cutter.set_enabled(false);
|
||||
cutter.menuPower = cutter.unitPower;
|
||||
cutter.power = 0;
|
||||
cutter.apply_power(0); // M5 just kills power, leaving inline mode unchanged
|
||||
if (cutter.cutter_mode != CUTTER_MODE_STANDARD) {
|
||||
if (parser.seen_test('I')) {
|
||||
TERN_(LASER_FEATURE, cutter.inline_power(cutter.power));
|
||||
cutter.set_enabled(false); // Needs to happen while we are in inline mode to clear inline power.
|
||||
cutter.cutter_mode = CUTTER_MODE_STANDARD; // Switch from inline to standard mode.
|
||||
}
|
||||
}
|
||||
cutter.set_enabled(false); // Disable enable output setting
|
||||
}
|
||||
|
||||
#endif // HAS_CUTTER
|
||||
|
@@ -27,35 +27,45 @@
|
||||
#include "../gcode.h"
|
||||
#include "../../module/stepper.h"
|
||||
|
||||
#if NUM_AXES == XYZ && EXTRUDERS >= 1
|
||||
#define HAS_M350_B_PARAM 1 // "5th axis" (after E0) for an original XYZEB setup.
|
||||
#if AXIS_COLLISION('B')
|
||||
#error "M350 parameter 'B' collision with axis name."
|
||||
#endif
|
||||
#endif
|
||||
|
||||
/**
|
||||
* M350: Set axis microstepping modes. S sets mode for all drivers.
|
||||
*
|
||||
* Warning: Steps-per-unit remains unchanged.
|
||||
*/
|
||||
void GcodeSuite::M350() {
|
||||
if (parser.seen('S')) LOOP_LE_N(i, 4) stepper.microstep_mode(i, parser.value_byte());
|
||||
LOOP_LOGICAL_AXES(i) if (parser.seen(axis_codes[i])) stepper.microstep_mode(i, parser.value_byte());
|
||||
if (parser.seen('B')) stepper.microstep_mode(4, parser.value_byte());
|
||||
if (parser.seen('S')) LOOP_DISTINCT_AXES(i) stepper.microstep_mode(i, parser.value_byte());
|
||||
LOOP_LOGICAL_AXES(i) if (parser.seenval(AXIS_CHAR(i))) stepper.microstep_mode(i, parser.value_byte());
|
||||
TERN_(HAS_M350_B_PARAM, if (parser.seenval('B')) stepper.microstep_mode(E_AXIS + 1, parser.value_byte()));
|
||||
stepper.microstep_readings();
|
||||
}
|
||||
|
||||
/**
|
||||
* M351: Toggle MS1 MS2 pins directly with axis codes X Y Z E B
|
||||
* M351: Toggle MS1 MS2 pins directly with axis codes X Y Z . . . E [B]
|
||||
* S# determines MS1, MS2 or MS3, X# sets the pin high/low.
|
||||
*
|
||||
* Parameter 'B' sets "5th axis" (after E0) only for an original XYZEB setup.
|
||||
*/
|
||||
void GcodeSuite::M351() {
|
||||
const int8_t bval = TERN(HAS_M350_B_PARAM, parser.byteval('B', -1), -1); UNUSED(bval);
|
||||
if (parser.seenval('S')) switch (parser.value_byte()) {
|
||||
case 1:
|
||||
LOOP_LOGICAL_AXES(i) if (parser.seenval(axis_codes[i])) stepper.microstep_ms(i, parser.value_byte(), -1, -1);
|
||||
if (parser.seenval('B')) stepper.microstep_ms(4, parser.value_byte(), -1, -1);
|
||||
LOOP_LOGICAL_AXES(i) if (parser.seenval(AXIS_CHAR(i))) stepper.microstep_ms(i, parser.value_byte(), -1, -1);
|
||||
TERN_(HAS_M350_B_PARAM, if (bval >= 0) stepper.microstep_ms(E_AXIS + 1, bval != 0, -1, -1));
|
||||
break;
|
||||
case 2:
|
||||
LOOP_LOGICAL_AXES(i) if (parser.seenval(axis_codes[i])) stepper.microstep_ms(i, -1, parser.value_byte(), -1);
|
||||
if (parser.seenval('B')) stepper.microstep_ms(4, -1, parser.value_byte(), -1);
|
||||
LOOP_LOGICAL_AXES(i) if (parser.seenval(AXIS_CHAR(i))) stepper.microstep_ms(i, -1, parser.value_byte(), -1);
|
||||
TERN_(HAS_M350_B_PARAM, if (bval >= 0) stepper.microstep_ms(E_AXIS + 1, -1, bval != 0, -1));
|
||||
break;
|
||||
case 3:
|
||||
LOOP_LOGICAL_AXES(i) if (parser.seenval(axis_codes[i])) stepper.microstep_ms(i, -1, -1, parser.value_byte());
|
||||
if (parser.seenval('B')) stepper.microstep_ms(4, -1, -1, parser.value_byte());
|
||||
LOOP_LOGICAL_AXES(i) if (parser.seenval(AXIS_CHAR(i))) stepper.microstep_ms(i, -1, -1, parser.value_byte());
|
||||
TERN_(HAS_M350_B_PARAM, if (bval >= 0) stepper.microstep_ms(E_AXIS + 1, -1, -1, bval != 0));
|
||||
break;
|
||||
}
|
||||
stepper.microstep_readings();
|
||||
|
@@ -37,7 +37,7 @@ void GcodeSuite::M380() {
|
||||
#if ENABLED(MANUAL_SOLENOID_CONTROL)
|
||||
enable_solenoid(parser.intval('S', active_extruder));
|
||||
#else
|
||||
enable_solenoid_on_active_extruder();
|
||||
enable_solenoid(active_extruder);
|
||||
#endif
|
||||
}
|
||||
|
||||
|
@@ -21,7 +21,7 @@
|
||||
*/
|
||||
|
||||
#include "../gcode.h"
|
||||
#include "../../module/stepper.h"
|
||||
#include "../../module/planner.h"
|
||||
|
||||
/**
|
||||
* M400: Finish all moves
|
||||
|
@@ -52,7 +52,7 @@ void protected_pin_err() {
|
||||
* S<byte> Pin status from 0 - 255
|
||||
* I Flag to ignore Marlin's pin protection
|
||||
*
|
||||
* M<mode> Pin mode: 0=INPUT 1=OUTPUT 2=INPUT_PULLUP 3=INPUT_PULLDOWN
|
||||
* T<mode> Pin mode: 0=INPUT 1=OUTPUT 2=INPUT_PULLUP 3=INPUT_PULLDOWN
|
||||
*/
|
||||
void GcodeSuite::M42() {
|
||||
const int pin_index = PARSED_PIN_INDEX('P', GET_PIN_MAP_INDEX(LED_PIN));
|
||||
@@ -63,7 +63,7 @@ void GcodeSuite::M42() {
|
||||
if (!parser.boolval('I') && pin_is_protected(pin)) return protected_pin_err();
|
||||
|
||||
bool avoidWrite = false;
|
||||
if (parser.seenval('M')) {
|
||||
if (parser.seenval('T')) {
|
||||
switch (parser.value_byte()) {
|
||||
case 0: pinMode(pin, INPUT); avoidWrite = true; break;
|
||||
case 1: pinMode(pin, OUTPUT); break;
|
||||
@@ -126,10 +126,10 @@ void GcodeSuite::M42() {
|
||||
extDigitalWrite(pin, pin_status);
|
||||
|
||||
#ifdef ARDUINO_ARCH_STM32
|
||||
// A simple I/O will be set to 0 by analogWrite()
|
||||
// A simple I/O will be set to 0 by hal.set_pwm_duty()
|
||||
if (pin_status <= 1 && !PWM_PIN(pin)) return;
|
||||
#endif
|
||||
analogWrite(pin, pin_status);
|
||||
hal.set_pwm_duty(pin, pin_status);
|
||||
}
|
||||
|
||||
#endif // DIRECT_PIN_CONTROL
|
||||
|
@@ -28,7 +28,6 @@
|
||||
|
||||
#include "../gcode.h"
|
||||
#include "../../module/motion.h"
|
||||
#include "../../module/stepper.h"
|
||||
#include "../../module/tool_change.h"
|
||||
#include "../../module/planner.h"
|
||||
|
||||
@@ -64,7 +63,7 @@
|
||||
void GcodeSuite::M605() {
|
||||
planner.synchronize();
|
||||
|
||||
if (parser.seen('S')) {
|
||||
if (parser.seenval('S')) {
|
||||
const DualXMode previous_mode = dual_x_carriage_mode;
|
||||
|
||||
dual_x_carriage_mode = (DualXMode)parser.value_byte();
|
||||
@@ -78,8 +77,8 @@
|
||||
|
||||
case DXC_DUPLICATION_MODE:
|
||||
// Set the X offset, but no less than the safety gap
|
||||
if (parser.seen('X')) duplicate_extruder_x_offset = _MAX(parser.value_linear_units(), (X2_MIN_POS) - (X1_MIN_POS));
|
||||
if (parser.seen('R')) duplicate_extruder_temp_offset = parser.value_celsius_diff();
|
||||
if (parser.seenval('X')) duplicate_extruder_x_offset = _MAX(parser.value_linear_units(), (X2_MIN_POS) - (X1_MIN_POS));
|
||||
if (parser.seenval('R')) duplicate_extruder_temp_offset = parser.value_celsius_diff();
|
||||
// Always switch back to tool 0
|
||||
if (active_extruder != 0) tool_change(0);
|
||||
break;
|
||||
@@ -110,7 +109,7 @@
|
||||
set_duplication_enabled(false);
|
||||
|
||||
#ifdef EVENT_GCODE_IDEX_AFTER_MODECHANGE
|
||||
gcode.process_subcommands_now_P(PSTR(EVENT_GCODE_IDEX_AFTER_MODECHANGE));
|
||||
process_subcommands_now(F(EVENT_GCODE_IDEX_AFTER_MODECHANGE));
|
||||
#endif
|
||||
}
|
||||
else if (!parser.seen('W')) // if no S or W parameter, the DXC mode gets reset to the user's default
|
||||
@@ -146,7 +145,7 @@
|
||||
|
||||
HOTEND_LOOP() {
|
||||
DEBUG_ECHOPGM_P(SP_T_STR, e);
|
||||
LOOP_LINEAR_AXES(a) DEBUG_ECHOPGM(" hotend_offset[", e, "].", AS_CHAR(AXIS_CHAR(a) | 0x20), "=", hotend_offset[e][a]);
|
||||
LOOP_NUM_AXES(a) DEBUG_ECHOPGM(" hotend_offset[", e, "].", AS_CHAR(AXIS_CHAR(a) | 0x20), "=", hotend_offset[e][a]);
|
||||
DEBUG_EOL();
|
||||
}
|
||||
DEBUG_EOL();
|
||||
|
@@ -25,7 +25,7 @@
|
||||
#include "../../module/temperature.h"
|
||||
#include "../../module/planner.h" // for planner.finish_and_disable
|
||||
#include "../../module/printcounter.h" // for print_job_timer.stop
|
||||
#include "../../lcd/marlinui.h" // for LCD_MESSAGEPGM_P
|
||||
#include "../../lcd/marlinui.h" // for LCD_MESSAGE_F
|
||||
|
||||
#include "../../inc/MarlinConfig.h"
|
||||
|
||||
@@ -54,7 +54,7 @@
|
||||
|
||||
// S: Report the current power supply state and exit
|
||||
if (parser.seen('S')) {
|
||||
SERIAL_ECHOPGM_P(powerManager.psu_on ? PSTR("PS:1\n") : PSTR("PS:0\n"));
|
||||
SERIAL_ECHOF(powerManager.psu_on ? F("PS:1\n") : F("PS:0\n"));
|
||||
return;
|
||||
}
|
||||
|
||||
@@ -75,7 +75,7 @@
|
||||
#endif
|
||||
// PATCH END: Knutwurst
|
||||
|
||||
TERN_(HAS_LCD_MENU, ui.reset_status());
|
||||
TERN_(HAS_MARLINUI_MENU, ui.reset_status());
|
||||
}
|
||||
|
||||
#endif // PSU_CONTROL
|
||||
@@ -86,26 +86,47 @@
|
||||
* This code should ALWAYS be available for FULL SHUTDOWN!
|
||||
*/
|
||||
void GcodeSuite::M81() {
|
||||
thermalManager.disable_all_heaters();
|
||||
planner.finish_and_disable();
|
||||
thermalManager.cooldown();
|
||||
|
||||
print_job_timer.stop();
|
||||
|
||||
#if HAS_FAN
|
||||
thermalManager.zero_fan_speeds();
|
||||
#if ENABLED(PROBING_FANS_OFF)
|
||||
thermalManager.fans_paused = false;
|
||||
ZERO(thermalManager.saved_fan_speed);
|
||||
#endif
|
||||
#if BOTH(HAS_FAN, PROBING_FANS_OFF)
|
||||
thermalManager.fans_paused = false;
|
||||
ZERO(thermalManager.saved_fan_speed);
|
||||
#endif
|
||||
|
||||
safe_delay(1000); // Wait 1 second before switching off
|
||||
|
||||
LCD_MESSAGE_F(MACHINE_NAME " " STR_OFF ".");
|
||||
|
||||
bool delayed_power_off = false;
|
||||
|
||||
#if ENABLED(POWER_OFF_TIMER)
|
||||
if (parser.seenval('D')) {
|
||||
uint16_t delay = parser.value_ushort();
|
||||
if (delay > 1) { // skip already observed 1s delay
|
||||
delayed_power_off = true;
|
||||
powerManager.setPowerOffTimer(SEC_TO_MS(delay - 1));
|
||||
}
|
||||
}
|
||||
#endif
|
||||
|
||||
#if ENABLED(POWER_OFF_WAIT_FOR_COOLDOWN)
|
||||
if (parser.boolval('S')) {
|
||||
delayed_power_off = true;
|
||||
powerManager.setPowerOffOnCooldown(true);
|
||||
}
|
||||
#endif
|
||||
|
||||
if (delayed_power_off) {
|
||||
SERIAL_ECHOLNPGM(STR_DELAYED_POWEROFF);
|
||||
return;
|
||||
}
|
||||
|
||||
#if HAS_SUICIDE
|
||||
suicide();
|
||||
#elif ENABLED(PSU_CONTROL)
|
||||
powerManager.power_off_soon();
|
||||
#endif
|
||||
|
||||
LCD_MESSAGEPGM_P(PSTR(MACHINE_NAME " " STR_OFF "."));
|
||||
}
|
||||
|
@@ -29,7 +29,14 @@ void GcodeSuite::M85() {
|
||||
|
||||
if (parser.seen('S')) {
|
||||
reset_stepper_timeout();
|
||||
max_inactive_time = parser.value_millis_from_seconds();
|
||||
const millis_t ms = parser.value_millis_from_seconds();
|
||||
#if LASER_SAFETY_TIMEOUT_MS > 0
|
||||
if (ms && ms <= LASER_SAFETY_TIMEOUT_MS) {
|
||||
SERIAL_ECHO_MSG("M85 timeout must be > ", MS_TO_SEC(LASER_SAFETY_TIMEOUT_MS + 999), " s for laser safety.");
|
||||
return;
|
||||
}
|
||||
#endif
|
||||
max_inactive_time = ms;
|
||||
}
|
||||
|
||||
}
|
||||
|
@@ -24,8 +24,8 @@
|
||||
|
||||
#if ENABLED(PLATFORM_M997_SUPPORT)
|
||||
|
||||
#if ENABLED(DWIN_CREALITY_LCD_ENHANCED)
|
||||
#include "../../lcd/e3v2/enhanced/dwin.h"
|
||||
#if ENABLED(DWIN_LCD_PROUI)
|
||||
#include "../../lcd/e3v2/proui/dwin.h"
|
||||
#endif
|
||||
|
||||
/**
|
||||
@@ -33,7 +33,7 @@
|
||||
*/
|
||||
void GcodeSuite::M997() {
|
||||
|
||||
TERN_(DWIN_CREALITY_LCD_ENHANCED, DWIN_RebootScreen());
|
||||
TERN_(DWIN_LCD_PROUI, DWIN_RebootScreen());
|
||||
|
||||
flashFirmware(parser.intval('S'));
|
||||
|
||||
|
@@ -22,7 +22,7 @@
|
||||
|
||||
#include "../gcode.h"
|
||||
|
||||
#include "../../lcd/marlinui.h" // for lcd_reset_alert_level
|
||||
#include "../../lcd/marlinui.h" // for ui.reset_alert_level
|
||||
#include "../../MarlinCore.h" // for marlin_state
|
||||
#include "../queue.h" // for flush_and_request_resend
|
||||
|
||||
|
@@ -25,6 +25,11 @@
|
||||
#include "../../core/serial.h"
|
||||
#include "../../inc/MarlinConfig.h"
|
||||
|
||||
#if ENABLED(CONFIGURATION_EMBEDDING)
|
||||
#include "../../sd/SdBaseFile.h"
|
||||
#include "../../mczip.h"
|
||||
#endif
|
||||
|
||||
/**
|
||||
* M500: Store settings in EEPROM
|
||||
*/
|
||||
@@ -50,9 +55,24 @@ void GcodeSuite::M502() {
|
||||
|
||||
/**
|
||||
* M503: print settings currently in memory
|
||||
*
|
||||
* S<bool> : Include / exclude header comments in the output. (Default: S1)
|
||||
*
|
||||
* With CONFIGURATION_EMBEDDING:
|
||||
* C<flag> : Save the full Marlin configuration to SD Card as "mc.zip"
|
||||
*/
|
||||
void GcodeSuite::M503() {
|
||||
(void)settings.report(!parser.boolval('S', true));
|
||||
|
||||
#if ENABLED(CONFIGURATION_EMBEDDING)
|
||||
if (parser.seen_test('C')) {
|
||||
SdBaseFile file;
|
||||
const uint16_t size = sizeof(mc_zip);
|
||||
// Need to create the config size on the SD card
|
||||
if (file.open("mc.zip", O_WRITE|O_CREAT) && file.write(pgm_read_ptr(mc_zip), size) != -1 && file.close())
|
||||
SERIAL_ECHO_MSG("Configuration saved as 'mc.zip'");
|
||||
}
|
||||
#endif
|
||||
}
|
||||
|
||||
#endif // !DISABLE_M503
|
||||
|
@@ -1,151 +0,0 @@
|
||||
/**
|
||||
* Marlin 3D Printer Firmware
|
||||
* Copyright (c) 2020 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 <https://www.gnu.org/licenses/>.
|
||||
*
|
||||
*/
|
||||
|
||||
#include "../../../inc/MarlinConfig.h"
|
||||
|
||||
#if HAS_L64XX
|
||||
|
||||
#include "../../gcode.h"
|
||||
#include "../../../libs/L64XX/L64XX_Marlin.h"
|
||||
#include "../../../module/stepper/indirection.h"
|
||||
|
||||
void echo_yes_no(const bool yes);
|
||||
|
||||
inline void L6470_say_status(const L64XX_axis_t axis) {
|
||||
if (L64xxManager.spi_abort) return;
|
||||
const L64XX_Marlin::L64XX_shadow_t &sh = L64xxManager.shadow;
|
||||
L64xxManager.get_status(axis);
|
||||
L64xxManager.say_axis(axis);
|
||||
#if ENABLED(L6470_CHITCHAT)
|
||||
char temp_buf[20];
|
||||
sprintf_P(temp_buf, PSTR(" status: %4x "), sh.STATUS_AXIS_RAW);
|
||||
SERIAL_ECHO(temp_buf);
|
||||
print_bin(sh.STATUS_AXIS_RAW);
|
||||
switch (sh.STATUS_AXIS_LAYOUT) {
|
||||
case L6470_STATUS_LAYOUT: SERIAL_ECHOPGM(" L6470"); break;
|
||||
case L6474_STATUS_LAYOUT: SERIAL_ECHOPGM(" L6474"); break;
|
||||
case L6480_STATUS_LAYOUT: SERIAL_ECHOPGM(" L6480/powerSTEP01"); break;
|
||||
}
|
||||
#endif
|
||||
SERIAL_ECHOPGM("\n...OUTPUT: ");
|
||||
SERIAL_ECHOPGM_P(sh.STATUS_AXIS & STATUS_HIZ ? PSTR("OFF") : PSTR("ON "));
|
||||
SERIAL_ECHOPGM(" BUSY: "); echo_yes_no((sh.STATUS_AXIS & STATUS_BUSY) == 0);
|
||||
SERIAL_ECHOPGM(" DIR: ");
|
||||
SERIAL_ECHOPGM_P((((sh.STATUS_AXIS & STATUS_DIR) >> 4) ^ L64xxManager.index_to_dir[axis]) ? PSTR("FORWARD") : PSTR("REVERSE"));
|
||||
if (sh.STATUS_AXIS_LAYOUT == L6480_STATUS_LAYOUT) {
|
||||
SERIAL_ECHOPGM(" Last Command: ");
|
||||
if (sh.STATUS_AXIS & sh.STATUS_AXIS_WRONG_CMD) SERIAL_ECHOPGM("VALID");
|
||||
else SERIAL_ECHOPGM("ERROR");
|
||||
SERIAL_ECHOPGM("\n...THERMAL: ");
|
||||
switch ((sh.STATUS_AXIS & (sh.STATUS_AXIS_TH_SD | sh.STATUS_AXIS_TH_WRN)) >> 11) {
|
||||
case 0: SERIAL_ECHOPGM("DEVICE SHUTDOWN"); break;
|
||||
case 1: SERIAL_ECHOPGM("BRIDGE SHUTDOWN"); break;
|
||||
case 2: SERIAL_ECHOPGM("WARNING "); break;
|
||||
case 3: SERIAL_ECHOPGM("OK "); break;
|
||||
}
|
||||
}
|
||||
else {
|
||||
SERIAL_ECHOPGM(" Last Command: ");
|
||||
if (!(sh.STATUS_AXIS & sh.STATUS_AXIS_WRONG_CMD)) SERIAL_ECHOPGM("IN");
|
||||
SERIAL_ECHOPGM("VALID ");
|
||||
SERIAL_ECHOPGM_P(sh.STATUS_AXIS & sh.STATUS_AXIS_NOTPERF_CMD ? PSTR("COMPLETED ") : PSTR("Not PERFORMED"));
|
||||
SERIAL_ECHOPGM("\n...THERMAL: ", !(sh.STATUS_AXIS & sh.STATUS_AXIS_TH_SD) ? "SHUTDOWN " : !(sh.STATUS_AXIS & sh.STATUS_AXIS_TH_WRN) ? "WARNING " : "OK ");
|
||||
}
|
||||
SERIAL_ECHOPGM(" OVERCURRENT:"); echo_yes_no((sh.STATUS_AXIS & sh.STATUS_AXIS_OCD) == 0);
|
||||
if (sh.STATUS_AXIS_LAYOUT != L6474_STATUS_LAYOUT) {
|
||||
SERIAL_ECHOPGM(" STALL:"); echo_yes_no((sh.STATUS_AXIS & sh.STATUS_AXIS_STEP_LOSS_A) == 0 || (sh.STATUS_AXIS & sh.STATUS_AXIS_STEP_LOSS_B) == 0);
|
||||
SERIAL_ECHOPGM(" STEP-CLOCK MODE:"); echo_yes_no((sh.STATUS_AXIS & sh.STATUS_AXIS_SCK_MOD) != 0);
|
||||
}
|
||||
else {
|
||||
SERIAL_ECHOPGM(" STALL: NA "
|
||||
" STEP-CLOCK MODE: NA"
|
||||
" UNDER VOLTAGE LOCKOUT: "); echo_yes_no((sh.STATUS_AXIS & sh.STATUS_AXIS_UVLO) == 0);
|
||||
}
|
||||
SERIAL_EOL();
|
||||
}
|
||||
|
||||
/**
|
||||
* M122: Debug L6470 drivers
|
||||
*/
|
||||
void GcodeSuite::M122() {
|
||||
L64xxManager.pause_monitor(true); // Keep monitor_driver() from stealing status
|
||||
L64xxManager.spi_active = true; // Tell set_directions() a series of SPI transfers is underway
|
||||
|
||||
//if (parser.seen('S'))
|
||||
// tmc_set_report_interval(parser.value_bool());
|
||||
//else
|
||||
|
||||
#if AXIS_IS_L64XX(X)
|
||||
L6470_say_status(X);
|
||||
#endif
|
||||
#if AXIS_IS_L64XX(X2)
|
||||
L6470_say_status(X2);
|
||||
#endif
|
||||
#if AXIS_IS_L64XX(Y)
|
||||
L6470_say_status(Y);
|
||||
#endif
|
||||
#if AXIS_IS_L64XX(Y2)
|
||||
L6470_say_status(Y2);
|
||||
#endif
|
||||
#if AXIS_IS_L64XX(Z)
|
||||
L6470_say_status(Z);
|
||||
#endif
|
||||
#if AXIS_IS_L64XX(Z2)
|
||||
L6470_say_status(Z2);
|
||||
#endif
|
||||
#if AXIS_IS_L64XX(Z3)
|
||||
L6470_say_status(Z3);
|
||||
#endif
|
||||
#if AXIS_IS_L64XX(Z4)
|
||||
L6470_say_status(Z4);
|
||||
#endif
|
||||
#if AXIS_IS_L64XX(E0)
|
||||
L6470_say_status(E0);
|
||||
#endif
|
||||
#if AXIS_IS_L64XX(E1)
|
||||
L6470_say_status(E1);
|
||||
#endif
|
||||
#if AXIS_IS_L64XX(E2)
|
||||
L6470_say_status(E2);
|
||||
#endif
|
||||
#if AXIS_IS_L64XX(E3)
|
||||
L6470_say_status(E3);
|
||||
#endif
|
||||
#if AXIS_IS_L64XX(E4)
|
||||
L6470_say_status(E4);
|
||||
#endif
|
||||
#if AXIS_IS_L64XX(E5)
|
||||
L6470_say_status(E5);
|
||||
#endif
|
||||
#if AXIS_IS_L64XX(E6)
|
||||
L6470_say_status(E6);
|
||||
#endif
|
||||
#if AXIS_IS_L64XX(E7)
|
||||
L6470_say_status(E7);
|
||||
#endif
|
||||
|
||||
L64xxManager.spi_active = false; // done with all SPI transfers - clear handshake flags
|
||||
L64xxManager.spi_abort = false;
|
||||
L64xxManager.pause_monitor(false);
|
||||
}
|
||||
|
||||
#endif // HAS_L64XX
|
@@ -1,376 +0,0 @@
|
||||
/**
|
||||
* Marlin 3D Printer Firmware
|
||||
* Copyright (c) 2020 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 <https://www.gnu.org/licenses/>.
|
||||
*
|
||||
*/
|
||||
|
||||
#include "../../../inc/MarlinConfig.h"
|
||||
|
||||
#if HAS_L64XX
|
||||
|
||||
#include "../../gcode.h"
|
||||
#include "../../../libs/L64XX/L64XX_Marlin.h"
|
||||
#include "../../../module/stepper/indirection.h"
|
||||
#include "../../../module/planner.h"
|
||||
|
||||
#define DEBUG_OUT ENABLED(L6470_CHITCHAT)
|
||||
#include "../../../core/debug_out.h"
|
||||
|
||||
/**
|
||||
* MACRO to fetch information on the items associated with current limiting
|
||||
* and maximum voltage output.
|
||||
*
|
||||
* L6470 can be setup to shutdown if either current threshold is exceeded.
|
||||
*
|
||||
* L6470 output current can not be set directly. It is set indirectly by
|
||||
* setting the maximum effective output voltage.
|
||||
*
|
||||
* Effective output voltage is set by PWM duty cycle.
|
||||
*
|
||||
* Maximum effective output voltage is affected by MANY variables. The main ones are:
|
||||
* KVAL_HOLD
|
||||
* KVAL_RUN
|
||||
* KVAL_ACC
|
||||
* KVAL_DEC
|
||||
* Vs compensation (if enabled)
|
||||
*/
|
||||
void L64XX_report_current(L64XX &motor, const L64XX_axis_t axis) {
|
||||
|
||||
if (L64xxManager.spi_abort) return; // don't do anything if set_directions() has occurred
|
||||
|
||||
const L64XX_Marlin::L64XX_shadow_t &sh = L64xxManager.shadow;
|
||||
const uint16_t status = L64xxManager.get_status(axis); //also populates shadow structure
|
||||
const uint8_t OverCurrent_Threshold = uint8_t(motor.GetParam(L6470_OCD_TH));
|
||||
|
||||
auto say_axis_status = [](const L64XX_axis_t axis, const uint16_t status) {
|
||||
L64xxManager.say_axis(axis);
|
||||
#if ENABLED(L6470_CHITCHAT)
|
||||
char tmp[10];
|
||||
sprintf_P(tmp, PSTR("%4x "), status);
|
||||
DEBUG_ECHOPGM(" status: ", tmp);
|
||||
print_bin(status);
|
||||
#else
|
||||
UNUSED(status);
|
||||
#endif
|
||||
SERIAL_EOL();
|
||||
};
|
||||
|
||||
char temp_buf[10];
|
||||
|
||||
switch (sh.STATUS_AXIS_LAYOUT) {
|
||||
case L6470_STATUS_LAYOUT: // L6470
|
||||
case L6480_STATUS_LAYOUT: { // L6480 & powerstep01
|
||||
const uint16_t Stall_Threshold = (uint8_t)motor.GetParam(L6470_STALL_TH),
|
||||
motor_status = (status & (STATUS_MOT_STATUS)) >> 5,
|
||||
L6470_ADC_out = motor.GetParam(L6470_ADC_OUT),
|
||||
L6470_ADC_out_limited = constrain(L6470_ADC_out, 8, 24);
|
||||
const float comp_coef = 1600.0f / L6470_ADC_out_limited;
|
||||
const uint16_t MicroSteps = _BV(motor.GetParam(L6470_STEP_MODE) & 0x07);
|
||||
|
||||
say_axis_status(axis, sh.STATUS_AXIS_RAW);
|
||||
|
||||
SERIAL_ECHOPGM("...OverCurrent Threshold: ");
|
||||
sprintf_P(temp_buf, PSTR("%2d ("), OverCurrent_Threshold);
|
||||
SERIAL_ECHO(temp_buf);
|
||||
SERIAL_ECHO((OverCurrent_Threshold + 1) * motor.OCD_CURRENT_CONSTANT_INV);
|
||||
SERIAL_ECHOPGM(" mA)");
|
||||
SERIAL_ECHOPGM(" Stall Threshold: ");
|
||||
sprintf_P(temp_buf, PSTR("%2d ("), Stall_Threshold);
|
||||
SERIAL_ECHO(temp_buf);
|
||||
SERIAL_ECHO((Stall_Threshold + 1) * motor.STALL_CURRENT_CONSTANT_INV);
|
||||
SERIAL_ECHOPGM(" mA)");
|
||||
SERIAL_ECHOPGM(" Motor Status: ");
|
||||
switch (motor_status) {
|
||||
case 0: SERIAL_ECHOPGM("stopped"); break;
|
||||
case 1: SERIAL_ECHOPGM("accelerating"); break;
|
||||
case 2: SERIAL_ECHOPGM("decelerating"); break;
|
||||
case 3: SERIAL_ECHOPGM("at constant speed"); break;
|
||||
}
|
||||
SERIAL_EOL();
|
||||
|
||||
SERIAL_ECHOPGM("...MicroSteps: ", MicroSteps,
|
||||
" ADC_OUT: ", L6470_ADC_out);
|
||||
SERIAL_ECHOPGM(" Vs_compensation: ");
|
||||
SERIAL_ECHOPGM_P((motor.GetParam(sh.L6470_AXIS_CONFIG) & CONFIG_EN_VSCOMP) ? PSTR("ENABLED ") : PSTR("DISABLED"));
|
||||
SERIAL_ECHOLNPGM(" Compensation coefficient: ~", comp_coef * 0.01f);
|
||||
|
||||
SERIAL_ECHOPGM("...KVAL_HOLD: ", motor.GetParam(L6470_KVAL_HOLD),
|
||||
" KVAL_RUN : ", motor.GetParam(L6470_KVAL_RUN),
|
||||
" KVAL_ACC: ", motor.GetParam(L6470_KVAL_ACC),
|
||||
" KVAL_DEC: ", motor.GetParam(L6470_KVAL_DEC),
|
||||
" V motor max = ");
|
||||
switch (motor_status) {
|
||||
case 0: SERIAL_ECHO(motor.GetParam(L6470_KVAL_HOLD) * 100 / 256); SERIAL_ECHOPGM("% (KVAL_HOLD)"); break;
|
||||
case 1: SERIAL_ECHO(motor.GetParam(L6470_KVAL_RUN) * 100 / 256); SERIAL_ECHOPGM("% (KVAL_RUN)"); break;
|
||||
case 2: SERIAL_ECHO(motor.GetParam(L6470_KVAL_ACC) * 100 / 256); SERIAL_ECHOPGM("% (KVAL_ACC)"); break;
|
||||
case 3: SERIAL_ECHO(motor.GetParam(L6470_KVAL_DEC) * 100 / 256); SERIAL_ECHOPGM("% (KVAL_HOLD)"); break;
|
||||
}
|
||||
SERIAL_EOL();
|
||||
|
||||
#if ENABLED(L6470_CHITCHAT)
|
||||
DEBUG_ECHOPGM("...SLEW RATE: ");
|
||||
switch (sh.STATUS_AXIS_LAYOUT) {
|
||||
case L6470_STATUS_LAYOUT: {
|
||||
switch ((motor.GetParam(sh.L6470_AXIS_CONFIG) & CONFIG_POW_SR) >> CONFIG_POW_SR_BIT) {
|
||||
case 0: { DEBUG_ECHOLNPGM("320V/uS") ; break; }
|
||||
case 1: { DEBUG_ECHOLNPGM("75V/uS") ; break; }
|
||||
case 2: { DEBUG_ECHOLNPGM("110V/uS") ; break; }
|
||||
case 3: { DEBUG_ECHOLNPGM("260V/uS") ; break; }
|
||||
}
|
||||
break;
|
||||
}
|
||||
case L6480_STATUS_LAYOUT: {
|
||||
switch (motor.GetParam(L6470_GATECFG1) & CONFIG1_SR ) {
|
||||
case CONFIG1_SR_220V_us: { DEBUG_ECHOLNPGM("220V/uS") ; break; }
|
||||
case CONFIG1_SR_400V_us: { DEBUG_ECHOLNPGM("400V/uS") ; break; }
|
||||
case CONFIG1_SR_520V_us: { DEBUG_ECHOLNPGM("520V/uS") ; break; }
|
||||
case CONFIG1_SR_980V_us: { DEBUG_ECHOLNPGM("980V/uS") ; break; }
|
||||
default: { DEBUG_ECHOLNPGM("unknown") ; break; }
|
||||
}
|
||||
}
|
||||
}
|
||||
#endif
|
||||
SERIAL_EOL();
|
||||
break;
|
||||
}
|
||||
|
||||
case L6474_STATUS_LAYOUT: { // L6474
|
||||
const uint16_t L6470_ADC_out = motor.GetParam(L6470_ADC_OUT) & 0x1F,
|
||||
L6474_TVAL_val = motor.GetParam(L6474_TVAL) & 0x7F;
|
||||
|
||||
say_axis_status(axis, sh.STATUS_AXIS_RAW);
|
||||
|
||||
SERIAL_ECHOPGM("...OverCurrent Threshold: ");
|
||||
sprintf_P(temp_buf, PSTR("%2d ("), OverCurrent_Threshold);
|
||||
SERIAL_ECHO(temp_buf);
|
||||
SERIAL_ECHO((OverCurrent_Threshold + 1) * motor.OCD_CURRENT_CONSTANT_INV);
|
||||
SERIAL_ECHOPGM(" mA)");
|
||||
SERIAL_ECHOPGM(" TVAL: ");
|
||||
sprintf_P(temp_buf, PSTR("%2d ("), L6474_TVAL_val);
|
||||
SERIAL_ECHO(temp_buf);
|
||||
SERIAL_ECHO((L6474_TVAL_val + 1) * motor.STALL_CURRENT_CONSTANT_INV);
|
||||
SERIAL_ECHOLNPGM(" mA) Motor Status: NA");
|
||||
|
||||
const uint16_t MicroSteps = _BV(motor.GetParam(L6470_STEP_MODE) & 0x07); //NOMORE(MicroSteps, 16);
|
||||
SERIAL_ECHOPGM("...MicroSteps: ", MicroSteps,
|
||||
" ADC_OUT: ", L6470_ADC_out);
|
||||
|
||||
SERIAL_ECHOLNPGM(" Vs_compensation: NA\n");
|
||||
SERIAL_ECHOLNPGM("...KVAL_HOLD: NA"
|
||||
" KVAL_RUN : NA"
|
||||
" KVAL_ACC: NA"
|
||||
" KVAL_DEC: NA"
|
||||
" V motor max = NA");
|
||||
|
||||
#if ENABLED(L6470_CHITCHAT)
|
||||
DEBUG_ECHOPGM("...SLEW RATE: ");
|
||||
switch ((motor.GetParam(sh.L6470_AXIS_CONFIG) & CONFIG_POW_SR) >> CONFIG_POW_SR_BIT) {
|
||||
case 0: DEBUG_ECHOLNPGM("320V/uS") ; break;
|
||||
case 1: DEBUG_ECHOLNPGM("75V/uS") ; break;
|
||||
case 2: DEBUG_ECHOLNPGM("110V/uS") ; break;
|
||||
case 3: DEBUG_ECHOLNPGM("260V/uS") ; break;
|
||||
default: DEBUG_ECHOLNPGM("slew rate: ", (motor.GetParam(sh.L6470_AXIS_CONFIG) & CONFIG_POW_SR) >> CONFIG_POW_SR_BIT); break;
|
||||
}
|
||||
#endif
|
||||
SERIAL_EOL();
|
||||
SERIAL_EOL();
|
||||
break;
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
/**
|
||||
* M906: report or set KVAL_HOLD which sets the maximum effective voltage provided by the
|
||||
* PWMs to the steppers
|
||||
*
|
||||
* On L6474 this sets the TVAL register (same address).
|
||||
*
|
||||
* I - select which driver(s) to change on multi-driver axis
|
||||
* 0 - (default) all drivers on the axis or E0
|
||||
* 1 - monitor only X, Y, Z or E1
|
||||
* 2 - monitor only X2, Y2, Z2 or E2
|
||||
* 3 - monitor only Z3 or E3
|
||||
* 4 - monitor only Z4 or E4
|
||||
* 5 - monitor only E5
|
||||
* Xxxx, Yxxx, Zxxx, Exxx - axis to change (optional)
|
||||
* L6474 - current in mA (4A max)
|
||||
* All others - 0-255
|
||||
*
|
||||
* Sets KVAL_HOLD which affects the current being driven through the stepper.
|
||||
*
|
||||
* L6470 is used in the STEP-CLOCK mode. KVAL_HOLD is the only KVAL_xxx
|
||||
* that affects the effective voltage seen by the stepper.
|
||||
*/
|
||||
void GcodeSuite::M906() {
|
||||
|
||||
L64xxManager.pause_monitor(true); // Keep monitor_driver() from stealing status
|
||||
|
||||
#define L6470_SET_KVAL_HOLD(Q) (AXIS_IS_L64XX(Q) ? stepper##Q.setTVALCurrent(value) : stepper##Q.SetParam(L6470_KVAL_HOLD, uint8_t(value)))
|
||||
|
||||
DEBUG_ECHOLNPGM("M906");
|
||||
|
||||
uint8_t report_current = true;
|
||||
|
||||
#if HAS_L64XX
|
||||
const uint8_t index = parser.byteval('I');
|
||||
#endif
|
||||
|
||||
LOOP_LOGICAL_AXES(i) if (uint16_t value = parser.intval(axis_codes[i])) {
|
||||
|
||||
report_current = false;
|
||||
|
||||
if (planner.has_blocks_queued() || planner.cleaning_buffer_counter) {
|
||||
SERIAL_ECHOLNPGM("Test aborted. Can't set KVAL_HOLD while steppers are moving.");
|
||||
return;
|
||||
}
|
||||
|
||||
switch (i) {
|
||||
case X_AXIS:
|
||||
#if AXIS_IS_L64XX(X)
|
||||
if (index == 0) L6470_SET_KVAL_HOLD(X);
|
||||
#endif
|
||||
#if AXIS_IS_L64XX(X2)
|
||||
if (index == 1) L6470_SET_KVAL_HOLD(X2);
|
||||
#endif
|
||||
break;
|
||||
|
||||
#if HAS_Y_AXIS
|
||||
case Y_AXIS:
|
||||
#if AXIS_IS_L64XX(Y)
|
||||
if (index == 0) L6470_SET_KVAL_HOLD(Y);
|
||||
#endif
|
||||
#if AXIS_IS_L64XX(Y2)
|
||||
if (index == 1) L6470_SET_KVAL_HOLD(Y2);
|
||||
#endif
|
||||
break;
|
||||
#endif
|
||||
|
||||
#if HAS_Z_AXIS
|
||||
case Z_AXIS:
|
||||
#if AXIS_IS_L64XX(Z)
|
||||
if (index == 0) L6470_SET_KVAL_HOLD(Z);
|
||||
#endif
|
||||
#if AXIS_IS_L64XX(Z2)
|
||||
if (index == 1) L6470_SET_KVAL_HOLD(Z2);
|
||||
#endif
|
||||
#if AXIS_IS_L64XX(Z3)
|
||||
if (index == 2) L6470_SET_KVAL_HOLD(Z3);
|
||||
#endif
|
||||
#if AXIS_DRIVER_TYPE_Z4(L6470)
|
||||
if (index == 3) L6470_SET_KVAL_HOLD(Z4);
|
||||
#endif
|
||||
break;
|
||||
#endif
|
||||
|
||||
#if E_STEPPERS
|
||||
case E_AXIS: {
|
||||
const int8_t target_e_stepper = get_target_e_stepper_from_command();
|
||||
if (target_e_stepper < 0) return;
|
||||
switch (target_e_stepper) {
|
||||
#if AXIS_IS_L64XX(E0)
|
||||
case 0: L6470_SET_KVAL_HOLD(E0); break;
|
||||
#endif
|
||||
#if AXIS_IS_L64XX(E1)
|
||||
case 1: L6470_SET_KVAL_HOLD(E1); break;
|
||||
#endif
|
||||
#if AXIS_IS_L64XX(E2)
|
||||
case 2: L6470_SET_KVAL_HOLD(E2); break;
|
||||
#endif
|
||||
#if AXIS_IS_L64XX(E3)
|
||||
case 3: L6470_SET_KVAL_HOLD(E3); break;
|
||||
#endif
|
||||
#if AXIS_IS_L64XX(E4)
|
||||
case 4: L6470_SET_KVAL_HOLD(E4); break;
|
||||
#endif
|
||||
#if AXIS_IS_L64XX(E5)
|
||||
case 5: L6470_SET_KVAL_HOLD(E5); break;
|
||||
#endif
|
||||
#if AXIS_IS_L64XX(E6)
|
||||
case 6: L6470_SET_KVAL_HOLD(E6); break;
|
||||
#endif
|
||||
#if AXIS_IS_L64XX(E7)
|
||||
case 7: L6470_SET_KVAL_HOLD(E7); break;
|
||||
#endif
|
||||
}
|
||||
} break;
|
||||
#endif
|
||||
}
|
||||
}
|
||||
|
||||
if (report_current) {
|
||||
#define L64XX_REPORT_CURRENT(Q) L64XX_report_current(stepper##Q, Q)
|
||||
|
||||
L64xxManager.spi_active = true; // Tell set_directions() a series of SPI transfers is underway
|
||||
|
||||
#if AXIS_IS_L64XX(X)
|
||||
L64XX_REPORT_CURRENT(X);
|
||||
#endif
|
||||
#if AXIS_IS_L64XX(X2)
|
||||
L64XX_REPORT_CURRENT(X2);
|
||||
#endif
|
||||
#if AXIS_IS_L64XX(Y)
|
||||
L64XX_REPORT_CURRENT(Y);
|
||||
#endif
|
||||
#if AXIS_IS_L64XX(Y2)
|
||||
L64XX_REPORT_CURRENT(Y2);
|
||||
#endif
|
||||
#if AXIS_IS_L64XX(Z)
|
||||
L64XX_REPORT_CURRENT(Z);
|
||||
#endif
|
||||
#if AXIS_IS_L64XX(Z2)
|
||||
L64XX_REPORT_CURRENT(Z2);
|
||||
#endif
|
||||
#if AXIS_IS_L64XX(Z3)
|
||||
L64XX_REPORT_CURRENT(Z3);
|
||||
#endif
|
||||
#if AXIS_IS_L64XX(Z4)
|
||||
L64XX_REPORT_CURRENT(Z4);
|
||||
#endif
|
||||
#if AXIS_IS_L64XX(E0)
|
||||
L64XX_REPORT_CURRENT(E0);
|
||||
#endif
|
||||
#if AXIS_IS_L64XX(E1)
|
||||
L64XX_REPORT_CURRENT(E1);
|
||||
#endif
|
||||
#if AXIS_IS_L64XX(E2)
|
||||
L64XX_REPORT_CURRENT(E2);
|
||||
#endif
|
||||
#if AXIS_IS_L64XX(E3)
|
||||
L64XX_REPORT_CURRENT(E3);
|
||||
#endif
|
||||
#if AXIS_IS_L64XX(E4)
|
||||
L64XX_REPORT_CURRENT(E4);
|
||||
#endif
|
||||
#if AXIS_IS_L64XX(E5)
|
||||
L64XX_REPORT_CURRENT(E5);
|
||||
#endif
|
||||
#if AXIS_IS_L64XX(E6)
|
||||
L64XX_REPORT_CURRENT(E6);
|
||||
#endif
|
||||
#if AXIS_IS_L64XX(E7)
|
||||
L64XX_REPORT_CURRENT(E7);
|
||||
#endif
|
||||
|
||||
L64xxManager.spi_active = false; // done with all SPI transfers - clear handshake flags
|
||||
L64xxManager.spi_abort = false;
|
||||
L64xxManager.pause_monitor(false);
|
||||
}
|
||||
}
|
||||
|
||||
#endif // HAS_L64XX
|
@@ -1,651 +0,0 @@
|
||||
/**
|
||||
* Marlin 3D Printer Firmware
|
||||
* Copyright (c) 2020 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 <https://www.gnu.org/licenses/>.
|
||||
*
|
||||
*/
|
||||
|
||||
//
|
||||
// NOTE: All tests assume each axis uses matching driver chips.
|
||||
//
|
||||
|
||||
#include "../../../inc/MarlinConfig.h"
|
||||
|
||||
#if HAS_L64XX
|
||||
|
||||
#include "../../gcode.h"
|
||||
#include "../../../module/stepper/indirection.h"
|
||||
#include "../../../module/planner.h"
|
||||
#include "../../../libs/L64XX/L64XX_Marlin.h"
|
||||
|
||||
#define DEBUG_OUT ENABLED(L6470_CHITCHAT)
|
||||
#include "../../../core/debug_out.h"
|
||||
|
||||
/**
|
||||
* M916: increase KVAL_HOLD until get thermal warning
|
||||
* NOTE - on L6474 it is TVAL that is used
|
||||
*
|
||||
* J - select which driver(s) to monitor on multi-driver axis
|
||||
* 0 - (default) monitor all drivers on the axis or E0
|
||||
* 1 - monitor only X, Y, Z, E1
|
||||
* 2 - monitor only X2, Y2, Z2, E2
|
||||
* 3 - monitor only Z3, E3
|
||||
* 4 - monitor only Z4, E4
|
||||
*
|
||||
* Xxxx, Yxxx, Zxxx, Exxx - axis to be monitored with displacement
|
||||
* xxx (1-255) is distance moved on either side of current position
|
||||
*
|
||||
* F - feedrate
|
||||
* optional - will use default max feedrate from configuration.h if not specified
|
||||
*
|
||||
* T - current (mA) setting for TVAL (0 - 4A in 31.25mA increments, rounds down) - L6474 only
|
||||
* optional - will report current value from driver if not specified
|
||||
*
|
||||
* K - value for KVAL_HOLD (0 - 255) (ignored for L6474)
|
||||
* optional - will report current value from driver if not specified
|
||||
*
|
||||
* D - time (in seconds) to run each setting of KVAL_HOLD/TVAL
|
||||
* optional - defaults to zero (runs each setting once)
|
||||
*/
|
||||
|
||||
/**
|
||||
* This routine is also useful for determining the approximate KVAL_HOLD
|
||||
* where the stepper stops losing steps. The sound will get noticeably quieter
|
||||
* as it stops losing steps.
|
||||
*/
|
||||
|
||||
void GcodeSuite::M916() {
|
||||
|
||||
DEBUG_ECHOLNPGM("M916");
|
||||
|
||||
L64xxManager.pause_monitor(true); // Keep monitor_driver() from stealing status
|
||||
|
||||
// Variables used by L64xxManager.get_user_input function - some may not be used
|
||||
char axis_mon[3][3] = { {" "}, {" "}, {" "} }; // list of Axes to be monitored
|
||||
L64XX_axis_t axis_index[3];
|
||||
uint16_t axis_status[3];
|
||||
uint8_t driver_count = 1;
|
||||
float position_max;
|
||||
float position_min;
|
||||
float final_feedrate;
|
||||
uint8_t kval_hold;
|
||||
uint8_t OCD_TH_val = 0;
|
||||
uint8_t STALL_TH_val = 0;
|
||||
uint16_t over_current_threshold;
|
||||
constexpr uint8_t over_current_flag = false; // M916 doesn't play with the overcurrent thresholds
|
||||
|
||||
#define DRIVER_TYPE_L6474(Q) AXIS_DRIVER_TYPE_##Q(L6474)
|
||||
|
||||
uint8_t j; // general purpose counter
|
||||
|
||||
if (L64xxManager.get_user_input(driver_count, axis_index, axis_mon, position_max, position_min, final_feedrate, kval_hold, over_current_flag, OCD_TH_val, STALL_TH_val, over_current_threshold))
|
||||
return; // quit if invalid user input
|
||||
|
||||
DEBUG_ECHOLNPGM("feedrate = ", final_feedrate);
|
||||
|
||||
planner.synchronize(); // wait for all current movement commands to complete
|
||||
|
||||
const L64XX_Marlin::L64XX_shadow_t &sh = L64xxManager.shadow;
|
||||
for (j = 0; j < driver_count; j++)
|
||||
L64xxManager.get_status(axis_index[j]); // clear out any pre-existing error flags
|
||||
|
||||
char temp_axis_string[] = " ";
|
||||
temp_axis_string[0] = axis_mon[0][0]; // need to have a string for use within sprintf format section
|
||||
char gcode_string[80];
|
||||
uint16_t status_composite = 0;
|
||||
|
||||
uint16_t M91x_counter = kval_hold;
|
||||
uint16_t M91x_counter_max;
|
||||
if (sh.STATUS_AXIS_LAYOUT == L6474_STATUS_LAYOUT) {
|
||||
M91x_counter_max = 128; // TVAL is 7 bits
|
||||
LIMIT(M91x_counter, 0U, 127U);
|
||||
}
|
||||
else
|
||||
M91x_counter_max = 256; // KVAL_HOLD is 8 bits
|
||||
|
||||
uint8_t M91x_delay_s = parser.byteval('D'); // get delay in seconds
|
||||
millis_t M91x_delay_ms = SEC_TO_MS(M91x_delay_s * 60);
|
||||
millis_t M91x_delay_end;
|
||||
|
||||
DEBUG_ECHOLNPGM(".\n.");
|
||||
|
||||
do {
|
||||
|
||||
if (sh.STATUS_AXIS_LAYOUT == L6474_STATUS_LAYOUT)
|
||||
DEBUG_ECHOLNPGM("TVAL current (mA) = ", (M91x_counter + 1) * sh.AXIS_STALL_CURRENT_CONSTANT_INV); // report TVAL current for this run
|
||||
else
|
||||
DEBUG_ECHOLNPGM("kval_hold = ", M91x_counter); // report KVAL_HOLD for this run
|
||||
|
||||
for (j = 0; j < driver_count; j++)
|
||||
L64xxManager.set_param(axis_index[j], L6470_KVAL_HOLD, M91x_counter); //set KVAL_HOLD or TVAL (same register address)
|
||||
|
||||
M91x_delay_end = millis() + M91x_delay_ms;
|
||||
do {
|
||||
// turn the motor(s) both directions
|
||||
sprintf_P(gcode_string, PSTR("G0 %s%03d F%03d"), temp_axis_string, uint16_t(position_min), uint16_t(final_feedrate));
|
||||
gcode.process_subcommands_now_P(gcode_string);
|
||||
|
||||
sprintf_P(gcode_string, PSTR("G0 %s%03d F%03d"), temp_axis_string, uint16_t(position_max), uint16_t(final_feedrate));
|
||||
gcode.process_subcommands_now_P(gcode_string);
|
||||
|
||||
// get the status after the motors have stopped
|
||||
planner.synchronize();
|
||||
|
||||
status_composite = 0; // clear out the old bits
|
||||
|
||||
for (j = 0; j < driver_count; j++) {
|
||||
axis_status[j] = (~L64xxManager.get_status(axis_index[j])) & sh.L6470_ERROR_MASK; // bits of interest are all active low
|
||||
status_composite |= axis_status[j] ;
|
||||
}
|
||||
|
||||
if (status_composite) break;
|
||||
} while (millis() < M91x_delay_end);
|
||||
|
||||
if (status_composite) break;
|
||||
|
||||
M91x_counter++;
|
||||
|
||||
} while (!(status_composite & (sh.STATUS_AXIS_TH_WRN | sh.STATUS_AXIS_TH_SD)) && (M91x_counter < M91x_counter_max));
|
||||
|
||||
DEBUG_ECHOLNPGM(".");
|
||||
|
||||
#if ENABLED(L6470_CHITCHAT)
|
||||
if (status_composite) {
|
||||
L64xxManager.error_status_decode(status_composite, axis_index[0],
|
||||
sh.STATUS_AXIS_TH_SD, sh.STATUS_AXIS_TH_WRN,
|
||||
sh.STATUS_AXIS_STEP_LOSS_A, sh.STATUS_AXIS_STEP_LOSS_B,
|
||||
sh.STATUS_AXIS_OCD, sh.STATUS_AXIS_LAYOUT);
|
||||
DEBUG_ECHOLNPGM(".");
|
||||
}
|
||||
#endif
|
||||
|
||||
if ((status_composite & (sh.STATUS_AXIS_TH_WRN | sh.STATUS_AXIS_TH_SD)))
|
||||
DEBUG_ECHOLNPGM(".\n.\nTest completed normally - Thermal warning/shutdown has occurred");
|
||||
else if (status_composite)
|
||||
DEBUG_ECHOLNPGM(".\n.\nTest completed abnormally - non-thermal error has occurred");
|
||||
else
|
||||
DEBUG_ECHOLNPGM(".\n.\nTest completed normally - Unable to get to thermal warning/shutdown");
|
||||
|
||||
L64xxManager.pause_monitor(false);
|
||||
}
|
||||
|
||||
/**
|
||||
* M917: Find minimum current thresholds
|
||||
*
|
||||
* Decrease OCD current until overcurrent error
|
||||
* Increase OCD until overcurrent error goes away
|
||||
* Decrease stall threshold until stall (not done on L6474)
|
||||
* Increase stall until stall error goes away (not done on L6474)
|
||||
*
|
||||
* J - select which driver(s) to monitor on multi-driver axis
|
||||
* 0 - (default) monitor all drivers on the axis or E0
|
||||
* 1 - monitor only X, Y, Z, E1
|
||||
* 2 - monitor only X2, Y2, Z2, E2
|
||||
* Xxxx, Yxxx, Zxxx, Exxx - axis to be monitored with displacement
|
||||
* xxx (1-255) is distance moved on either side of current position
|
||||
*
|
||||
* F - feedrate
|
||||
* optional - will use default max feedrate from Configuration.h if not specified
|
||||
*
|
||||
* I - starting over-current threshold
|
||||
* optional - will report current value from driver if not specified
|
||||
* if there are multiple drivers on the axis then all will be set the same
|
||||
*
|
||||
* T - current (mA) setting for TVAL (0 - 4A in 31.25mA increments, rounds down) - L6474 only
|
||||
* optional - will report current value from driver if not specified
|
||||
*
|
||||
* K - value for KVAL_HOLD (0 - 255) (ignored for L6474)
|
||||
* optional - will report current value from driver if not specified
|
||||
*/
|
||||
void GcodeSuite::M917() {
|
||||
|
||||
DEBUG_ECHOLNPGM("M917");
|
||||
|
||||
L64xxManager.pause_monitor(true); // Keep monitor_driver() from stealing status
|
||||
|
||||
char axis_mon[3][3] = { {" "}, {" "}, {" "} }; // list of Axes to be monitored
|
||||
L64XX_axis_t axis_index[3];
|
||||
uint16_t axis_status[3];
|
||||
uint8_t driver_count = 1;
|
||||
float position_max;
|
||||
float position_min;
|
||||
float final_feedrate;
|
||||
uint8_t kval_hold;
|
||||
uint8_t OCD_TH_val = 0;
|
||||
uint8_t STALL_TH_val = 0;
|
||||
uint16_t over_current_threshold;
|
||||
constexpr uint8_t over_current_flag = true;
|
||||
|
||||
uint8_t j; // general purpose counter
|
||||
|
||||
if (L64xxManager.get_user_input(driver_count, axis_index, axis_mon, position_max, position_min, final_feedrate, kval_hold, over_current_flag, OCD_TH_val, STALL_TH_val, over_current_threshold))
|
||||
return; // quit if invalid user input
|
||||
|
||||
DEBUG_ECHOLNPGM("feedrate = ", final_feedrate);
|
||||
|
||||
planner.synchronize(); // wait for all current movement commands to complete
|
||||
|
||||
const L64XX_Marlin::L64XX_shadow_t &sh = L64xxManager.shadow;
|
||||
for (j = 0; j < driver_count; j++)
|
||||
L64xxManager.get_status(axis_index[j]); // clear error flags
|
||||
char temp_axis_string[] = " ";
|
||||
temp_axis_string[0] = axis_mon[0][0]; // need a sprintf format string
|
||||
char gcode_string[80];
|
||||
uint16_t status_composite = 0;
|
||||
uint8_t test_phase = 0; // 0 - decreasing OCD - exit when OCD warning occurs (ignore STALL)
|
||||
// 1 - increasing OCD - exit when OCD warning stops (ignore STALL)
|
||||
// 2 - OCD finalized - decreasing STALL - exit when STALL warning happens
|
||||
// 3 - OCD finalized - increasing STALL - exit when STALL warning stop
|
||||
// 4 - all testing completed
|
||||
DEBUG_ECHOPGM(".\n.\n.\nover_current threshold : ", (OCD_TH_val + 1) * 375); // first status display
|
||||
DEBUG_ECHOPGM(" (OCD_TH: : ", OCD_TH_val);
|
||||
if (sh.STATUS_AXIS_LAYOUT != L6474_STATUS_LAYOUT) {
|
||||
DEBUG_ECHOPGM(") Stall threshold: ", (STALL_TH_val + 1) * 31.25);
|
||||
DEBUG_ECHOPGM(" (STALL_TH: ", STALL_TH_val);
|
||||
}
|
||||
DEBUG_ECHOLNPGM(")");
|
||||
|
||||
do {
|
||||
|
||||
if (sh.STATUS_AXIS_LAYOUT != L6474_STATUS_LAYOUT) DEBUG_ECHOPGM("STALL threshold : ", (STALL_TH_val + 1) * 31.25);
|
||||
DEBUG_ECHOLNPGM(" OCD threshold : ", (OCD_TH_val + 1) * 375);
|
||||
|
||||
sprintf_P(gcode_string, PSTR("G0 %s%03d F%03d"), temp_axis_string, uint16_t(position_min), uint16_t(final_feedrate));
|
||||
gcode.process_subcommands_now_P(gcode_string);
|
||||
|
||||
sprintf_P(gcode_string, PSTR("G0 %s%03d F%03d"), temp_axis_string, uint16_t(position_max), uint16_t(final_feedrate));
|
||||
gcode.process_subcommands_now_P(gcode_string);
|
||||
|
||||
planner.synchronize();
|
||||
|
||||
status_composite = 0; // clear out the old bits
|
||||
|
||||
for (j = 0; j < driver_count; j++) {
|
||||
axis_status[j] = (~L64xxManager.get_status(axis_index[j])) & sh.L6470_ERROR_MASK; // bits of interest are all active low
|
||||
status_composite |= axis_status[j];
|
||||
}
|
||||
|
||||
if (status_composite && (status_composite & sh.STATUS_AXIS_UVLO)) {
|
||||
DEBUG_ECHOLNPGM("Test aborted (Undervoltage lockout active)");
|
||||
#if ENABLED(L6470_CHITCHAT)
|
||||
for (j = 0; j < driver_count; j++) {
|
||||
if (j) DEBUG_ECHOPGM("...");
|
||||
L64xxManager.error_status_decode(axis_status[j], axis_index[j],
|
||||
sh.STATUS_AXIS_TH_SD, sh.STATUS_AXIS_TH_WRN,
|
||||
sh.STATUS_AXIS_STEP_LOSS_A, sh.STATUS_AXIS_STEP_LOSS_B,
|
||||
sh.STATUS_AXIS_OCD, sh.STATUS_AXIS_LAYOUT);
|
||||
}
|
||||
#endif
|
||||
return;
|
||||
}
|
||||
|
||||
if (status_composite & (sh.STATUS_AXIS_TH_WRN | sh.STATUS_AXIS_TH_SD)) {
|
||||
DEBUG_ECHOLNPGM("thermal problem - waiting for chip(s) to cool down ");
|
||||
uint16_t status_composite_temp = 0;
|
||||
uint8_t k = 0;
|
||||
do {
|
||||
k++;
|
||||
if (!(k % 4)) {
|
||||
kval_hold *= 0.95;
|
||||
DEBUG_EOL();
|
||||
DEBUG_ECHOLNPGM("Lowering KVAL_HOLD by about 5% to ", kval_hold);
|
||||
for (j = 0; j < driver_count; j++)
|
||||
L64xxManager.set_param(axis_index[j], L6470_KVAL_HOLD, kval_hold);
|
||||
}
|
||||
DEBUG_ECHOLNPGM(".");
|
||||
gcode.reset_stepper_timeout(); // keep steppers powered
|
||||
watchdog_refresh();
|
||||
safe_delay(5000);
|
||||
status_composite_temp = 0;
|
||||
for (j = 0; j < driver_count; j++) {
|
||||
axis_status[j] = (~L64xxManager.get_status(axis_index[j])) & sh.L6470_ERROR_MASK; // bits of interest are all active low
|
||||
status_composite_temp |= axis_status[j];
|
||||
}
|
||||
}
|
||||
while (status_composite_temp & (sh.STATUS_AXIS_TH_WRN | sh.STATUS_AXIS_TH_SD));
|
||||
DEBUG_EOL();
|
||||
}
|
||||
if (status_composite & (sh.STATUS_AXIS_STEP_LOSS_A | sh.STATUS_AXIS_STEP_LOSS_B | sh.STATUS_AXIS_OCD)) {
|
||||
switch (test_phase) {
|
||||
|
||||
case 0: {
|
||||
if (status_composite & sh.STATUS_AXIS_OCD) {
|
||||
// phase 0 with OCD warning - time to go to next phase
|
||||
if (OCD_TH_val >= sh.AXIS_OCD_TH_MAX) {
|
||||
OCD_TH_val = sh.AXIS_OCD_TH_MAX; // limit to max
|
||||
test_phase = 2; // at highest value so skip phase 1
|
||||
//DEBUG_ECHOLNPGM("LOGIC E0A OCD at highest - skip to 2");
|
||||
DEBUG_ECHOLNPGM("OCD at highest - OCD finalized");
|
||||
}
|
||||
else {
|
||||
OCD_TH_val++; // normal exit to next phase
|
||||
test_phase = 1; // setup for first pass of phase 1
|
||||
//DEBUG_ECHOLNPGM("LOGIC E0B - inc OCD & go to 1");
|
||||
DEBUG_ECHOLNPGM("inc OCD");
|
||||
}
|
||||
}
|
||||
else { // phase 0 without OCD warning - keep on decrementing if can
|
||||
if (OCD_TH_val) {
|
||||
OCD_TH_val--; // try lower value
|
||||
//DEBUG_ECHOLNPGM("LOGIC E0C - dec OCD");
|
||||
DEBUG_ECHOLNPGM("dec OCD");
|
||||
}
|
||||
else {
|
||||
test_phase = 2; // at lowest value without warning so skip phase 1
|
||||
//DEBUG_ECHOLNPGM("LOGIC E0D - OCD at latest - go to 2");
|
||||
DEBUG_ECHOLNPGM("OCD finalized");
|
||||
}
|
||||
}
|
||||
} break;
|
||||
|
||||
case 1: {
|
||||
if (status_composite & sh.STATUS_AXIS_OCD) {
|
||||
// phase 1 with OCD warning - increment if can
|
||||
if (OCD_TH_val >= sh.AXIS_OCD_TH_MAX) {
|
||||
OCD_TH_val = sh.AXIS_OCD_TH_MAX; // limit to max
|
||||
test_phase = 2; // at highest value so go to next phase
|
||||
//DEBUG_ECHOLNPGM("LOGIC E1A - OCD at max - go to 2");
|
||||
DEBUG_ECHOLNPGM("OCD finalized");
|
||||
}
|
||||
else {
|
||||
OCD_TH_val++; // try a higher value
|
||||
//DEBUG_ECHOLNPGM("LOGIC E1B - inc OCD");
|
||||
DEBUG_ECHOLNPGM("inc OCD");
|
||||
}
|
||||
}
|
||||
else { // phase 1 without OCD warning - normal exit to phase 2
|
||||
test_phase = 2;
|
||||
//DEBUG_ECHOLNPGM("LOGIC E1C - no OCD warning - go to 1");
|
||||
DEBUG_ECHOLNPGM("OCD finalized");
|
||||
}
|
||||
} break;
|
||||
|
||||
case 2: {
|
||||
if (sh.STATUS_AXIS_LAYOUT == L6474_STATUS_LAYOUT) { // skip all STALL_TH steps if L6474
|
||||
test_phase = 4;
|
||||
break;
|
||||
}
|
||||
if (status_composite & (sh.STATUS_AXIS_STEP_LOSS_A | sh.STATUS_AXIS_STEP_LOSS_B)) {
|
||||
// phase 2 with stall warning - time to go to next phase
|
||||
if (STALL_TH_val >= 127) {
|
||||
STALL_TH_val = 127; // limit to max
|
||||
//DEBUG_ECHOLNPGM("LOGIC E2A - STALL warning, STALL at max, quit");
|
||||
DEBUG_ECHOLNPGM("finished - STALL at maximum value but still have stall warning");
|
||||
test_phase = 4;
|
||||
}
|
||||
else {
|
||||
test_phase = 3; // normal exit to next phase (found failing value of STALL)
|
||||
STALL_TH_val++; // setup for first pass of phase 3
|
||||
//DEBUG_ECHOLNPGM("LOGIC E2B - INC - STALL warning, inc Stall, go to 3");
|
||||
DEBUG_ECHOLNPGM("inc Stall");
|
||||
}
|
||||
}
|
||||
else { // phase 2 without stall warning - decrement if can
|
||||
if (STALL_TH_val) {
|
||||
STALL_TH_val--; // try a lower value
|
||||
//DEBUG_ECHOLNPGM("LOGIC E2C - no STALL, dec STALL");
|
||||
DEBUG_ECHOLNPGM("dec STALL");
|
||||
}
|
||||
else {
|
||||
DEBUG_ECHOLNPGM("finished - STALL at lowest value but still do NOT have stall warning");
|
||||
test_phase = 4;
|
||||
//DEBUG_ECHOLNPGM("LOGIC E2D - no STALL, at lowest so quit");
|
||||
}
|
||||
}
|
||||
} break;
|
||||
|
||||
case 3: {
|
||||
if (sh.STATUS_AXIS_LAYOUT == L6474_STATUS_LAYOUT) { // skip all STALL_TH steps if L6474
|
||||
test_phase = 4;
|
||||
break;
|
||||
}
|
||||
if (status_composite & (sh.STATUS_AXIS_STEP_LOSS_A | sh.STATUS_AXIS_STEP_LOSS_B)) {
|
||||
// phase 3 with stall warning - increment if can
|
||||
if (STALL_TH_val >= 127) {
|
||||
STALL_TH_val = 127; // limit to max
|
||||
DEBUG_ECHOLNPGM("finished - STALL at maximum value but still have stall warning");
|
||||
test_phase = 4;
|
||||
//DEBUG_ECHOLNPGM("LOGIC E3A - STALL, at max so quit");
|
||||
}
|
||||
else {
|
||||
STALL_TH_val++; // still looking for passing value
|
||||
//DEBUG_ECHOLNPGM("LOGIC E3B - STALL, inc stall");
|
||||
DEBUG_ECHOLNPGM("inc stall");
|
||||
}
|
||||
}
|
||||
else { //phase 3 without stall warning but have OCD warning
|
||||
DEBUG_ECHOLNPGM("Hardware problem - OCD warning without STALL warning");
|
||||
test_phase = 4;
|
||||
//DEBUG_ECHOLNPGM("LOGIC E3C - not STALLED, hardware problem (quit)");
|
||||
}
|
||||
} break;
|
||||
|
||||
}
|
||||
|
||||
}
|
||||
else {
|
||||
switch (test_phase) {
|
||||
case 0: { // phase 0 without OCD warning - keep on decrementing if can
|
||||
if (OCD_TH_val) {
|
||||
OCD_TH_val--; // try lower value
|
||||
//DEBUG_ECHOLNPGM("LOGIC N0A - DEC OCD");
|
||||
DEBUG_ECHOLNPGM("DEC OCD");
|
||||
}
|
||||
else {
|
||||
test_phase = 2; // at lowest value without warning so skip phase 1
|
||||
//DEBUG_ECHOLNPGM("LOGIC N0B - OCD at lowest (go to phase 2)");
|
||||
DEBUG_ECHOLNPGM("OCD finalized");
|
||||
}
|
||||
} break;
|
||||
|
||||
case 1: //DEBUG_ECHOLNPGM("LOGIC N1 (go directly to 2)"); // phase 1 without OCD warning - drop directly to phase 2
|
||||
DEBUG_ECHOLNPGM("OCD finalized");
|
||||
|
||||
case 2: { // phase 2 without stall warning - keep on decrementing if can
|
||||
if (sh.STATUS_AXIS_LAYOUT == L6474_STATUS_LAYOUT) { // skip all STALL_TH steps if L6474
|
||||
test_phase = 4;
|
||||
break;
|
||||
}
|
||||
if (STALL_TH_val) {
|
||||
STALL_TH_val--; // try a lower value (stay in phase 2)
|
||||
//DEBUG_ECHOLNPGM("LOGIC N2B - dec STALL");
|
||||
DEBUG_ECHOLNPGM("dec STALL");
|
||||
}
|
||||
else {
|
||||
DEBUG_ECHOLNPGM("finished - STALL at lowest value but still no stall warning");
|
||||
test_phase = 4;
|
||||
//DEBUG_ECHOLNPGM("LOGIC N2C - STALL at lowest (quit)");
|
||||
}
|
||||
} break;
|
||||
|
||||
case 3: {
|
||||
if (sh.STATUS_AXIS_LAYOUT == L6474_STATUS_LAYOUT) { // skip all STALL_TH steps if L6474
|
||||
test_phase = 4;
|
||||
break;
|
||||
}
|
||||
test_phase = 4;
|
||||
//DEBUG_ECHOLNPGM("LOGIC N3 - finished!");
|
||||
DEBUG_ECHOLNPGM("finished!");
|
||||
} break; // phase 3 without any warnings - desired exit
|
||||
} //
|
||||
} // end of status checks
|
||||
|
||||
if (test_phase != 4) {
|
||||
for (j = 0; j < driver_count; j++) { // update threshold(s)
|
||||
L64xxManager.set_param(axis_index[j], L6470_OCD_TH, OCD_TH_val);
|
||||
if (sh.STATUS_AXIS_LAYOUT != L6474_STATUS_LAYOUT) L64xxManager.set_param(axis_index[j], L6470_STALL_TH, STALL_TH_val);
|
||||
if (L64xxManager.get_param(axis_index[j], L6470_OCD_TH) != OCD_TH_val) DEBUG_ECHOLNPGM("OCD mismatch");
|
||||
if ((L64xxManager.get_param(axis_index[j], L6470_STALL_TH) != STALL_TH_val) && (sh.STATUS_AXIS_LAYOUT != L6474_STATUS_LAYOUT)) DEBUG_ECHOLNPGM("STALL mismatch");
|
||||
}
|
||||
}
|
||||
|
||||
} while (test_phase != 4);
|
||||
|
||||
DEBUG_ECHOLNPGM(".");
|
||||
if (status_composite) {
|
||||
#if ENABLED(L6470_CHITCHAT)
|
||||
for (j = 0; j < driver_count; j++) {
|
||||
if (j) DEBUG_ECHOPGM("...");
|
||||
L64xxManager.error_status_decode(axis_status[j], axis_index[j],
|
||||
sh.STATUS_AXIS_TH_SD, sh.STATUS_AXIS_TH_WRN,
|
||||
sh.STATUS_AXIS_STEP_LOSS_A, sh.STATUS_AXIS_STEP_LOSS_B,
|
||||
sh.STATUS_AXIS_OCD, sh.STATUS_AXIS_LAYOUT);
|
||||
}
|
||||
DEBUG_ECHOLNPGM(".");
|
||||
#endif
|
||||
DEBUG_ECHOLNPGM("Completed with errors");
|
||||
}
|
||||
else
|
||||
DEBUG_ECHOLNPGM("Completed with no errors");
|
||||
DEBUG_ECHOLNPGM(".");
|
||||
|
||||
L64xxManager.pause_monitor(false);
|
||||
}
|
||||
|
||||
/**
|
||||
* M918: increase speed until error or max feedrate achieved (as shown in configuration.h))
|
||||
*
|
||||
* J - select which driver(s) to monitor on multi-driver axis
|
||||
* 0 - (default) monitor all drivers on the axis or E0
|
||||
* 1 - monitor only X, Y, Z, E1
|
||||
* 2 - monitor only X2, Y2, Z2, E2
|
||||
* Xxxx, Yxxx, Zxxx, Exxx - axis to be monitored with displacement
|
||||
* xxx (1-255) is distance moved on either side of current position
|
||||
*
|
||||
* I - over current threshold
|
||||
* optional - will report current value from driver if not specified
|
||||
*
|
||||
* T - current (mA) setting for TVAL (0 - 4A in 31.25mA increments, rounds down) - L6474 only
|
||||
* optional - will report current value from driver if not specified
|
||||
*
|
||||
* K - value for KVAL_HOLD (0 - 255) (ignored for L6474)
|
||||
* optional - will report current value from driver if not specified
|
||||
*
|
||||
* M - value for microsteps (1 - 128) (optional)
|
||||
* optional - will report current value from driver if not specified
|
||||
*/
|
||||
void GcodeSuite::M918() {
|
||||
|
||||
DEBUG_ECHOLNPGM("M918");
|
||||
|
||||
L64xxManager.pause_monitor(true); // Keep monitor_driver() from stealing status
|
||||
|
||||
char axis_mon[3][3] = { {" "}, {" "}, {" "} }; // list of Axes to be monitored
|
||||
L64XX_axis_t axis_index[3];
|
||||
uint16_t axis_status[3];
|
||||
uint8_t driver_count = 1;
|
||||
float position_max, position_min;
|
||||
float final_feedrate;
|
||||
uint8_t kval_hold;
|
||||
uint8_t OCD_TH_val = 0;
|
||||
uint8_t STALL_TH_val = 0;
|
||||
uint16_t over_current_threshold;
|
||||
constexpr uint8_t over_current_flag = true;
|
||||
|
||||
const L64XX_Marlin::L64XX_shadow_t &sh = L64xxManager.shadow;
|
||||
|
||||
uint8_t j; // general purpose counter
|
||||
|
||||
if (L64xxManager.get_user_input(driver_count, axis_index, axis_mon, position_max, position_min, final_feedrate, kval_hold, over_current_flag, OCD_TH_val, STALL_TH_val, over_current_threshold))
|
||||
return; // quit if invalid user input
|
||||
|
||||
L64xxManager.get_status(axis_index[0]); // populate shadow array
|
||||
|
||||
uint8_t m_steps = parser.byteval('M');
|
||||
|
||||
if (m_steps != 0) {
|
||||
LIMIT(m_steps, 1, sh.STATUS_AXIS_LAYOUT == L6474_STATUS_LAYOUT ? 16 : 128); // L6474
|
||||
|
||||
uint8_t stepVal;
|
||||
for (stepVal = 0; stepVal < 8; stepVal++) { // convert to L64xx register value
|
||||
if (m_steps == 1) break;
|
||||
m_steps >>= 1;
|
||||
}
|
||||
|
||||
if (sh.STATUS_AXIS_LAYOUT == L6474_STATUS_LAYOUT)
|
||||
stepVal |= 0x98; // NO SYNC
|
||||
else
|
||||
stepVal |= (!SYNC_EN) | SYNC_SEL_1 | stepVal;
|
||||
|
||||
for (j = 0; j < driver_count; j++) {
|
||||
L64xxManager.set_param(axis_index[j], dSPIN_HARD_HIZ, 0); // can't write STEP register if stepper being powered
|
||||
// results in an extra NOOP being sent (data 00)
|
||||
L64xxManager.set_param(axis_index[j], L6470_STEP_MODE, stepVal); // set microsteps
|
||||
}
|
||||
}
|
||||
m_steps = L64xxManager.get_param(axis_index[0], L6470_STEP_MODE) & 0x07; // get microsteps
|
||||
|
||||
DEBUG_ECHOLNPGM("Microsteps = ", _BV(m_steps));
|
||||
DEBUG_ECHOLNPGM("target (maximum) feedrate = ", final_feedrate);
|
||||
|
||||
const float feedrate_inc = final_feedrate / 10, // Start at 1/10 of max & go up by 1/10 per step
|
||||
fr_limit = final_feedrate * 0.99f; // Rounding-safe comparison value
|
||||
float current_feedrate = 0;
|
||||
|
||||
planner.synchronize(); // Wait for moves to complete
|
||||
|
||||
for (j = 0; j < driver_count; j++)
|
||||
L64xxManager.get_status(axis_index[j]); // Clear error flags
|
||||
|
||||
char temp_axis_string[2] = " ";
|
||||
temp_axis_string[0] = axis_mon[0][0]; // Need a sprintf format string
|
||||
//temp_axis_string[1] = '\n';
|
||||
|
||||
char gcode_string[80];
|
||||
uint16_t status_composite = 0;
|
||||
DEBUG_ECHOLNPGM(".\n.\n."); // Make feedrate outputs easier to read
|
||||
|
||||
do {
|
||||
current_feedrate += feedrate_inc;
|
||||
DEBUG_ECHOLNPGM("...feedrate = ", current_feedrate);
|
||||
|
||||
sprintf_P(gcode_string, PSTR("G0 %s%03d F%03d"), temp_axis_string, uint16_t(position_min), uint16_t(current_feedrate));
|
||||
gcode.process_subcommands_now_P(gcode_string);
|
||||
|
||||
sprintf_P(gcode_string, PSTR("G0 %s%03d F%03d"), temp_axis_string, uint16_t(position_max), uint16_t(current_feedrate));
|
||||
gcode.process_subcommands_now_P(gcode_string);
|
||||
|
||||
planner.synchronize();
|
||||
|
||||
for (j = 0; j < driver_count; j++) {
|
||||
axis_status[j] = (~L64xxManager.get_status(axis_index[j])) & 0x0800; // Bits of interest are all active LOW
|
||||
status_composite |= axis_status[j];
|
||||
}
|
||||
if (status_composite) break; // Break on any error
|
||||
} while (current_feedrate < fr_limit);
|
||||
|
||||
DEBUG_ECHOPGM("Completed with ");
|
||||
if (status_composite) {
|
||||
DEBUG_ECHOLNPGM("errors");
|
||||
#if ENABLED(L6470_CHITCHAT)
|
||||
for (j = 0; j < driver_count; j++) {
|
||||
if (j) DEBUG_ECHOPGM("...");
|
||||
L64xxManager.error_status_decode(axis_status[j], axis_index[j],
|
||||
sh.STATUS_AXIS_TH_SD, sh.STATUS_AXIS_TH_WRN,
|
||||
sh.STATUS_AXIS_STEP_LOSS_A, sh.STATUS_AXIS_STEP_LOSS_B,
|
||||
sh.STATUS_AXIS_OCD, sh.STATUS_AXIS_LAYOUT);
|
||||
}
|
||||
#endif
|
||||
}
|
||||
else
|
||||
DEBUG_ECHOLNPGM("no errors");
|
||||
|
||||
L64xxManager.pause_monitor(false);
|
||||
}
|
||||
|
||||
#endif // HAS_L64XX
|
68
Marlin/src/gcode/feature/adc/M3426.cpp
Normal file
68
Marlin/src/gcode/feature/adc/M3426.cpp
Normal file
@@ -0,0 +1,68 @@
|
||||
/**
|
||||
* Marlin 3D Printer Firmware
|
||||
* Copyright (c) 2021 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 <https://www.gnu.org/licenses/>.
|
||||
*
|
||||
*/
|
||||
|
||||
#include "../../../inc/MarlinConfig.h"
|
||||
|
||||
#if ENABLED(HAS_MCP3426_ADC)
|
||||
|
||||
#include "../../gcode.h"
|
||||
|
||||
#include "../../../feature/adc/adc_mcp3426.h"
|
||||
|
||||
#define MCP3426_BASE_ADDR (0b1101 << 3)
|
||||
|
||||
/**
|
||||
* M3426: Read 16 bit (signed) value from I2C MCP3426 ADC device
|
||||
*
|
||||
* M3426 C<byte-1 value in base 10> channel 1 or 2
|
||||
* M3426 G<byte-1 value in base 10> gain 1, 2, 4 or 8
|
||||
* M3426 I<byte-2 value in base 10> 0 or 1, invert reply
|
||||
*/
|
||||
void GcodeSuite::M3426() {
|
||||
uint8_t channel = parser.byteval('C', 1), // Channel 1 or 2
|
||||
gain = parser.byteval('G', 1), // Gain 1, 2, 4, or 8
|
||||
address = parser.byteval('A', 3); // Address 0-7 (or 104-111)
|
||||
const bool inverted = parser.boolval('I');
|
||||
|
||||
if (address <= 7) address += MCP3426_BASE_ADDR;
|
||||
|
||||
if (WITHIN(channel, 1, 2) && (gain == 1 || gain == 2 || gain == 4 || gain == 8) && WITHIN(address, MCP3426_BASE_ADDR, MCP3426_BASE_ADDR + 7)) {
|
||||
int16_t result = mcp3426.ReadValue(channel, gain, address);
|
||||
|
||||
if (mcp3426.Error == false) {
|
||||
if (inverted) {
|
||||
// Should we invert the reading (32767 - ADC value) ?
|
||||
// Caters to end devices that expect values to increase when in reality they decrease.
|
||||
// e.g., A pressure sensor in a vacuum when the end device expects a positive pressure.
|
||||
result = INT16_MAX - result;
|
||||
}
|
||||
//SERIAL_ECHOPGM(STR_OK);
|
||||
SERIAL_ECHOLNPGM("V:", result, " C:", channel, " G:", gain, " I:", inverted ? 1 : 0);
|
||||
}
|
||||
else
|
||||
SERIAL_ERROR_MSG("MCP342X i2c error");
|
||||
}
|
||||
else
|
||||
SERIAL_ERROR_MSG("MCP342X Bad request");
|
||||
}
|
||||
|
||||
#endif // HAS_MCP3426_ADC
|
@@ -26,7 +26,6 @@
|
||||
|
||||
#include "../../gcode.h"
|
||||
#include "../../../module/planner.h"
|
||||
#include "../../../module/stepper.h"
|
||||
|
||||
#if ENABLED(EXTRA_LIN_ADVANCE_K)
|
||||
float other_extruder_advance_K[EXTRUDERS];
|
||||
@@ -117,10 +116,10 @@ void GcodeSuite::M900() {
|
||||
#if EXTRUDERS < 2
|
||||
SERIAL_ECHOLNPGM("Advance S", new_slot, " K", kref, "(S", !new_slot, " K", lref, ")");
|
||||
#else
|
||||
LOOP_L_N(i, EXTRUDERS) {
|
||||
const bool slot = TEST(lin_adv_slot, i);
|
||||
SERIAL_ECHOLNPGM("Advance T", i, " S", slot, " K", planner.extruder_advance_K[i],
|
||||
"(S", !slot, " K", other_extruder_advance_K[i], ")");
|
||||
EXTRUDER_LOOP() {
|
||||
const bool slot = TEST(lin_adv_slot, e);
|
||||
SERIAL_ECHOLNPGM("Advance T", e, " S", slot, " K", planner.extruder_advance_K[e],
|
||||
"(S", !slot, " K", other_extruder_advance_K[e], ")");
|
||||
SERIAL_EOL();
|
||||
}
|
||||
#endif
|
||||
@@ -132,9 +131,9 @@ void GcodeSuite::M900() {
|
||||
SERIAL_ECHOLNPGM("Advance K=", planner.extruder_advance_K[0]);
|
||||
#else
|
||||
SERIAL_ECHOPGM("Advance K");
|
||||
LOOP_L_N(i, EXTRUDERS) {
|
||||
SERIAL_CHAR(' ', '0' + i, ':');
|
||||
SERIAL_DECIMAL(planner.extruder_advance_K[i]);
|
||||
EXTRUDER_LOOP() {
|
||||
SERIAL_CHAR(' ', '0' + e, ':');
|
||||
SERIAL_DECIMAL(planner.extruder_advance_K[e]);
|
||||
}
|
||||
SERIAL_EOL();
|
||||
#endif
|
||||
@@ -145,14 +144,14 @@ void GcodeSuite::M900() {
|
||||
}
|
||||
|
||||
void GcodeSuite::M900_report(const bool forReplay/*=true*/) {
|
||||
report_heading(forReplay, PSTR(STR_LINEAR_ADVANCE));
|
||||
report_heading(forReplay, F(STR_LINEAR_ADVANCE));
|
||||
#if EXTRUDERS < 2
|
||||
report_echo_start(forReplay);
|
||||
SERIAL_ECHOLNPGM(" M900 K", planner.extruder_advance_K[0]);
|
||||
#else
|
||||
LOOP_L_N(i, EXTRUDERS) {
|
||||
EXTRUDER_LOOP() {
|
||||
report_echo_start(forReplay);
|
||||
SERIAL_ECHOLNPGM(" M900 T", i, " K", planner.extruder_advance_K[i]);
|
||||
SERIAL_ECHOLNPGM(" M900 T", e, " K", planner.extruder_advance_K[e]);
|
||||
}
|
||||
#endif
|
||||
}
|
||||
|
@@ -44,14 +44,14 @@ void GcodeSuite::M486() {
|
||||
cancelable.object_count = parser.intval('T', 1);
|
||||
}
|
||||
|
||||
if (parser.seen('S'))
|
||||
if (parser.seenval('S'))
|
||||
cancelable.set_active_object(parser.value_int());
|
||||
|
||||
if (parser.seen('C')) cancelable.cancel_active_object();
|
||||
|
||||
if (parser.seen('P')) cancelable.cancel_object(parser.value_int());
|
||||
if (parser.seenval('P')) cancelable.cancel_object(parser.value_int());
|
||||
|
||||
if (parser.seen('U')) cancelable.uncancel_object(parser.value_int());
|
||||
if (parser.seenval('U')) cancelable.uncancel_object(parser.value_int());
|
||||
}
|
||||
|
||||
#endif // CANCEL_OBJECTS
|
||||
|
@@ -45,12 +45,14 @@
|
||||
* X, Y, Z : Specify axes to move during cleaning. Default: ALL.
|
||||
*/
|
||||
void GcodeSuite::G12() {
|
||||
|
||||
// Don't allow nozzle cleaning without homing first
|
||||
if (homing_needed_error()) return;
|
||||
constexpr main_axes_bits_t clean_axis_mask = main_axes_mask & ~TERN0(NOZZLE_CLEAN_NO_Z, Z_AXIS) & ~TERN0(NOZZLE_CLEAN_NO_Y, Y_AXIS);
|
||||
if (homing_needed_error(clean_axis_mask)) return;
|
||||
|
||||
#ifdef WIPE_SEQUENCE_COMMANDS
|
||||
if (!parser.seen_any()) {
|
||||
gcode.process_subcommands_now_P(PSTR(WIPE_SEQUENCE_COMMANDS));
|
||||
process_subcommands_now(F(WIPE_SEQUENCE_COMMANDS));
|
||||
return;
|
||||
}
|
||||
#endif
|
||||
|
@@ -67,7 +67,7 @@ void GcodeSuite::M710() {
|
||||
}
|
||||
|
||||
void GcodeSuite::M710_report(const bool forReplay/*=true*/) {
|
||||
report_heading_etc(forReplay, PSTR(STR_CONTROLLER_FAN));
|
||||
report_heading_etc(forReplay, F(STR_CONTROLLER_FAN));
|
||||
SERIAL_ECHOLNPGM(" M710"
|
||||
" S", int(controllerFan.settings.active_speed),
|
||||
" I", int(controllerFan.settings.idle_speed),
|
||||
|
@@ -39,51 +39,77 @@
|
||||
#endif
|
||||
|
||||
/**
|
||||
* M907: Set digital trimpot motor current using axis codes X, Y, Z, E, B, S
|
||||
* M907: Set digital trimpot motor current using axis codes X [Y] [Z] [I] [J] [K] [U] [V] [W] [E]
|
||||
* B<current> - Special case for E1 (Requires DIGIPOTSS_PIN or DIGIPOT_MCP4018 or DIGIPOT_MCP4451)
|
||||
* C<current> - Special case for E2 (Requires DIGIPOTSS_PIN or DIGIPOT_MCP4018 or DIGIPOT_MCP4451)
|
||||
* S<current> - Set current in mA for all axes (Requires DIGIPOTSS_PIN or DIGIPOT_MCP4018 or DIGIPOT_MCP4451), or
|
||||
* Set percentage of max current for all axes (Requires HAS_DIGIPOT_DAC)
|
||||
*/
|
||||
void GcodeSuite::M907() {
|
||||
#if HAS_MOTOR_CURRENT_SPI
|
||||
|
||||
if (!parser.seen("BS" LOGICAL_AXES_STRING))
|
||||
if (!parser.seen("BS" STR_AXES_LOGICAL))
|
||||
return M907_report();
|
||||
|
||||
LOOP_LOGICAL_AXES(i) if (parser.seenval(axis_codes[i])) stepper.set_digipot_current(i, parser.value_int());
|
||||
if (parser.seenval('B')) stepper.set_digipot_current(4, parser.value_int());
|
||||
if (parser.seenval('S')) LOOP_LE_N(i, 4) stepper.set_digipot_current(i, parser.value_int());
|
||||
if (parser.seenval('S')) LOOP_L_N(i, MOTOR_CURRENT_COUNT) stepper.set_digipot_current(i, parser.value_int());
|
||||
LOOP_LOGICAL_AXES(i) if (parser.seenval(IAXIS_CHAR(i))) stepper.set_digipot_current(i, parser.value_int()); // X Y Z (I J K U V W) E (map to drivers according to DIGIPOT_CHANNELS. Default with NUM_AXES 3: map X Y Z E to X Y Z E0)
|
||||
// Additional extruders use B,C.
|
||||
// TODO: Change these parameters because 'E' is used and D should be reserved for debugging. B<index>?
|
||||
#if E_STEPPERS >= 2
|
||||
if (parser.seenval('B')) stepper.set_digipot_current(E_AXIS + 1, parser.value_int());
|
||||
#if E_STEPPERS >= 3
|
||||
if (parser.seenval('C')) stepper.set_digipot_current(E_AXIS + 2, parser.value_int());
|
||||
#endif
|
||||
#endif
|
||||
|
||||
#elif HAS_MOTOR_CURRENT_PWM
|
||||
|
||||
if (!parser.seen(
|
||||
#if ANY_PIN(MOTOR_CURRENT_PWM_X, MOTOR_CURRENT_PWM_Y, MOTOR_CURRENT_PWM_XY)
|
||||
"XY"
|
||||
#if ANY_PIN(MOTOR_CURRENT_PWM_X, MOTOR_CURRENT_PWM_Y, MOTOR_CURRENT_PWM_XY, MOTOR_CURRENT_PWM_I, MOTOR_CURRENT_PWM_J, MOTOR_CURRENT_PWM_K, MOTOR_CURRENT_PWM_U, MOTOR_CURRENT_PWM_V, MOTOR_CURRENT_PWM_W)
|
||||
#define HAS_X_Y_XY_I_J_K_U_V_W 1
|
||||
#endif
|
||||
|
||||
#if HAS_X_Y_XY_I_J_K_U_V_W || ANY_PIN(MOTOR_CURRENT_PWM_E, MOTOR_CURRENT_PWM_Z)
|
||||
|
||||
if (!parser.seen("S"
|
||||
#if HAS_X_Y_XY_I_J_K_U_V_W
|
||||
"XY" SECONDARY_AXIS_GANG("I", "J", "K", "U", "V", "W")
|
||||
#endif
|
||||
#if PIN_EXISTS(MOTOR_CURRENT_PWM_Z)
|
||||
"Z"
|
||||
#endif
|
||||
#if PIN_EXISTS(MOTOR_CURRENT_PWM_E)
|
||||
"E"
|
||||
#endif
|
||||
)) return M907_report();
|
||||
|
||||
if (parser.seenval('S')) LOOP_L_N(a, MOTOR_CURRENT_COUNT) stepper.set_digipot_current(a, parser.value_int());
|
||||
|
||||
#if HAS_X_Y_XY_I_J_K_U_V_W
|
||||
if (NUM_AXIS_GANG(
|
||||
parser.seenval('X'), || parser.seenval('Y'), || false,
|
||||
|| parser.seenval('I'), || parser.seenval('J'), || parser.seenval('K'),
|
||||
|| parser.seenval('U'), || parser.seenval('V'), || parser.seenval('W')
|
||||
)) stepper.set_digipot_current(0, parser.value_int());
|
||||
#endif
|
||||
#if PIN_EXISTS(MOTOR_CURRENT_PWM_Z)
|
||||
"Z"
|
||||
if (parser.seenval('Z')) stepper.set_digipot_current(1, parser.value_int());
|
||||
#endif
|
||||
#if PIN_EXISTS(MOTOR_CURRENT_PWM_E)
|
||||
"E"
|
||||
if (parser.seenval('E')) stepper.set_digipot_current(2, parser.value_int());
|
||||
#endif
|
||||
)) return M907_report();
|
||||
|
||||
#if ANY_PIN(MOTOR_CURRENT_PWM_X, MOTOR_CURRENT_PWM_Y, MOTOR_CURRENT_PWM_XY)
|
||||
if (parser.seenval('X') || parser.seenval('Y')) stepper.set_digipot_current(0, parser.value_int());
|
||||
#endif
|
||||
#if PIN_EXISTS(MOTOR_CURRENT_PWM_Z)
|
||||
if (parser.seenval('Z')) stepper.set_digipot_current(1, parser.value_int());
|
||||
#endif
|
||||
#if PIN_EXISTS(MOTOR_CURRENT_PWM_E)
|
||||
if (parser.seenval('E')) stepper.set_digipot_current(2, parser.value_int());
|
||||
#endif
|
||||
|
||||
#endif
|
||||
#endif // HAS_MOTOR_CURRENT_PWM
|
||||
|
||||
#if HAS_MOTOR_CURRENT_I2C
|
||||
// this one uses actual amps in floating point
|
||||
LOOP_LOGICAL_AXES(i) if (parser.seenval(axis_codes[i])) digipot_i2c.set_current(i, parser.value_float());
|
||||
// Additional extruders use B,C,D for channels 4,5,6.
|
||||
// TODO: Change these parameters because 'E' is used. B<index>?
|
||||
#if HAS_EXTRUDERS
|
||||
for (uint8_t i = E_AXIS + 1; i < DIGIPOT_I2C_NUM_CHANNELS; i++)
|
||||
if (parser.seenval('S')) LOOP_L_N(q, DIGIPOT_I2C_NUM_CHANNELS) digipot_i2c.set_current(q, parser.value_float());
|
||||
LOOP_LOGICAL_AXES(i) if (parser.seenval(IAXIS_CHAR(i))) digipot_i2c.set_current(i, parser.value_float()); // X Y Z (I J K U V W) E (map to drivers according to pots adresses. Default with NUM_AXES 3 X Y Z E: map to X Y Z E0)
|
||||
// Additional extruders use B,C,D.
|
||||
// TODO: Change these parameters because 'E' is used and because 'D' should be reserved for debugging. B<index>?
|
||||
#if E_STEPPERS >= 2
|
||||
for (uint8_t i = E_AXIS + 1; i < _MAX(DIGIPOT_I2C_NUM_CHANNELS, (NUM_AXES + 3)); i++)
|
||||
if (parser.seenval('B' + i - (E_AXIS + 1))) digipot_i2c.set_current(i, parser.value_float());
|
||||
#endif
|
||||
#endif
|
||||
@@ -91,30 +117,36 @@ void GcodeSuite::M907() {
|
||||
#if HAS_MOTOR_CURRENT_DAC
|
||||
if (parser.seenval('S')) {
|
||||
const float dac_percent = parser.value_float();
|
||||
LOOP_LE_N(i, 4) stepper_dac.set_current_percent(i, dac_percent);
|
||||
LOOP_LOGICAL_AXES(i) stepper_dac.set_current_percent(i, dac_percent);
|
||||
}
|
||||
LOOP_LOGICAL_AXES(i) if (parser.seenval(axis_codes[i])) stepper_dac.set_current_percent(i, parser.value_float());
|
||||
LOOP_LOGICAL_AXES(i) if (parser.seenval(IAXIS_CHAR(i))) stepper_dac.set_current_percent(i, parser.value_float()); // X Y Z (I J K U V W) E (map to drivers according to DAC_STEPPER_ORDER. Default with NUM_AXES 3: X Y Z E map to X Y Z E0)
|
||||
#endif
|
||||
}
|
||||
|
||||
#if HAS_MOTOR_CURRENT_SPI || HAS_MOTOR_CURRENT_PWM
|
||||
|
||||
void GcodeSuite::M907_report(const bool forReplay/*=true*/) {
|
||||
report_heading_etc(forReplay, PSTR(STR_STEPPER_MOTOR_CURRENTS));
|
||||
report_heading_etc(forReplay, F(STR_STEPPER_MOTOR_CURRENTS));
|
||||
#if HAS_MOTOR_CURRENT_PWM
|
||||
SERIAL_ECHOLNPGM_P( // PWM-based has 3 values:
|
||||
PSTR(" M907 X"), stepper.motor_current_setting[0] // X and Y
|
||||
SERIAL_ECHOLNPGM_P( // PWM-based has 3 values:
|
||||
PSTR(" M907 X"), stepper.motor_current_setting[0] // X, Y, (I, J, K, U, V, W)
|
||||
, SP_Z_STR, stepper.motor_current_setting[1] // Z
|
||||
, SP_E_STR, stepper.motor_current_setting[2] // E
|
||||
);
|
||||
#elif HAS_MOTOR_CURRENT_SPI
|
||||
SERIAL_ECHOPGM(" M907"); // SPI-based has 5 values:
|
||||
LOOP_LOGICAL_AXES(q) { // X Y Z (I J K) E (map to X Y Z (I J K) E0 by default)
|
||||
SERIAL_CHAR(' ', axis_codes[q]);
|
||||
LOOP_LOGICAL_AXES(q) { // X Y Z (I J K U V W) E (map to X Y Z (I J K U V W) E0 by default)
|
||||
SERIAL_CHAR(' ', IAXIS_CHAR(q));
|
||||
SERIAL_ECHO(stepper.motor_current_setting[q]);
|
||||
}
|
||||
SERIAL_CHAR(' ', 'B'); // B (maps to E1 by default)
|
||||
SERIAL_ECHOLN(stepper.motor_current_setting[4]);
|
||||
#if E_STEPPERS >= 2
|
||||
SERIAL_ECHOPGM_P(PSTR(" B"), stepper.motor_current_setting[E_AXIS + 1] // B (maps to E1 with NUM_AXES 3 according to DIGIPOT_CHANNELS)
|
||||
#if E_STEPPERS >= 3
|
||||
, PSTR(" C"), stepper.motor_current_setting[E_AXIS + 2] // C (mapping to E2 must be defined by DIGIPOT_CHANNELS)
|
||||
#endif
|
||||
);
|
||||
#endif
|
||||
SERIAL_EOL();
|
||||
#endif
|
||||
}
|
||||
|
||||
|
@@ -38,7 +38,7 @@
|
||||
void GcodeSuite::M207() { fwretract.M207(); }
|
||||
|
||||
void GcodeSuite::M207_report(const bool forReplay/*=true*/) {
|
||||
report_heading_etc(forReplay, PSTR(STR_RETRACT_S_F_Z));
|
||||
report_heading_etc(forReplay, F(STR_RETRACT_S_F_Z));
|
||||
fwretract.M207_report();
|
||||
}
|
||||
|
||||
@@ -53,7 +53,7 @@ void GcodeSuite::M207_report(const bool forReplay/*=true*/) {
|
||||
void GcodeSuite::M208() { fwretract.M208(); }
|
||||
|
||||
void GcodeSuite::M208_report(const bool forReplay/*=true*/) {
|
||||
report_heading_etc(forReplay, PSTR(STR_RECOVER_S_F));
|
||||
report_heading_etc(forReplay, F(STR_RECOVER_S_F));
|
||||
fwretract.M208_report();
|
||||
}
|
||||
|
||||
@@ -68,7 +68,7 @@ void GcodeSuite::M208_report(const bool forReplay/*=true*/) {
|
||||
void GcodeSuite::M209() { fwretract.M209(); }
|
||||
|
||||
void GcodeSuite::M209_report(const bool forReplay/*=true*/) {
|
||||
report_heading_etc(forReplay, PSTR(STR_AUTO_RETRACT_S));
|
||||
report_heading_etc(forReplay, F(STR_AUTO_RETRACT_S));
|
||||
fwretract.M209_report();
|
||||
}
|
||||
|
||||
|
@@ -45,10 +45,10 @@
|
||||
*/
|
||||
void GcodeSuite::M260() {
|
||||
// Set the target address
|
||||
if (parser.seen('A')) i2c.address(parser.value_byte());
|
||||
if (parser.seenval('A')) i2c.address(parser.value_byte());
|
||||
|
||||
// Add a new byte to the buffer
|
||||
if (parser.seen('B')) i2c.addbyte(parser.value_byte());
|
||||
if (parser.seenval('B')) i2c.addbyte(parser.value_byte());
|
||||
|
||||
// Flush the buffer to the bus
|
||||
if (parser.seen('S')) i2c.send();
|
||||
@@ -60,15 +60,16 @@ void GcodeSuite::M260() {
|
||||
/**
|
||||
* M261: Request X bytes from I2C slave device
|
||||
*
|
||||
* Usage: M261 A<slave device address base 10> B<number of bytes>
|
||||
* Usage: M261 A<slave device address base 10> B<number of bytes> S<style>
|
||||
*/
|
||||
void GcodeSuite::M261() {
|
||||
if (parser.seen('A')) i2c.address(parser.value_byte());
|
||||
if (parser.seenval('A')) i2c.address(parser.value_byte());
|
||||
|
||||
uint8_t bytes = parser.byteval('B', 1);
|
||||
const uint8_t bytes = parser.byteval('B', 1), // Bytes to request
|
||||
style = parser.byteval('S'); // Serial output style (ASCII, HEX etc)
|
||||
|
||||
if (i2c.addr && bytes && bytes <= TWIBUS_BUFFER_SIZE)
|
||||
i2c.relay(bytes);
|
||||
i2c.relay(bytes, style);
|
||||
else
|
||||
SERIAL_ERROR_MSG("Bad i2c request");
|
||||
}
|
||||
|
@@ -31,14 +31,16 @@
|
||||
* M150: Set Status LED Color - Use R-U-B-W for R-G-B-W
|
||||
* and Brightness - Use P (for NEOPIXEL only)
|
||||
*
|
||||
* Always sets all 3 or 4 components. If a component is left out, set to 0.
|
||||
* If brightness is left out, no value changed
|
||||
* Always sets all 3 or 4 components unless the K flag is specified.
|
||||
* If a component is left out, set to 0.
|
||||
* If brightness is left out, no value changed.
|
||||
*
|
||||
* With NEOPIXEL_LED:
|
||||
* I<index> Set the NeoPixel index to affect. Default: All
|
||||
* K Keep all unspecified values unchanged instead of setting to 0.
|
||||
*
|
||||
* With NEOPIXEL2_SEPARATE:
|
||||
* S<index> The NeoPixel strip to set. Default is index 0.
|
||||
* S<index> The NeoPixel strip to set. Default: All.
|
||||
*
|
||||
* Examples:
|
||||
*
|
||||
@@ -51,16 +53,19 @@
|
||||
* M150 P ; Set LED full brightness
|
||||
* M150 I1 R ; Set NEOPIXEL index 1 to red
|
||||
* M150 S1 I1 R ; Set SEPARATE index 1 to red
|
||||
* M150 K R127 ; Set LED red to 50% without changing blue or green
|
||||
*/
|
||||
void GcodeSuite::M150() {
|
||||
int32_t old_color = 0;
|
||||
|
||||
#if ENABLED(NEOPIXEL_LED)
|
||||
const int8_t index = parser.intval('I', -1);
|
||||
const pixel_index_t index = parser.intval('I', -1);
|
||||
#if ENABLED(NEOPIXEL2_SEPARATE)
|
||||
int8_t brightness = neo.brightness(), unit = parser.intval('S', -1);
|
||||
switch (unit) {
|
||||
case -1: neo2.neoindex = index; // fall-thru
|
||||
case 0: neo.neoindex = index; break;
|
||||
case 1: neo2.neoindex = index; brightness = neo2.brightness(); break;
|
||||
case 0: neo.neoindex = index; old_color = parser.seen('K') ? neo.pixel_color(index >= 0 ? index : 0) : 0; break;
|
||||
case 1: neo2.neoindex = index; brightness = neo2.brightness(); old_color = parser.seen('K') ? neo2.pixel_color(index >= 0 ? index : 0) : 0; break;
|
||||
}
|
||||
#else
|
||||
const uint8_t brightness = neo.brightness();
|
||||
@@ -69,10 +74,10 @@ void GcodeSuite::M150() {
|
||||
#endif
|
||||
|
||||
const LEDColor color = LEDColor(
|
||||
parser.seen('R') ? (parser.has_value() ? parser.value_byte() : 255) : 0,
|
||||
parser.seen('U') ? (parser.has_value() ? parser.value_byte() : 255) : 0,
|
||||
parser.seen('B') ? (parser.has_value() ? parser.value_byte() : 255) : 0
|
||||
OPTARG(HAS_WHITE_LED, parser.seen('W') ? (parser.has_value() ? parser.value_byte() : 255) : 0)
|
||||
parser.seen('R') ? (parser.has_value() ? parser.value_byte() : 255) : (old_color >> 16) & 0xFF,
|
||||
parser.seen('U') ? (parser.has_value() ? parser.value_byte() : 255) : (old_color >> 8) & 0xFF,
|
||||
parser.seen('B') ? (parser.has_value() ? parser.value_byte() : 255) : old_color & 0xFF
|
||||
OPTARG(HAS_WHITE_LED, parser.seen('W') ? (parser.has_value() ? parser.value_byte() : 255) : (old_color >> 24) & 0xFF)
|
||||
OPTARG(NEOPIXEL_LED, parser.seen('P') ? (parser.has_value() ? parser.value_byte() : 255) : brightness)
|
||||
);
|
||||
|
||||
|
@@ -57,14 +57,14 @@ void MAC_report() {
|
||||
|
||||
// Display current values when the link is active,
|
||||
// otherwise show the stored values
|
||||
void ip_report(const uint16_t cmd, PGM_P const post, const IPAddress &ipo) {
|
||||
void ip_report(const uint16_t cmd, FSTR_P const post, const IPAddress &ipo) {
|
||||
SERIAL_CHAR('M'); SERIAL_ECHO(cmd); SERIAL_CHAR(' ');
|
||||
LOOP_L_N(i, 4) {
|
||||
SERIAL_ECHO(ipo[i]);
|
||||
if (i < 3) SERIAL_CHAR('.');
|
||||
}
|
||||
SERIAL_ECHOPGM(" ; ");
|
||||
SERIAL_ECHOLNPGM_P(post);
|
||||
SERIAL_ECHOLNF(post);
|
||||
}
|
||||
|
||||
/**
|
||||
@@ -98,7 +98,7 @@ void GcodeSuite::M552() {
|
||||
}
|
||||
|
||||
void GcodeSuite::M552_report() {
|
||||
ip_report(552, PSTR("ip address"), Ethernet.linkStatus() == LinkON ? Ethernet.localIP() : ethernet.ip);
|
||||
ip_report(552, F("ip address"), Ethernet.linkStatus() == LinkON ? Ethernet.localIP() : ethernet.ip);
|
||||
}
|
||||
|
||||
/**
|
||||
@@ -112,7 +112,7 @@ void GcodeSuite::M553() {
|
||||
}
|
||||
|
||||
void GcodeSuite::M553_report() {
|
||||
ip_report(553, PSTR("subnet mask"), Ethernet.linkStatus() == LinkON ? Ethernet.subnetMask() : ethernet.subnet);
|
||||
ip_report(553, F("subnet mask"), Ethernet.linkStatus() == LinkON ? Ethernet.subnetMask() : ethernet.subnet);
|
||||
}
|
||||
|
||||
/**
|
||||
@@ -126,7 +126,7 @@ void GcodeSuite::M554() {
|
||||
}
|
||||
|
||||
void GcodeSuite::M554_report() {
|
||||
ip_report(554, PSTR("gateway"), Ethernet.linkStatus() == LinkON ? Ethernet.gatewayIP() : ethernet.gateway);
|
||||
ip_report(554, F("gateway"), Ethernet.linkStatus() == LinkON ? Ethernet.gatewayIP() : ethernet.gateway);
|
||||
}
|
||||
|
||||
#endif // HAS_ETHERNET
|
||||
|
@@ -47,13 +47,20 @@ void GcodeSuite::G60() {
|
||||
SBI(saved_slots[slot >> 3], slot & 0x07);
|
||||
|
||||
#if ENABLED(SAVED_POSITIONS_DEBUG)
|
||||
DEBUG_ECHOPGM(STR_SAVED_POS " S", slot);
|
||||
{
|
||||
const xyze_pos_t &pos = stored_position[slot];
|
||||
DEBUG_ECHOLNPAIR_F_P(
|
||||
LIST_N(DOUBLE(LOGICAL_AXES), SP_E_STR, pos.e,
|
||||
PSTR(" : X"), pos.x, SP_Y_STR, pos.y, SP_Z_STR, pos.z,
|
||||
SP_I_STR, pos.i, SP_J_STR, pos.j, SP_K_STR, pos.k)
|
||||
DEBUG_ECHOPGM(STR_SAVED_POS " S", slot, " :");
|
||||
DEBUG_ECHOLNPGM_P(
|
||||
LIST_N(DOUBLE(NUM_AXES),
|
||||
SP_X_LBL, pos.x, SP_Y_LBL, pos.y, SP_Z_LBL, pos.z,
|
||||
SP_I_LBL, pos.i, SP_J_LBL, pos.j, SP_K_LBL, pos.k,
|
||||
SP_U_LBL, pos.u, SP_V_LBL, pos.v, SP_W_LBL, pos.w
|
||||
)
|
||||
#if HAS_EXTRUDERS
|
||||
, SP_E_LBL, pos.e
|
||||
#endif
|
||||
);
|
||||
}
|
||||
#endif
|
||||
}
|
||||
|
||||
|
@@ -41,7 +41,7 @@
|
||||
*
|
||||
* If XYZE are not given, default restore uses the smart blocking move.
|
||||
*/
|
||||
void GcodeSuite::G61(void) {
|
||||
void GcodeSuite::G61() {
|
||||
|
||||
const uint8_t slot = parser.byteval('S');
|
||||
|
||||
@@ -68,10 +68,10 @@ void GcodeSuite::G61(void) {
|
||||
SYNC_E(stored_position[slot].e);
|
||||
}
|
||||
else {
|
||||
if (parser.seen(LINEAR_AXIS_GANG("X", "Y", "Z", AXIS4_STR, AXIS5_STR, AXIS6_STR))) {
|
||||
if (parser.seen(STR_AXES_MAIN)) {
|
||||
DEBUG_ECHOPGM(STR_RESTORING_POS " S", slot);
|
||||
LOOP_LINEAR_AXES(i) {
|
||||
destination[i] = parser.seen(AXIS_CHAR(i))
|
||||
LOOP_NUM_AXES(i) {
|
||||
destination[i] = parser.seenval(AXIS_CHAR(i))
|
||||
? stored_position[slot][i] + parser.value_axis_units((AxisEnum)i)
|
||||
: current_position[i];
|
||||
DEBUG_CHAR(' ', AXIS_CHAR(i));
|
||||
|
@@ -49,6 +49,12 @@
|
||||
* L<linear> = Override retract Length
|
||||
* X<pos> = Override park position X
|
||||
* Y<pos> = Override park position Y
|
||||
* A<pos> = Override park position A (requires AXIS*_NAME 'A')
|
||||
* B<pos> = Override park position B (requires AXIS*_NAME 'B')
|
||||
* C<pos> = Override park position C (requires AXIS*_NAME 'C')
|
||||
* U<pos> = Override park position U (requires AXIS*_NAME 'U')
|
||||
* V<pos> = Override park position V (requires AXIS*_NAME 'V')
|
||||
* W<pos> = Override park position W (requires AXIS*_NAME 'W')
|
||||
* Z<linear> = Override Z raise
|
||||
*
|
||||
* With an LCD menu:
|
||||
@@ -60,12 +66,23 @@ void GcodeSuite::M125() {
|
||||
|
||||
xyz_pos_t park_point = NOZZLE_PARK_POINT;
|
||||
|
||||
// Move XY axes to filament change position or given position
|
||||
if (parser.seenval('X')) park_point.x = RAW_X_POSITION(parser.linearval('X'));
|
||||
if (parser.seenval('Y')) park_point.y = RAW_X_POSITION(parser.linearval('Y'));
|
||||
// Move to filament change position or given position
|
||||
NUM_AXIS_CODE(
|
||||
if (parser.seenval('X')) park_point.x = RAW_X_POSITION(parser.linearval('X')),
|
||||
if (parser.seenval('Y')) park_point.y = RAW_Y_POSITION(parser.linearval('Y')),
|
||||
NOOP,
|
||||
if (parser.seenval(AXIS4_NAME)) park_point.i = RAW_I_POSITION(parser.linearval(AXIS4_NAME)),
|
||||
if (parser.seenval(AXIS5_NAME)) park_point.j = RAW_J_POSITION(parser.linearval(AXIS5_NAME)),
|
||||
if (parser.seenval(AXIS6_NAME)) park_point.k = RAW_K_POSITION(parser.linearval(AXIS6_NAME)),
|
||||
if (parser.seenval(AXIS7_NAME)) park_point.u = RAW_U_POSITION(parser.linearval(AXIS7_NAME)),
|
||||
if (parser.seenval(AXIS8_NAME)) park_point.v = RAW_V_POSITION(parser.linearval(AXIS8_NAME)),
|
||||
if (parser.seenval(AXIS9_NAME)) park_point.w = RAW_W_POSITION(parser.linearval(AXIS9_NAME))
|
||||
);
|
||||
|
||||
// Lift Z axis
|
||||
if (parser.seenval('Z')) park_point.z = parser.linearval('Z');
|
||||
#if HAS_Z_AXIS
|
||||
if (parser.seenval('Z')) park_point.z = parser.linearval('Z');
|
||||
#endif
|
||||
|
||||
#if HAS_HOTEND_OFFSET && NONE(DUAL_X_CARRIAGE, DELTA)
|
||||
park_point += hotend_offset[active_extruder];
|
||||
@@ -76,7 +93,7 @@ void GcodeSuite::M125() {
|
||||
ui.pause_show_message(PAUSE_MESSAGE_PARKING, PAUSE_MODE_PAUSE_PRINT);
|
||||
|
||||
// If possible, show an LCD prompt with the 'P' flag
|
||||
const bool show_lcd = TERN0(HAS_LCD_MENU, parser.boolval('P'));
|
||||
const bool show_lcd = TERN0(HAS_MARLINUI_MENU, parser.boolval('P'));
|
||||
|
||||
if (pause_print(retract, park_point, show_lcd, 0)) {
|
||||
if (ENABLED(EXTENSIBLE_UI) || BOTH(EMERGENCY_PARSER, HOST_PROMPT_SUPPORT) || !sd_printing || show_lcd) {
|
||||
|
@@ -41,8 +41,11 @@
|
||||
#include "../../../module/tool_change.h"
|
||||
#endif
|
||||
|
||||
#if ENABLED(MMU2_MENUS)
|
||||
#include "../../../lcd/menu/menu_mmu2.h"
|
||||
#if HAS_PRUSA_MMU2
|
||||
#include "../../../feature/mmu/mmu2.h"
|
||||
#if ENABLED(MMU2_MENUS)
|
||||
#include "../../../lcd/menu/menu_mmu2.h"
|
||||
#endif
|
||||
#endif
|
||||
|
||||
#if ENABLED(MIXING_EXTRUDER)
|
||||
@@ -58,8 +61,14 @@
|
||||
*
|
||||
* E[distance] - Retract the filament this far
|
||||
* Z[distance] - Move the Z axis by this distance
|
||||
* X[position] - Move to this X position, with Y
|
||||
* Y[position] - Move to this Y position, with X
|
||||
* X[position] - Move to this X position (instead of NOZZLE_PARK_POINT.x)
|
||||
* Y[position] - Move to this Y position (instead of NOZZLE_PARK_POINT.y)
|
||||
* I[position] - Move to this I position (instead of NOZZLE_PARK_POINT.i)
|
||||
* J[position] - Move to this J position (instead of NOZZLE_PARK_POINT.j)
|
||||
* K[position] - Move to this K position (instead of NOZZLE_PARK_POINT.k)
|
||||
* C[position] - Move to this U position (instead of NOZZLE_PARK_POINT.u)
|
||||
* H[position] - Move to this V position (instead of NOZZLE_PARK_POINT.v)
|
||||
* O[position] - Move to this W position (instead of NOZZLE_PARK_POINT.w)
|
||||
* U[distance] - Retract distance for removal (manual reload)
|
||||
* L[distance] - Extrude distance for insertion (manual reload)
|
||||
* B[count] - Number of times to beep, -1 for indefinite (if equipped with a buzzer)
|
||||
@@ -93,13 +102,13 @@ void GcodeSuite::M600() {
|
||||
// PATCH END: Knutwurst
|
||||
|
||||
#if ENABLED(MIXING_EXTRUDER)
|
||||
const int8_t target_e_stepper = get_target_e_stepper_from_command();
|
||||
if (target_e_stepper < 0) return;
|
||||
const int8_t eindex = get_target_e_stepper_from_command();
|
||||
if (eindex < 0) return;
|
||||
|
||||
const uint8_t old_mixing_tool = mixer.get_current_vtool();
|
||||
mixer.T(MIXER_DIRECT_SET_TOOL);
|
||||
|
||||
MIXER_STEPPER_LOOP(i) mixer.set_collector(i, i == uint8_t(target_e_stepper) ? 1.0 : 0.0);
|
||||
MIXER_STEPPER_LOOP(i) mixer.set_collector(i, i == uint8_t(eindex) ? 1.0 : 0.0);
|
||||
mixer.normalize();
|
||||
|
||||
const int8_t target_extruder = active_extruder;
|
||||
@@ -121,21 +130,20 @@ void GcodeSuite::M600() {
|
||||
}
|
||||
#endif
|
||||
|
||||
// Show initial "wait for start" message
|
||||
#if DISABLED(MMU2_MENUS)
|
||||
ui.pause_show_message(PAUSE_MESSAGE_CHANGING, PAUSE_MODE_PAUSE_PRINT, target_extruder);
|
||||
#endif
|
||||
const bool standardM600 = TERN1(MMU2_MENUS, !mmu2.enabled());
|
||||
|
||||
#if ENABLED(HOME_BEFORE_FILAMENT_CHANGE)
|
||||
// If needed, home before parking for filament change
|
||||
home_if_needed(true);
|
||||
#endif
|
||||
// Show initial "wait for start" message
|
||||
if (standardM600)
|
||||
ui.pause_show_message(PAUSE_MESSAGE_CHANGING, PAUSE_MODE_PAUSE_PRINT, target_extruder);
|
||||
|
||||
// If needed, home before parking for filament change
|
||||
TERN_(HOME_BEFORE_FILAMENT_CHANGE, home_if_needed(true));
|
||||
|
||||
#if HAS_MULTI_EXTRUDER
|
||||
// Change toolhead if specified
|
||||
const uint8_t active_extruder_before_filament_change = active_extruder;
|
||||
if (active_extruder != target_extruder && TERN1(DUAL_X_CARRIAGE, !idex_is_duplicating()))
|
||||
tool_change(target_extruder, false);
|
||||
tool_change(target_extruder);
|
||||
#endif
|
||||
|
||||
// Initial retract before move to filament change position
|
||||
@@ -143,30 +151,26 @@ void GcodeSuite::M600() {
|
||||
|
||||
xyz_pos_t park_point NOZZLE_PARK_POINT;
|
||||
|
||||
// Lift Z axis
|
||||
if (parser.seenval('Z')) park_point.z = parser.linearval('Z');
|
||||
|
||||
// Move XY axes to filament change position or given position
|
||||
if (parser.seenval('X')) park_point.x = parser.linearval('X');
|
||||
if (parser.seenval('Y')) park_point.y = parser.linearval('Y');
|
||||
NUM_AXIS_CODE(
|
||||
if (parser.seenval('X')) park_point.x = parser.linearval('X'),
|
||||
if (parser.seenval('Y')) park_point.y = parser.linearval('Y'),
|
||||
if (parser.seenval('Z')) park_point.z = parser.linearval('Z'), // Lift Z axis
|
||||
if (parser.seenval('I')) park_point.i = parser.linearval('I'),
|
||||
if (parser.seenval('J')) park_point.j = parser.linearval('J'),
|
||||
if (parser.seenval('K')) park_point.k = parser.linearval('K'),
|
||||
if (parser.seenval('C')) park_point.u = parser.linearval('C'), // U axis
|
||||
if (parser.seenval('H')) park_point.v = parser.linearval('H'), // V axis
|
||||
if (parser.seenval('O')) park_point.w = parser.linearval('O') // W axis
|
||||
);
|
||||
|
||||
#if HAS_HOTEND_OFFSET && NONE(DUAL_X_CARRIAGE, DELTA)
|
||||
park_point += hotend_offset[active_extruder];
|
||||
#endif
|
||||
|
||||
#if ENABLED(MMU2_MENUS)
|
||||
// For MMU2 reset retract and load/unload values so they don't mess with MMU filament handling
|
||||
constexpr float unload_length = 0.5f,
|
||||
slow_load_length = 0.0f,
|
||||
fast_load_length = 0.0f;
|
||||
#else
|
||||
// Unload filament
|
||||
const float unload_length = -ABS(parser.axisunitsval('U', E_AXIS, fc_settings[active_extruder].unload_length));
|
||||
// Slow load filament
|
||||
constexpr float slow_load_length = FILAMENT_CHANGE_SLOW_LOAD_LENGTH;
|
||||
// Fast load filament
|
||||
const float fast_load_length = ABS(parser.axisunitsval('L', E_AXIS, fc_settings[active_extruder].load_length));
|
||||
#endif
|
||||
// Unload filament
|
||||
// For MMU2, when enabled, reset retract value so it doesn't mess with MMU filament handling
|
||||
const float unload_length = standardM600 ? -ABS(parser.axisunitsval('U', E_AXIS, fc_settings[active_extruder].unload_length)) : 0.5f;
|
||||
|
||||
const int beep_count = parser.intval('B', -1
|
||||
#ifdef FILAMENT_CHANGE_ALERT_BEEPS
|
||||
@@ -175,20 +179,29 @@ void GcodeSuite::M600() {
|
||||
);
|
||||
|
||||
if (pause_print(retract, park_point, true, unload_length DXC_PASS)) {
|
||||
#if ENABLED(MMU2_MENUS)
|
||||
mmu2_M600();
|
||||
resume_print(slow_load_length, fast_load_length, 0, beep_count DXC_PASS);
|
||||
#else
|
||||
if (standardM600) {
|
||||
wait_for_confirmation(true, beep_count DXC_PASS);
|
||||
resume_print(slow_load_length, fast_load_length, ADVANCED_PAUSE_PURGE_LENGTH,
|
||||
beep_count, (parser.seenval('R') ? parser.value_celsius() : 0) DXC_PASS);
|
||||
#endif
|
||||
resume_print(
|
||||
FILAMENT_CHANGE_SLOW_LOAD_LENGTH,
|
||||
ABS(parser.axisunitsval('L', E_AXIS, fc_settings[active_extruder].load_length)),
|
||||
ADVANCED_PAUSE_PURGE_LENGTH,
|
||||
beep_count,
|
||||
parser.celsiusval('R')
|
||||
DXC_PASS
|
||||
);
|
||||
}
|
||||
else {
|
||||
#if ENABLED(MMU2_MENUS)
|
||||
mmu2_M600();
|
||||
resume_print(0, 0, 0, beep_count, 0 DXC_PASS);
|
||||
#endif
|
||||
}
|
||||
}
|
||||
|
||||
#if HAS_MULTI_EXTRUDER
|
||||
// Restore toolhead if it was changed
|
||||
if (active_extruder_before_filament_change != active_extruder)
|
||||
tool_change(active_extruder_before_filament_change, false);
|
||||
tool_change(active_extruder_before_filament_change);
|
||||
#endif
|
||||
|
||||
TERN_(MIXING_EXTRUDER, mixer.T(old_mixing_tool)); // Restore original mixing tool
|
||||
|
@@ -48,7 +48,7 @@ void GcodeSuite::M603() {
|
||||
if (target_extruder < 0) return;
|
||||
|
||||
// Unload length
|
||||
if (parser.seen('U')) {
|
||||
if (parser.seenval('U')) {
|
||||
fc_settings[target_extruder].unload_length = ABS(parser.value_axis_units(E_AXIS));
|
||||
#if ENABLED(PREVENT_LENGTHY_EXTRUDE)
|
||||
NOMORE(fc_settings[target_extruder].unload_length, EXTRUDE_MAXLENGTH);
|
||||
@@ -56,7 +56,7 @@ void GcodeSuite::M603() {
|
||||
}
|
||||
|
||||
// Load length
|
||||
if (parser.seen('L')) {
|
||||
if (parser.seenval('L')) {
|
||||
fc_settings[target_extruder].load_length = ABS(parser.value_axis_units(E_AXIS));
|
||||
#if ENABLED(PREVENT_LENGTHY_EXTRUDE)
|
||||
NOMORE(fc_settings[target_extruder].load_length, EXTRUDE_MAXLENGTH);
|
||||
@@ -65,14 +65,14 @@ void GcodeSuite::M603() {
|
||||
}
|
||||
|
||||
void GcodeSuite::M603_report(const bool forReplay/*=true*/) {
|
||||
report_heading(forReplay, PSTR(STR_FILAMENT_LOAD_UNLOAD));
|
||||
report_heading(forReplay, F(STR_FILAMENT_LOAD_UNLOAD));
|
||||
|
||||
#if EXTRUDERS == 1
|
||||
report_echo_start(forReplay);
|
||||
SERIAL_ECHOPGM(" M603 L", LINEAR_UNIT(fc_settings[0].load_length), " U", LINEAR_UNIT(fc_settings[0].unload_length), " ;");
|
||||
say_units();
|
||||
#else
|
||||
LOOP_L_N(e, EXTRUDERS) {
|
||||
EXTRUDER_LOOP() {
|
||||
report_echo_start(forReplay);
|
||||
SERIAL_ECHOPGM(" M603 T", e, " L", LINEAR_UNIT(fc_settings[e].load_length), " U", LINEAR_UNIT(fc_settings[e].unload_length), " ;");
|
||||
say_units();
|
||||
|
@@ -60,13 +60,13 @@ void GcodeSuite::M701() {
|
||||
if (TERN0(NO_MOTION_BEFORE_HOMING, axes_should_home())) park_point.z = 0;
|
||||
|
||||
#if ENABLED(MIXING_EXTRUDER)
|
||||
const int8_t target_e_stepper = get_target_e_stepper_from_command();
|
||||
if (target_e_stepper < 0) return;
|
||||
const int8_t eindex = get_target_e_stepper_from_command();
|
||||
if (eindex < 0) return;
|
||||
|
||||
const uint8_t old_mixing_tool = mixer.get_current_vtool();
|
||||
mixer.T(MIXER_DIRECT_SET_TOOL);
|
||||
|
||||
MIXER_STEPPER_LOOP(i) mixer.set_collector(i, (i == (uint8_t)target_e_stepper) ? 1.0 : 0.0);
|
||||
MIXER_STEPPER_LOOP(i) mixer.set_collector(i, i == uint8_t(eindex) ? 1.0 : 0.0);
|
||||
mixer.normalize();
|
||||
|
||||
const int8_t target_extruder = active_extruder;
|
||||
@@ -85,7 +85,7 @@ void GcodeSuite::M701() {
|
||||
// Change toolhead if specified
|
||||
uint8_t active_extruder_before_filament_change = active_extruder;
|
||||
if (active_extruder != target_extruder)
|
||||
tool_change(target_extruder, false);
|
||||
tool_change(target_extruder);
|
||||
#endif
|
||||
|
||||
auto move_z_by = [](const_float_t zdist) {
|
||||
@@ -106,7 +106,7 @@ void GcodeSuite::M701() {
|
||||
#else
|
||||
constexpr float purge_length = ADVANCED_PAUSE_PURGE_LENGTH,
|
||||
slow_load_length = FILAMENT_CHANGE_SLOW_LOAD_LENGTH;
|
||||
const float fast_load_length = ABS(parser.seen('L') ? parser.value_axis_units(E_AXIS)
|
||||
const float fast_load_length = ABS(parser.seenval('L') ? parser.value_axis_units(E_AXIS)
|
||||
: fc_settings[active_extruder].load_length);
|
||||
load_filament(
|
||||
slow_load_length, fast_load_length, purge_length,
|
||||
@@ -124,7 +124,7 @@ void GcodeSuite::M701() {
|
||||
#if HAS_MULTI_EXTRUDER && (HAS_PRUSA_MMU1 || !HAS_MMU)
|
||||
// Restore toolhead if it was changed
|
||||
if (active_extruder_before_filament_change != active_extruder)
|
||||
tool_change(active_extruder_before_filament_change, false);
|
||||
tool_change(active_extruder_before_filament_change);
|
||||
#endif
|
||||
|
||||
TERN_(MIXING_EXTRUDER, mixer.T(old_mixing_tool)); // Restore original mixing tool
|
||||
@@ -165,10 +165,10 @@ void GcodeSuite::M702() {
|
||||
#endif
|
||||
|
||||
if (seenT) {
|
||||
const int8_t target_e_stepper = get_target_e_stepper_from_command();
|
||||
if (target_e_stepper < 0) return;
|
||||
const int8_t eindex = get_target_e_stepper_from_command();
|
||||
if (eindex < 0) return;
|
||||
mixer.T(MIXER_DIRECT_SET_TOOL);
|
||||
MIXER_STEPPER_LOOP(i) mixer.set_collector(i, (i == (uint8_t)target_e_stepper) ? 1.0 : 0.0);
|
||||
MIXER_STEPPER_LOOP(i) mixer.set_collector(i, i == uint8_t(eindex) ? 1.0 : 0.0);
|
||||
mixer.normalize();
|
||||
}
|
||||
|
||||
@@ -188,7 +188,7 @@ void GcodeSuite::M702() {
|
||||
// Change toolhead if specified
|
||||
uint8_t active_extruder_before_filament_change = active_extruder;
|
||||
if (active_extruder != target_extruder)
|
||||
tool_change(target_extruder, false);
|
||||
tool_change(target_extruder);
|
||||
#endif
|
||||
|
||||
// Lift Z axis
|
||||
@@ -202,7 +202,7 @@ void GcodeSuite::M702() {
|
||||
#if BOTH(HAS_MULTI_EXTRUDER, FILAMENT_UNLOAD_ALL_EXTRUDERS)
|
||||
if (!parser.seenval('T')) {
|
||||
HOTEND_LOOP() {
|
||||
if (e != active_extruder) tool_change(e, false);
|
||||
if (e != active_extruder) tool_change(e);
|
||||
unload_filament(-fc_settings[e].unload_length, true, PAUSE_MODE_UNLOAD_FILAMENT);
|
||||
}
|
||||
}
|
||||
@@ -228,7 +228,7 @@ void GcodeSuite::M702() {
|
||||
#if HAS_MULTI_EXTRUDER && (HAS_PRUSA_MMU1 || !HAS_MMU)
|
||||
// Restore toolhead if it was changed
|
||||
if (active_extruder_before_filament_change != active_extruder)
|
||||
tool_change(active_extruder_before_filament_change, false);
|
||||
tool_change(active_extruder_before_filament_change);
|
||||
#endif
|
||||
|
||||
TERN_(MIXING_EXTRUDER, mixer.T(old_mixing_tool)); // Restore original mixing tool
|
||||
|
@@ -53,9 +53,7 @@ void GcodeSuite::M430() {
|
||||
SERIAL_ECHOLNPGM(
|
||||
#if ENABLED(POWER_MONITOR_CURRENT)
|
||||
"Current: ", power_monitor.getAmps(), "A"
|
||||
#if ENABLED(POWER_MONITOR_VOLTAGE)
|
||||
" "
|
||||
#endif
|
||||
TERN_(POWER_MONITOR_VOLTAGE, " ")
|
||||
#endif
|
||||
#if ENABLED(POWER_MONITOR_VOLTAGE)
|
||||
"Voltage: ", power_monitor.getVolts(), "V"
|
||||
|
@@ -33,8 +33,8 @@
|
||||
#include "../../../lcd/extui/ui_api.h"
|
||||
#elif ENABLED(DWIN_CREALITY_LCD)
|
||||
#include "../../../lcd/e3v2/creality/dwin.h"
|
||||
#elif ENABLED(DWIN_CREALITY_LCD_ENHANCED)
|
||||
#include "../../../lcd/e3v2/enhanced/dwin.h"
|
||||
#elif ENABLED(DWIN_LCD_PROUI)
|
||||
#include "../../../lcd/e3v2/proui/dwin.h"
|
||||
#elif ENABLED(DWIN_CREALITY_LCD_JYERSUI)
|
||||
#include "../../../lcd/e3v2/jyersui/dwin.h" // Temporary fix until it can be better implemented
|
||||
#endif
|
||||
@@ -44,17 +44,17 @@
|
||||
|
||||
void menu_job_recovery();
|
||||
|
||||
inline void plr_error(PGM_P const prefix) {
|
||||
inline void plr_error(FSTR_P const prefix) {
|
||||
#if ENABLED(DEBUG_POWER_LOSS_RECOVERY)
|
||||
DEBUG_ECHO_START();
|
||||
DEBUG_ECHOPGM_P(prefix);
|
||||
DEBUG_ECHOF(prefix);
|
||||
DEBUG_ECHOLNPGM(" Job Recovery Data");
|
||||
#else
|
||||
UNUSED(prefix);
|
||||
#endif
|
||||
}
|
||||
|
||||
#if HAS_LCD_MENU
|
||||
#if HAS_MARLINUI_MENU
|
||||
void lcd_power_loss_recovery_cancel();
|
||||
#endif
|
||||
|
||||
@@ -67,7 +67,7 @@ void GcodeSuite::M1000() {
|
||||
|
||||
if (recovery.valid()) {
|
||||
if (parser.seen_test('S')) {
|
||||
#if HAS_LCD_MENU
|
||||
#if HAS_MARLINUI_MENU
|
||||
ui.goto_screen(menu_job_recovery);
|
||||
#elif HAS_DWIN_E3V2_BASIC
|
||||
recovery.dwin_flag = true;
|
||||
@@ -80,7 +80,7 @@ void GcodeSuite::M1000() {
|
||||
#endif
|
||||
}
|
||||
else if (parser.seen_test('C')) {
|
||||
#if HAS_LCD_MENU
|
||||
#if HAS_MARLINUI_MENU
|
||||
lcd_power_loss_recovery_cancel();
|
||||
#else
|
||||
recovery.cancel();
|
||||
@@ -91,7 +91,7 @@ void GcodeSuite::M1000() {
|
||||
recovery.resume();
|
||||
}
|
||||
else
|
||||
plr_error(recovery.info.valid_head ? PSTR("No") : PSTR("Invalid"));
|
||||
plr_error(recovery.info.valid_head ? F("No") : F("Invalid"));
|
||||
|
||||
}
|
||||
|
||||
|
@@ -47,17 +47,16 @@ void GcodeSuite::M413() {
|
||||
if (parser.seen("RL")) recovery.load();
|
||||
if (parser.seen_test('W')) recovery.save(true);
|
||||
if (parser.seen_test('P')) recovery.purge();
|
||||
if (parser.seen_test('D')) recovery.debug(PSTR("M413"));
|
||||
#if PIN_EXISTS(POWER_LOSS)
|
||||
if (parser.seen_test('O')) recovery._outage();
|
||||
#endif
|
||||
if (parser.seen_test('E')) SERIAL_ECHOPGM_P(recovery.exists() ? PSTR("PLR Exists\n") : PSTR("No PLR\n"));
|
||||
if (parser.seen_test('V')) SERIAL_ECHOPGM_P(recovery.valid() ? PSTR("Valid\n") : PSTR("Invalid\n"));
|
||||
if (parser.seen_test('D')) recovery.debug(F("M413"));
|
||||
if (parser.seen_test('O')) recovery._outage(true);
|
||||
if (parser.seen_test('C')) (void)recovery.check();
|
||||
if (parser.seen_test('E')) SERIAL_ECHOF(recovery.exists() ? F("PLR Exists\n") : F("No PLR\n"));
|
||||
if (parser.seen_test('V')) SERIAL_ECHOF(recovery.valid() ? F("Valid\n") : F("Invalid\n"));
|
||||
#endif
|
||||
}
|
||||
|
||||
void GcodeSuite::M413_report(const bool forReplay/*=true*/) {
|
||||
report_heading_etc(forReplay, PSTR(STR_POWER_LOSS_RECOVERY));
|
||||
report_heading_etc(forReplay, F(STR_POWER_LOSS_RECOVERY));
|
||||
SERIAL_ECHOPGM(" M413 S", AS_DIGIT(recovery.enabled), " ; ");
|
||||
serialprintln_onoff(recovery.enabled);
|
||||
}
|
||||
|
@@ -48,7 +48,7 @@ void GcodeSuite::M412() {
|
||||
if (seenR || seenS) runout.reset();
|
||||
if (seenS) runout.enabled = parser.value_bool();
|
||||
#if HAS_FILAMENT_RUNOUT_DISTANCE
|
||||
if (parser.seen('D')) runout.set_runout_distance(parser.value_linear_units());
|
||||
if (parser.seenval('D')) runout.set_runout_distance(parser.value_linear_units());
|
||||
#endif
|
||||
}
|
||||
else {
|
||||
@@ -67,7 +67,7 @@ void GcodeSuite::M412() {
|
||||
}
|
||||
|
||||
void GcodeSuite::M412_report(const bool forReplay/*=true*/) {
|
||||
report_heading_etc(forReplay, PSTR(STR_FILAMENT_RUNOUT_SENSOR));
|
||||
report_heading_etc(forReplay, F(STR_FILAMENT_RUNOUT_SENSOR));
|
||||
SERIAL_ECHOPGM(
|
||||
" M412 S", runout.enabled
|
||||
#if HAS_FILAMENT_RUNOUT_DISTANCE
|
||||
|
@@ -26,7 +26,7 @@
|
||||
|
||||
#include "../../gcode.h"
|
||||
#include "../../../feature/tmc_util.h"
|
||||
#include "../../../module/stepper/indirection.h"
|
||||
#include "../../../module/stepper/indirection.h" // for restore_stepper_drivers
|
||||
|
||||
/**
|
||||
* M122: Debug TMC drivers
|
||||
@@ -35,7 +35,7 @@ void GcodeSuite::M122() {
|
||||
xyze_bool_t print_axis = ARRAY_N_1(LOGICAL_AXES, false);
|
||||
|
||||
bool print_all = true;
|
||||
LOOP_LOGICAL_AXES(i) if (parser.seen_test(axis_codes[i])) { print_axis[i] = true; print_all = false; }
|
||||
LOOP_LOGICAL_AXES(i) if (parser.seen_test(AXIS_CHAR(i))) { print_axis[i] = true; print_all = false; }
|
||||
|
||||
if (print_all) LOOP_LOGICAL_AXES(i) print_axis[i] = true;
|
||||
|
||||
|
@@ -24,6 +24,10 @@
|
||||
|
||||
#if HAS_STEALTHCHOP
|
||||
|
||||
#if AXIS_COLLISION('I')
|
||||
#error "M569 parameter 'I' collision with axis name."
|
||||
#endif
|
||||
|
||||
#include "../../gcode.h"
|
||||
#include "../../../feature/tmc_util.h"
|
||||
#include "../../../module/stepper/indirection.h"
|
||||
@@ -32,7 +36,7 @@ template<typename TMC>
|
||||
void tmc_say_stealth_status(TMC &st) {
|
||||
st.printLabel();
|
||||
SERIAL_ECHOPGM(" driver mode:\t");
|
||||
SERIAL_ECHOLNPGM_P(st.get_stealthChop() ? PSTR("stealthChop") : PSTR("spreadCycle"));
|
||||
SERIAL_ECHOLNF(st.get_stealthChop() ? F("stealthChop") : F("spreadCycle"));
|
||||
}
|
||||
template<typename TMC>
|
||||
void tmc_set_stealthChop(TMC &st, const bool enable) {
|
||||
@@ -40,35 +44,35 @@ void tmc_set_stealthChop(TMC &st, const bool enable) {
|
||||
st.refresh_stepping_mode();
|
||||
}
|
||||
|
||||
static void set_stealth_status(const bool enable, const int8_t target_e_stepper) {
|
||||
static void set_stealth_status(const bool enable, const int8_t eindex) {
|
||||
#define TMC_SET_STEALTH(Q) tmc_set_stealthChop(stepper##Q, enable)
|
||||
|
||||
#if X_HAS_STEALTHCHOP || Y_HAS_STEALTHCHOP || Z_HAS_STEALTHCHOP \
|
||||
|| I_HAS_STEALTHCHOP || J_HAS_STEALTHCHOP || K_HAS_STEALTHCHOP \
|
||||
|| X2_HAS_STEALTHCHOP || Y2_HAS_STEALTHCHOP || Z2_HAS_STEALTHCHOP || Z3_HAS_STEALTHCHOP || Z4_HAS_STEALTHCHOP
|
||||
const uint8_t index = parser.byteval('I');
|
||||
#if X2_HAS_STEALTHCHOP || Y2_HAS_STEALTHCHOP || Z2_HAS_STEALTHCHOP || Z3_HAS_STEALTHCHOP || Z4_HAS_STEALTHCHOP
|
||||
const int8_t index = parser.byteval('I', -1);
|
||||
#else
|
||||
constexpr int8_t index = -1;
|
||||
#endif
|
||||
|
||||
LOOP_LOGICAL_AXES(i) if (parser.seen(axis_codes[i])) {
|
||||
LOOP_LOGICAL_AXES(i) if (parser.seen(AXIS_CHAR(i))) {
|
||||
switch (i) {
|
||||
case X_AXIS:
|
||||
TERN_(X_HAS_STEALTHCHOP, if (index == 0) TMC_SET_STEALTH(X));
|
||||
TERN_(X2_HAS_STEALTHCHOP, if (index == 1) TMC_SET_STEALTH(X2));
|
||||
TERN_(X_HAS_STEALTHCHOP, if (index < 0 || index == 0) TMC_SET_STEALTH(X));
|
||||
TERN_(X2_HAS_STEALTHCHOP, if (index < 0 || index == 1) TMC_SET_STEALTH(X2));
|
||||
break;
|
||||
|
||||
#if HAS_Y_AXIS
|
||||
case Y_AXIS:
|
||||
TERN_(Y_HAS_STEALTHCHOP, if (index == 0) TMC_SET_STEALTH(Y));
|
||||
TERN_(Y2_HAS_STEALTHCHOP, if (index == 1) TMC_SET_STEALTH(Y2));
|
||||
TERN_(Y_HAS_STEALTHCHOP, if (index < 0 || index == 0) TMC_SET_STEALTH(Y));
|
||||
TERN_(Y2_HAS_STEALTHCHOP, if (index < 0 || index == 1) TMC_SET_STEALTH(Y2));
|
||||
break;
|
||||
#endif
|
||||
|
||||
#if HAS_Z_AXIS
|
||||
case Z_AXIS:
|
||||
TERN_(Z_HAS_STEALTHCHOP, if (index == 0) TMC_SET_STEALTH(Z));
|
||||
TERN_(Z2_HAS_STEALTHCHOP, if (index == 1) TMC_SET_STEALTH(Z2));
|
||||
TERN_(Z3_HAS_STEALTHCHOP, if (index == 2) TMC_SET_STEALTH(Z3));
|
||||
TERN_(Z4_HAS_STEALTHCHOP, if (index == 3) TMC_SET_STEALTH(Z4));
|
||||
TERN_(Z_HAS_STEALTHCHOP, if (index < 0 || index == 0) TMC_SET_STEALTH(Z));
|
||||
TERN_(Z2_HAS_STEALTHCHOP, if (index < 0 || index == 1) TMC_SET_STEALTH(Z2));
|
||||
TERN_(Z3_HAS_STEALTHCHOP, if (index < 0 || index == 2) TMC_SET_STEALTH(Z3));
|
||||
TERN_(Z4_HAS_STEALTHCHOP, if (index < 0 || index == 3) TMC_SET_STEALTH(Z4));
|
||||
break;
|
||||
#endif
|
||||
|
||||
@@ -81,20 +85,26 @@ static void set_stealth_status(const bool enable, const int8_t target_e_stepper)
|
||||
#if K_HAS_STEALTHCHOP
|
||||
case K_AXIS: TMC_SET_STEALTH(K); break;
|
||||
#endif
|
||||
#if U_HAS_STEALTHCHOP
|
||||
case U_AXIS: TMC_SET_STEALTH(U); break;
|
||||
#endif
|
||||
#if V_HAS_STEALTHCHOP
|
||||
case V_AXIS: TMC_SET_STEALTH(V); break;
|
||||
#endif
|
||||
#if W_HAS_STEALTHCHOP
|
||||
case W_AXIS: TMC_SET_STEALTH(W); break;
|
||||
#endif
|
||||
|
||||
#if E_STEPPERS
|
||||
case E_AXIS: {
|
||||
if (target_e_stepper < 0) return;
|
||||
switch (target_e_stepper) {
|
||||
TERN_(E0_HAS_STEALTHCHOP, case 0: TMC_SET_STEALTH(E0); break;)
|
||||
TERN_(E1_HAS_STEALTHCHOP, case 1: TMC_SET_STEALTH(E1); break;)
|
||||
TERN_(E2_HAS_STEALTHCHOP, case 2: TMC_SET_STEALTH(E2); break;)
|
||||
TERN_(E3_HAS_STEALTHCHOP, case 3: TMC_SET_STEALTH(E3); break;)
|
||||
TERN_(E4_HAS_STEALTHCHOP, case 4: TMC_SET_STEALTH(E4); break;)
|
||||
TERN_(E5_HAS_STEALTHCHOP, case 5: TMC_SET_STEALTH(E5); break;)
|
||||
TERN_(E6_HAS_STEALTHCHOP, case 6: TMC_SET_STEALTH(E6); break;)
|
||||
TERN_(E7_HAS_STEALTHCHOP, case 7: TMC_SET_STEALTH(E7); break;)
|
||||
}
|
||||
TERN_(E0_HAS_STEALTHCHOP, if (eindex < 0 || eindex == 0) TMC_SET_STEALTH(E0));
|
||||
TERN_(E1_HAS_STEALTHCHOP, if (eindex < 0 || eindex == 1) TMC_SET_STEALTH(E1));
|
||||
TERN_(E2_HAS_STEALTHCHOP, if (eindex < 0 || eindex == 2) TMC_SET_STEALTH(E2));
|
||||
TERN_(E3_HAS_STEALTHCHOP, if (eindex < 0 || eindex == 3) TMC_SET_STEALTH(E3));
|
||||
TERN_(E4_HAS_STEALTHCHOP, if (eindex < 0 || eindex == 4) TMC_SET_STEALTH(E4));
|
||||
TERN_(E5_HAS_STEALTHCHOP, if (eindex < 0 || eindex == 5) TMC_SET_STEALTH(E5));
|
||||
TERN_(E6_HAS_STEALTHCHOP, if (eindex < 0 || eindex == 6) TMC_SET_STEALTH(E6));
|
||||
TERN_(E7_HAS_STEALTHCHOP, if (eindex < 0 || eindex == 7) TMC_SET_STEALTH(E7));
|
||||
} break;
|
||||
#endif
|
||||
}
|
||||
@@ -114,6 +124,9 @@ static void say_stealth_status() {
|
||||
OPTCODE( I_HAS_STEALTHCHOP, TMC_SAY_STEALTH_STATUS(I))
|
||||
OPTCODE( J_HAS_STEALTHCHOP, TMC_SAY_STEALTH_STATUS(J))
|
||||
OPTCODE( K_HAS_STEALTHCHOP, TMC_SAY_STEALTH_STATUS(K))
|
||||
OPTCODE( U_HAS_STEALTHCHOP, TMC_SAY_STEALTH_STATUS(U))
|
||||
OPTCODE( V_HAS_STEALTHCHOP, TMC_SAY_STEALTH_STATUS(V))
|
||||
OPTCODE( W_HAS_STEALTHCHOP, TMC_SAY_STEALTH_STATUS(W))
|
||||
OPTCODE(E0_HAS_STEALTHCHOP, TMC_SAY_STEALTH_STATUS(E0))
|
||||
OPTCODE(E1_HAS_STEALTHCHOP, TMC_SAY_STEALTH_STATUS(E1))
|
||||
OPTCODE(E2_HAS_STEALTHCHOP, TMC_SAY_STEALTH_STATUS(E2))
|
||||
@@ -133,20 +146,20 @@ static void say_stealth_status() {
|
||||
*/
|
||||
void GcodeSuite::M569() {
|
||||
if (parser.seen('S'))
|
||||
set_stealth_status(parser.value_bool(), get_target_e_stepper_from_command());
|
||||
set_stealth_status(parser.value_bool(), get_target_e_stepper_from_command(-2));
|
||||
else
|
||||
say_stealth_status();
|
||||
}
|
||||
|
||||
void GcodeSuite::M569_report(const bool forReplay/*=true*/) {
|
||||
report_heading(forReplay, PSTR(STR_DRIVER_STEPPING_MODE));
|
||||
report_heading(forReplay, F(STR_DRIVER_STEPPING_MODE));
|
||||
|
||||
auto say_M569 = [](const bool forReplay, const char * const etc=nullptr, const bool eol=false) {
|
||||
auto say_M569 = [](const bool forReplay, FSTR_P const etc=nullptr, const bool eol=false) {
|
||||
if (!forReplay) SERIAL_ECHO_START();
|
||||
SERIAL_ECHOPGM(" M569 S1");
|
||||
if (etc) {
|
||||
SERIAL_CHAR(' ');
|
||||
SERIAL_ECHOPGM_P(etc);
|
||||
SERIAL_ECHOF(etc);
|
||||
}
|
||||
if (eol) SERIAL_EOL();
|
||||
};
|
||||
@@ -156,17 +169,23 @@ void GcodeSuite::M569_report(const bool forReplay/*=true*/) {
|
||||
chop_z = TERN0(Z_HAS_STEALTHCHOP, stepperZ.get_stored_stealthChop()),
|
||||
chop_i = TERN0(I_HAS_STEALTHCHOP, stepperI.get_stored_stealthChop()),
|
||||
chop_j = TERN0(J_HAS_STEALTHCHOP, stepperJ.get_stored_stealthChop()),
|
||||
chop_k = TERN0(K_HAS_STEALTHCHOP, stepperK.get_stored_stealthChop());
|
||||
chop_k = TERN0(K_HAS_STEALTHCHOP, stepperK.get_stored_stealthChop()),
|
||||
chop_u = TERN0(U_HAS_STEALTHCHOP, stepperU.get_stored_stealthChop()),
|
||||
chop_v = TERN0(V_HAS_STEALTHCHOP, stepperV.get_stored_stealthChop()),
|
||||
chop_w = TERN0(W_HAS_STEALTHCHOP, stepperW.get_stored_stealthChop());
|
||||
|
||||
if (chop_x || chop_y || chop_z || chop_i || chop_j || chop_k) {
|
||||
if (chop_x || chop_y || chop_z || chop_i || chop_j || chop_k || chop_u || chop_v || chop_w) {
|
||||
say_M569(forReplay);
|
||||
LINEAR_AXIS_CODE(
|
||||
NUM_AXIS_CODE(
|
||||
if (chop_x) SERIAL_ECHOPGM_P(SP_X_STR),
|
||||
if (chop_y) SERIAL_ECHOPGM_P(SP_Y_STR),
|
||||
if (chop_z) SERIAL_ECHOPGM_P(SP_Z_STR),
|
||||
if (chop_i) SERIAL_ECHOPGM_P(SP_I_STR),
|
||||
if (chop_j) SERIAL_ECHOPGM_P(SP_J_STR),
|
||||
if (chop_k) SERIAL_ECHOPGM_P(SP_K_STR)
|
||||
if (chop_k) SERIAL_ECHOPGM_P(SP_K_STR),
|
||||
if (chop_u) SERIAL_ECHOPGM_P(SP_U_STR),
|
||||
if (chop_v) SERIAL_ECHOPGM_P(SP_V_STR),
|
||||
if (chop_w) SERIAL_ECHOPGM_P(SP_W_STR)
|
||||
);
|
||||
SERIAL_EOL();
|
||||
}
|
||||
@@ -176,28 +195,41 @@ void GcodeSuite::M569_report(const bool forReplay/*=true*/) {
|
||||
chop_z2 = TERN0(Z2_HAS_STEALTHCHOP, stepperZ2.get_stored_stealthChop());
|
||||
|
||||
if (chop_x2 || chop_y2 || chop_z2) {
|
||||
say_M569(forReplay, PSTR("I1"));
|
||||
say_M569(forReplay, F("I1"));
|
||||
if (chop_x2) SERIAL_ECHOPGM_P(SP_X_STR);
|
||||
if (chop_y2) SERIAL_ECHOPGM_P(SP_Y_STR);
|
||||
if (chop_z2) SERIAL_ECHOPGM_P(SP_Z_STR);
|
||||
SERIAL_EOL();
|
||||
}
|
||||
|
||||
if (TERN0(Z3_HAS_STEALTHCHOP, stepperZ3.get_stored_stealthChop())) { say_M569(forReplay, PSTR("I2 Z"), true); }
|
||||
if (TERN0(Z4_HAS_STEALTHCHOP, stepperZ4.get_stored_stealthChop())) { say_M569(forReplay, PSTR("I3 Z"), true); }
|
||||
|
||||
if (TERN0( I_HAS_STEALTHCHOP, stepperI.get_stored_stealthChop())) { say_M569(forReplay, SP_I_STR, true); }
|
||||
if (TERN0( J_HAS_STEALTHCHOP, stepperJ.get_stored_stealthChop())) { say_M569(forReplay, SP_J_STR, true); }
|
||||
if (TERN0( K_HAS_STEALTHCHOP, stepperK.get_stored_stealthChop())) { say_M569(forReplay, SP_K_STR, true); }
|
||||
|
||||
if (TERN0(E0_HAS_STEALTHCHOP, stepperE0.get_stored_stealthChop())) { say_M569(forReplay, PSTR("T0 E"), true); }
|
||||
if (TERN0(E1_HAS_STEALTHCHOP, stepperE1.get_stored_stealthChop())) { say_M569(forReplay, PSTR("T1 E"), true); }
|
||||
if (TERN0(E2_HAS_STEALTHCHOP, stepperE2.get_stored_stealthChop())) { say_M569(forReplay, PSTR("T2 E"), true); }
|
||||
if (TERN0(E3_HAS_STEALTHCHOP, stepperE3.get_stored_stealthChop())) { say_M569(forReplay, PSTR("T3 E"), true); }
|
||||
if (TERN0(E4_HAS_STEALTHCHOP, stepperE4.get_stored_stealthChop())) { say_M569(forReplay, PSTR("T4 E"), true); }
|
||||
if (TERN0(E5_HAS_STEALTHCHOP, stepperE5.get_stored_stealthChop())) { say_M569(forReplay, PSTR("T5 E"), true); }
|
||||
if (TERN0(E6_HAS_STEALTHCHOP, stepperE6.get_stored_stealthChop())) { say_M569(forReplay, PSTR("T6 E"), true); }
|
||||
if (TERN0(E7_HAS_STEALTHCHOP, stepperE7.get_stored_stealthChop())) { say_M569(forReplay, PSTR("T7 E"), true); }
|
||||
if (TERN0(Z3_HAS_STEALTHCHOP, stepperZ3.get_stored_stealthChop())) { say_M569(forReplay, F("I2 Z"), true); }
|
||||
if (TERN0(Z4_HAS_STEALTHCHOP, stepperZ4.get_stored_stealthChop())) { say_M569(forReplay, F("I3 Z"), true); }
|
||||
#if HAS_I_AXIS
|
||||
if (TERN0(I_HAS_STEALTHCHOP, stepperI.get_stored_stealthChop())) { say_M569(forReplay, FPSTR(SP_I_STR), true); }
|
||||
#endif
|
||||
#if HAS_J_AXIS
|
||||
if (TERN0(J_HAS_STEALTHCHOP, stepperJ.get_stored_stealthChop())) { say_M569(forReplay, FPSTR(SP_J_STR), true); }
|
||||
#endif
|
||||
#if HAS_K_AXIS
|
||||
if (TERN0(K_HAS_STEALTHCHOP, stepperK.get_stored_stealthChop())) { say_M569(forReplay, FPSTR(SP_K_STR), true); }
|
||||
#endif
|
||||
#if HAS_U_AXIS
|
||||
if (TERN0(U_HAS_STEALTHCHOP, stepperU.get_stored_stealthChop())) { say_M569(forReplay, FPSTR(SP_U_STR), true); }
|
||||
#endif
|
||||
#if HAS_V_AXIS
|
||||
if (TERN0(V_HAS_STEALTHCHOP, stepperV.get_stored_stealthChop())) { say_M569(forReplay, FPSTR(SP_V_STR), true); }
|
||||
#endif
|
||||
#if HAS_W_AXIS
|
||||
if (TERN0(W_HAS_STEALTHCHOP, stepperW.get_stored_stealthChop())) { say_M569(forReplay, FPSTR(SP_W_STR), true); }
|
||||
#endif
|
||||
if (TERN0(E0_HAS_STEALTHCHOP, stepperE0.get_stored_stealthChop())) { say_M569(forReplay, F("T0 E"), true); }
|
||||
if (TERN0(E1_HAS_STEALTHCHOP, stepperE1.get_stored_stealthChop())) { say_M569(forReplay, F("T1 E"), true); }
|
||||
if (TERN0(E2_HAS_STEALTHCHOP, stepperE2.get_stored_stealthChop())) { say_M569(forReplay, F("T2 E"), true); }
|
||||
if (TERN0(E3_HAS_STEALTHCHOP, stepperE3.get_stored_stealthChop())) { say_M569(forReplay, F("T3 E"), true); }
|
||||
if (TERN0(E4_HAS_STEALTHCHOP, stepperE4.get_stored_stealthChop())) { say_M569(forReplay, F("T4 E"), true); }
|
||||
if (TERN0(E5_HAS_STEALTHCHOP, stepperE5.get_stored_stealthChop())) { say_M569(forReplay, F("T5 E"), true); }
|
||||
if (TERN0(E6_HAS_STEALTHCHOP, stepperE6.get_stored_stealthChop())) { say_M569(forReplay, F("T6 E"), true); }
|
||||
if (TERN0(E7_HAS_STEALTHCHOP, stepperE7.get_stored_stealthChop())) { say_M569(forReplay, F("T7 E"), true); }
|
||||
}
|
||||
|
||||
#endif // HAS_STEALTHCHOP
|
||||
|
@@ -28,6 +28,12 @@
|
||||
#include "../../../feature/tmc_util.h"
|
||||
#include "../../../module/stepper/indirection.h"
|
||||
|
||||
template<typename TMC>
|
||||
static void tmc_print_current(TMC &st) {
|
||||
st.printLabel();
|
||||
SERIAL_ECHOLNPGM(" driver current: ", st.getMilliamps());
|
||||
}
|
||||
|
||||
/**
|
||||
* M906: Set motor current in milliamps.
|
||||
*
|
||||
@@ -35,6 +41,12 @@
|
||||
* X[current] - Set mA current for X driver(s)
|
||||
* Y[current] - Set mA current for Y driver(s)
|
||||
* Z[current] - Set mA current for Z driver(s)
|
||||
* A[current] - Set mA current for A driver(s) (Requires AXIS*_NAME 'A')
|
||||
* B[current] - Set mA current for B driver(s) (Requires AXIS*_NAME 'B')
|
||||
* C[current] - Set mA current for C driver(s) (Requires AXIS*_NAME 'C')
|
||||
* U[current] - Set mA current for U driver(s) (Requires AXIS*_NAME 'U')
|
||||
* V[current] - Set mA current for V driver(s) (Requires AXIS*_NAME 'V')
|
||||
* W[current] - Set mA current for W driver(s) (Requires AXIS*_NAME 'W')
|
||||
* E[current] - Set mA current for E driver(s)
|
||||
*
|
||||
* I[index] - Axis sub-index (Omit or 0 for X, Y, Z; 1 for X2, Y2, Z2; 2 for Z3; 3 for Z4.)
|
||||
@@ -48,46 +60,50 @@ void GcodeSuite::M906() {
|
||||
|
||||
bool report = true;
|
||||
|
||||
#if AXIS_IS_TMC(X) || AXIS_IS_TMC(X2) || AXIS_IS_TMC(Y) || AXIS_IS_TMC(Y2) || AXIS_IS_TMC(Z) || AXIS_IS_TMC(Z2) || AXIS_IS_TMC(Z3) || AXIS_IS_TMC(Z4) || AXIS_IS_TMC(I) || AXIS_IS_TMC(J) || AXIS_IS_TMC(K)
|
||||
const uint8_t index = parser.byteval('I');
|
||||
#if AXIS_IS_TMC(X2) || AXIS_IS_TMC(Y2) || AXIS_IS_TMC(Z2) || AXIS_IS_TMC(Z3) || AXIS_IS_TMC(Z4)
|
||||
const int8_t index = parser.byteval('I', -1);
|
||||
#elif AXIS_IS_TMC(X) || AXIS_IS_TMC(Y) || AXIS_IS_TMC(Z)
|
||||
constexpr int8_t index = -1;
|
||||
#endif
|
||||
|
||||
LOOP_LOGICAL_AXES(i) if (uint16_t value = parser.intval(axis_codes[i])) {
|
||||
LOOP_LOGICAL_AXES(i) if (uint16_t value = parser.intval(AXIS_CHAR(i))) {
|
||||
report = false;
|
||||
switch (i) {
|
||||
case X_AXIS:
|
||||
#if AXIS_IS_TMC(X)
|
||||
if (index == 0) TMC_SET_CURRENT(X);
|
||||
#endif
|
||||
#if AXIS_IS_TMC(X2)
|
||||
if (index == 1) TMC_SET_CURRENT(X2);
|
||||
#endif
|
||||
break;
|
||||
|
||||
#if HAS_Y_AXIS
|
||||
case Y_AXIS:
|
||||
#if AXIS_IS_TMC(Y)
|
||||
if (index == 0) TMC_SET_CURRENT(Y);
|
||||
#if AXIS_IS_TMC(X) || AXIS_IS_TMC(X2)
|
||||
case X_AXIS:
|
||||
#if AXIS_IS_TMC(X)
|
||||
if (index < 0 || index == 0) TMC_SET_CURRENT(X);
|
||||
#endif
|
||||
#if AXIS_IS_TMC(Y2)
|
||||
if (index == 1) TMC_SET_CURRENT(Y2);
|
||||
#if AXIS_IS_TMC(X2)
|
||||
if (index < 0 || index == 1) TMC_SET_CURRENT(X2);
|
||||
#endif
|
||||
break;
|
||||
#endif
|
||||
|
||||
#if HAS_Z_AXIS
|
||||
#if AXIS_IS_TMC(Y) || AXIS_IS_TMC(Y2)
|
||||
case Y_AXIS:
|
||||
#if AXIS_IS_TMC(Y)
|
||||
if (index < 0 || index == 0) TMC_SET_CURRENT(Y);
|
||||
#endif
|
||||
#if AXIS_IS_TMC(Y2)
|
||||
if (index < 0 || index == 1) TMC_SET_CURRENT(Y2);
|
||||
#endif
|
||||
break;
|
||||
#endif
|
||||
|
||||
#if AXIS_IS_TMC(Z) || AXIS_IS_TMC(Z2) || AXIS_IS_TMC(Z3) || AXIS_IS_TMC(Z4)
|
||||
case Z_AXIS:
|
||||
#if AXIS_IS_TMC(Z)
|
||||
if (index == 0) TMC_SET_CURRENT(Z);
|
||||
if (index < 0 || index == 0) TMC_SET_CURRENT(Z);
|
||||
#endif
|
||||
#if AXIS_IS_TMC(Z2)
|
||||
if (index == 1) TMC_SET_CURRENT(Z2);
|
||||
if (index < 0 || index == 1) TMC_SET_CURRENT(Z2);
|
||||
#endif
|
||||
#if AXIS_IS_TMC(Z3)
|
||||
if (index == 2) TMC_SET_CURRENT(Z3);
|
||||
if (index < 0 || index == 2) TMC_SET_CURRENT(Z3);
|
||||
#endif
|
||||
#if AXIS_IS_TMC(Z4)
|
||||
if (index == 3) TMC_SET_CURRENT(Z4);
|
||||
if (index < 0 || index == 3) TMC_SET_CURRENT(Z4);
|
||||
#endif
|
||||
break;
|
||||
#endif
|
||||
@@ -101,37 +117,43 @@ void GcodeSuite::M906() {
|
||||
#if AXIS_IS_TMC(K)
|
||||
case K_AXIS: TMC_SET_CURRENT(K); break;
|
||||
#endif
|
||||
#if AXIS_IS_TMC(U)
|
||||
case U_AXIS: TMC_SET_CURRENT(U); break;
|
||||
#endif
|
||||
#if AXIS_IS_TMC(V)
|
||||
case V_AXIS: TMC_SET_CURRENT(V); break;
|
||||
#endif
|
||||
#if AXIS_IS_TMC(W)
|
||||
case W_AXIS: TMC_SET_CURRENT(W); break;
|
||||
#endif
|
||||
|
||||
#if E_STEPPERS
|
||||
#if AXIS_IS_TMC(E0) || AXIS_IS_TMC(E1) || AXIS_IS_TMC(E2) || AXIS_IS_TMC(E3) || AXIS_IS_TMC(E4) || AXIS_IS_TMC(E5) || AXIS_IS_TMC(E6) || AXIS_IS_TMC(E7)
|
||||
case E_AXIS: {
|
||||
const int8_t target_e_stepper = get_target_e_stepper_from_command();
|
||||
if (target_e_stepper < 0) return;
|
||||
switch (target_e_stepper) {
|
||||
#if AXIS_IS_TMC(E0)
|
||||
case 0: TMC_SET_CURRENT(E0); break;
|
||||
#endif
|
||||
#if AXIS_IS_TMC(E1)
|
||||
case 1: TMC_SET_CURRENT(E1); break;
|
||||
#endif
|
||||
#if AXIS_IS_TMC(E2)
|
||||
case 2: TMC_SET_CURRENT(E2); break;
|
||||
#endif
|
||||
#if AXIS_IS_TMC(E3)
|
||||
case 3: TMC_SET_CURRENT(E3); break;
|
||||
#endif
|
||||
#if AXIS_IS_TMC(E4)
|
||||
case 4: TMC_SET_CURRENT(E4); break;
|
||||
#endif
|
||||
#if AXIS_IS_TMC(E5)
|
||||
case 5: TMC_SET_CURRENT(E5); break;
|
||||
#endif
|
||||
#if AXIS_IS_TMC(E6)
|
||||
case 6: TMC_SET_CURRENT(E6); break;
|
||||
#endif
|
||||
#if AXIS_IS_TMC(E7)
|
||||
case 7: TMC_SET_CURRENT(E7); break;
|
||||
#endif
|
||||
}
|
||||
const int8_t eindex = get_target_e_stepper_from_command(-2);
|
||||
#if AXIS_IS_TMC(E0)
|
||||
if (eindex < 0 || eindex == 0) TMC_SET_CURRENT(E0);
|
||||
#endif
|
||||
#if AXIS_IS_TMC(E1)
|
||||
if (eindex < 0 || eindex == 1) TMC_SET_CURRENT(E1);
|
||||
#endif
|
||||
#if AXIS_IS_TMC(E2)
|
||||
if (eindex < 0 || eindex == 2) TMC_SET_CURRENT(E2);
|
||||
#endif
|
||||
#if AXIS_IS_TMC(E3)
|
||||
if (eindex < 0 || eindex == 3) TMC_SET_CURRENT(E3);
|
||||
#endif
|
||||
#if AXIS_IS_TMC(E4)
|
||||
if (eindex < 0 || eindex == 4) TMC_SET_CURRENT(E4);
|
||||
#endif
|
||||
#if AXIS_IS_TMC(E5)
|
||||
if (eindex < 0 || eindex == 5) TMC_SET_CURRENT(E5);
|
||||
#endif
|
||||
#if AXIS_IS_TMC(E6)
|
||||
if (eindex < 0 || eindex == 6) TMC_SET_CURRENT(E6);
|
||||
#endif
|
||||
#if AXIS_IS_TMC(E7)
|
||||
if (eindex < 0 || eindex == 7) TMC_SET_CURRENT(E7);
|
||||
#endif
|
||||
} break;
|
||||
#endif
|
||||
}
|
||||
@@ -171,6 +193,16 @@ void GcodeSuite::M906() {
|
||||
#if AXIS_IS_TMC(K)
|
||||
TMC_SAY_CURRENT(K);
|
||||
#endif
|
||||
#if AXIS_IS_TMC(U)
|
||||
TMC_SAY_CURRENT(U);
|
||||
#endif
|
||||
#if AXIS_IS_TMC(V)
|
||||
TMC_SAY_CURRENT(V);
|
||||
#endif
|
||||
#if AXIS_IS_TMC(W)
|
||||
TMC_SAY_CURRENT(W);
|
||||
#endif
|
||||
|
||||
#if AXIS_IS_TMC(E0)
|
||||
TMC_SAY_CURRENT(E0);
|
||||
#endif
|
||||
@@ -199,7 +231,7 @@ void GcodeSuite::M906() {
|
||||
}
|
||||
|
||||
void GcodeSuite::M906_report(const bool forReplay/*=true*/) {
|
||||
report_heading(forReplay, PSTR(STR_STEPPER_DRIVER_CURRENT));
|
||||
report_heading(forReplay, F(STR_STEPPER_DRIVER_CURRENT));
|
||||
|
||||
auto say_M906 = [](const bool forReplay) {
|
||||
report_echo_start(forReplay);
|
||||
@@ -207,7 +239,8 @@ void GcodeSuite::M906_report(const bool forReplay/*=true*/) {
|
||||
};
|
||||
|
||||
#if AXIS_IS_TMC(X) || AXIS_IS_TMC(Y) || AXIS_IS_TMC(Z) \
|
||||
|| AXIS_IS_TMC(I) || AXIS_IS_TMC(J) || AXIS_IS_TMC(K)
|
||||
|| AXIS_IS_TMC(I) || AXIS_IS_TMC(J) || AXIS_IS_TMC(K) \
|
||||
|| AXIS_IS_TMC(U) || AXIS_IS_TMC(V) || AXIS_IS_TMC(W)
|
||||
say_M906(forReplay);
|
||||
#if AXIS_IS_TMC(X)
|
||||
SERIAL_ECHOPGM_P(SP_X_STR, stepperX.getMilliamps());
|
||||
@@ -227,6 +260,15 @@ void GcodeSuite::M906_report(const bool forReplay/*=true*/) {
|
||||
#if AXIS_IS_TMC(K)
|
||||
SERIAL_ECHOPGM_P(SP_K_STR, stepperK.getMilliamps());
|
||||
#endif
|
||||
#if AXIS_IS_TMC(U)
|
||||
SERIAL_ECHOPGM_P(SP_U_STR, stepperU.getMilliamps());
|
||||
#endif
|
||||
#if AXIS_IS_TMC(V)
|
||||
SERIAL_ECHOPGM_P(SP_V_STR, stepperV.getMilliamps());
|
||||
#endif
|
||||
#if AXIS_IS_TMC(W)
|
||||
SERIAL_ECHOPGM_P(SP_W_STR, stepperW.getMilliamps());
|
||||
#endif
|
||||
SERIAL_EOL();
|
||||
#endif
|
||||
|
||||
|
@@ -38,30 +38,54 @@
|
||||
#if M91x_USE(X) || M91x_USE(X2)
|
||||
#define M91x_SOME_X 1
|
||||
#endif
|
||||
#if LINEAR_AXES >= 2 && (M91x_USE(Y) || M91x_USE(Y2))
|
||||
#if HAS_Y_AXIS && (M91x_USE(Y) || M91x_USE(Y2))
|
||||
#define M91x_SOME_Y 1
|
||||
#endif
|
||||
#if HAS_Z_AXIS && (M91x_USE(Z) || M91x_USE(Z2) || M91x_USE(Z3) || M91x_USE(Z4))
|
||||
#define M91x_SOME_Z 1
|
||||
#endif
|
||||
#if LINEAR_AXES >= 4 && M91x_USE(I)
|
||||
#if HAS_I_AXIS && M91x_USE(I)
|
||||
#define M91x_USE_I 1
|
||||
#endif
|
||||
#if LINEAR_AXES >= 5 && M91x_USE(J)
|
||||
#if HAS_J_AXIS && M91x_USE(J)
|
||||
#define M91x_USE_J 1
|
||||
#endif
|
||||
#if LINEAR_AXES >= 6 && M91x_USE(K)
|
||||
#if HAS_K_AXIS && M91x_USE(K)
|
||||
#define M91x_USE_K 1
|
||||
#endif
|
||||
#if HAS_U_AXIS && M91x_USE(U)
|
||||
#define M91x_USE_U 1
|
||||
#endif
|
||||
#if HAS_V_AXIS && M91x_USE(V)
|
||||
#define M91x_USE_V 1
|
||||
#endif
|
||||
#if HAS_W_AXIS && M91x_USE(W)
|
||||
#define M91x_USE_W 1
|
||||
#endif
|
||||
|
||||
#if M91x_USE_E(0) || M91x_USE_E(1) || M91x_USE_E(2) || M91x_USE_E(3) || M91x_USE_E(4) || M91x_USE_E(5) || M91x_USE_E(6) || M91x_USE_E(7)
|
||||
#define M91x_SOME_E 1
|
||||
#endif
|
||||
|
||||
#if !M91x_SOME_X && !M91x_SOME_Y && !M91x_SOME_Z && !M91x_USE_I && !M91x_USE_J && !M91x_USE_K && !M91x_SOME_E
|
||||
#if !M91x_SOME_X && !M91x_SOME_Y && !M91x_SOME_Z && !M91x_USE_I && !M91x_USE_J && !M91x_USE_K && !M91x_USE_U && !M91x_USE_V && !M91x_USE_W && !M91x_SOME_E
|
||||
#error "MONITOR_DRIVER_STATUS requires at least one TMC2130, 2160, 2208, 2209, 2660, 5130, or 5160."
|
||||
#endif
|
||||
|
||||
template<typename TMC>
|
||||
static void tmc_report_otpw(TMC &st) {
|
||||
st.printLabel();
|
||||
SERIAL_ECHOPGM(" temperature prewarn triggered: ");
|
||||
serialprint_truefalse(st.getOTPW());
|
||||
SERIAL_EOL();
|
||||
}
|
||||
|
||||
template<typename TMC>
|
||||
static void tmc_clear_otpw(TMC &st) {
|
||||
st.clear_otpw();
|
||||
st.printLabel();
|
||||
SERIAL_ECHOLNPGM(" prewarn flag cleared");
|
||||
}
|
||||
|
||||
/**
|
||||
* M911: Report TMC stepper driver overtemperature pre-warn flag
|
||||
* This flag is held by the library, persisting until cleared by M912
|
||||
@@ -94,6 +118,9 @@
|
||||
TERN_(M91x_USE_I, tmc_report_otpw(stepperI));
|
||||
TERN_(M91x_USE_J, tmc_report_otpw(stepperJ));
|
||||
TERN_(M91x_USE_K, tmc_report_otpw(stepperK));
|
||||
TERN_(M91x_USE_U, tmc_report_otpw(stepperU));
|
||||
TERN_(M91x_USE_V, tmc_report_otpw(stepperV));
|
||||
TERN_(M91x_USE_W, tmc_report_otpw(stepperW));
|
||||
#if M91x_USE_E(0)
|
||||
tmc_report_otpw(stepperE0);
|
||||
#endif
|
||||
@@ -122,7 +149,7 @@
|
||||
|
||||
/**
|
||||
* M912: Clear TMC stepper driver overtemperature pre-warn flag held by the library
|
||||
* Specify one or more axes with X, Y, Z, X1, Y1, Z1, X2, Y2, Z2, Z3, Z4 and E[index].
|
||||
* Specify one or more axes with X, Y, Z, X1, Y1, Z1, X2, Y2, Z2, Z3, Z4, A, B, C, U, V, W, and E[index].
|
||||
* If no axes are given, clear all.
|
||||
*
|
||||
* Examples:
|
||||
@@ -139,9 +166,12 @@
|
||||
hasI = TERN0(M91x_USE_I, parser.seen(axis_codes.i)),
|
||||
hasJ = TERN0(M91x_USE_J, parser.seen(axis_codes.j)),
|
||||
hasK = TERN0(M91x_USE_K, parser.seen(axis_codes.k)),
|
||||
hasU = TERN0(M91x_USE_U, parser.seen(axis_codes.u)),
|
||||
hasV = TERN0(M91x_USE_V, parser.seen(axis_codes.v)),
|
||||
hasW = TERN0(M91x_USE_W, parser.seen(axis_codes.w)),
|
||||
hasE = TERN0(M91x_SOME_E, parser.seen(axis_codes.e));
|
||||
|
||||
const bool hasNone = !hasE && !hasX && !hasY && !hasZ && !hasI && !hasJ && !hasK;
|
||||
const bool hasNone = !hasE && !hasX && !hasY && !hasZ && !hasI && !hasJ && !hasK && !hasU && !hasV && !hasW;
|
||||
|
||||
#if M91x_SOME_X
|
||||
const int8_t xval = int8_t(parser.byteval(axis_codes.x, 0xFF));
|
||||
@@ -191,6 +221,18 @@
|
||||
const int8_t kval = int8_t(parser.byteval(axis_codes.k, 0xFF));
|
||||
if (hasNone || kval == 1 || (hasK && kval < 0)) tmc_clear_otpw(stepperK);
|
||||
#endif
|
||||
#if M91x_USE_U
|
||||
const int8_t uval = int8_t(parser.byteval(axis_codes.u, 0xFF));
|
||||
if (hasNone || uval == 1 || (hasU && uval < 0)) tmc_clear_otpw(stepperU);
|
||||
#endif
|
||||
#if M91x_USE_V
|
||||
const int8_t vval = int8_t(parser.byteval(axis_codes.v, 0xFF));
|
||||
if (hasNone || vval == 1 || (hasV && vval < 0)) tmc_clear_otpw(stepperV);
|
||||
#endif
|
||||
#if M91x_USE_W
|
||||
const int8_t wval = int8_t(parser.byteval(axis_codes.w, 0xFF));
|
||||
if (hasNone || wval == 1 || (hasW && wval < 0)) tmc_clear_otpw(stepperW);
|
||||
#endif
|
||||
|
||||
#if M91x_SOME_E
|
||||
const int8_t eval = int8_t(parser.byteval(axis_codes.e, 0xFF));
|
||||
@@ -223,11 +265,17 @@
|
||||
|
||||
#endif // MONITOR_DRIVER_STATUS
|
||||
|
||||
/**
|
||||
* M913: Set HYBRID_THRESHOLD speed.
|
||||
*/
|
||||
#if ENABLED(HYBRID_THRESHOLD)
|
||||
|
||||
template<typename TMC>
|
||||
static void tmc_print_pwmthrs(TMC &st) {
|
||||
st.printLabel();
|
||||
SERIAL_ECHOLNPGM(" stealthChop max speed: ", st.get_pwm_thrs());
|
||||
}
|
||||
|
||||
/**
|
||||
* M913: Set HYBRID_THRESHOLD speed.
|
||||
*/
|
||||
void GcodeSuite::M913() {
|
||||
#define TMC_SAY_PWMTHRS(A,Q) tmc_print_pwmthrs(stepper##Q)
|
||||
#define TMC_SET_PWMTHRS(A,Q) stepper##Q.set_pwm_thrs(value)
|
||||
@@ -235,20 +283,36 @@
|
||||
#define TMC_SET_PWMTHRS_E(E) stepperE##E.set_pwm_thrs(value)
|
||||
|
||||
bool report = true;
|
||||
#if AXIS_IS_TMC(X) || AXIS_IS_TMC(X2) || AXIS_IS_TMC(Y) || AXIS_IS_TMC(Y2) || AXIS_IS_TMC(Z) || AXIS_IS_TMC(Z2) || AXIS_IS_TMC(Z3) || AXIS_IS_TMC(Z4) || AXIS_IS_TMC(I) || AXIS_IS_TMC(J) || AXIS_IS_TMC(K)
|
||||
#if AXIS_IS_TMC(X2) || AXIS_IS_TMC(Y2) || AXIS_IS_TMC(Z2) || AXIS_IS_TMC(Z3) || AXIS_IS_TMC(Z4)
|
||||
const uint8_t index = parser.byteval('I');
|
||||
#elif AXIS_IS_TMC(X) || AXIS_IS_TMC(Y) || AXIS_IS_TMC(Z)
|
||||
constexpr uint8_t index = 0;
|
||||
#endif
|
||||
LOOP_LOGICAL_AXES(i) if (int32_t value = parser.longval(axis_codes[i])) {
|
||||
LOOP_LOGICAL_AXES(i) if (int32_t value = parser.longval(AXIS_CHAR(i))) {
|
||||
report = false;
|
||||
switch (i) {
|
||||
case X_AXIS:
|
||||
TERN_(X_HAS_STEALTHCHOP, if (index < 2) TMC_SET_PWMTHRS(X,X));
|
||||
TERN_(X2_HAS_STEALTHCHOP, if (!(index & 1)) TMC_SET_PWMTHRS(X,X2));
|
||||
break;
|
||||
case Y_AXIS:
|
||||
TERN_(Y_HAS_STEALTHCHOP, if (index < 2) TMC_SET_PWMTHRS(Y,Y));
|
||||
TERN_(Y2_HAS_STEALTHCHOP, if (!(index & 1)) TMC_SET_PWMTHRS(Y,Y2));
|
||||
break;
|
||||
#if X_HAS_STEALTHCHOP || X2_HAS_STEALTHCHOP
|
||||
case X_AXIS:
|
||||
TERN_(X_HAS_STEALTHCHOP, if (index < 2) TMC_SET_PWMTHRS(X,X));
|
||||
TERN_(X2_HAS_STEALTHCHOP, if (!(index & 1)) TMC_SET_PWMTHRS(X,X2));
|
||||
break;
|
||||
#endif
|
||||
|
||||
#if Y_HAS_STEALTHCHOP || Y2_HAS_STEALTHCHOP
|
||||
case Y_AXIS:
|
||||
TERN_(Y_HAS_STEALTHCHOP, if (index < 2) TMC_SET_PWMTHRS(Y,Y));
|
||||
TERN_(Y2_HAS_STEALTHCHOP, if (!(index & 1)) TMC_SET_PWMTHRS(Y,Y2));
|
||||
break;
|
||||
#endif
|
||||
|
||||
#if Z_HAS_STEALTHCHOP || Z2_HAS_STEALTHCHOP || Z3_HAS_STEALTHCHOP || Z4_HAS_STEALTHCHOP
|
||||
case Z_AXIS:
|
||||
TERN_(Z_HAS_STEALTHCHOP, if (index < 2) TMC_SET_PWMTHRS(Z,Z));
|
||||
TERN_(Z2_HAS_STEALTHCHOP, if (!index || index == 2) TMC_SET_PWMTHRS(Z,Z2));
|
||||
TERN_(Z3_HAS_STEALTHCHOP, if (!index || index == 3) TMC_SET_PWMTHRS(Z,Z3));
|
||||
TERN_(Z4_HAS_STEALTHCHOP, if (!index || index == 4) TMC_SET_PWMTHRS(Z,Z4));
|
||||
break;
|
||||
#endif
|
||||
|
||||
#if I_HAS_STEALTHCHOP
|
||||
case I_AXIS: TMC_SET_PWMTHRS(I,I); break;
|
||||
@@ -259,27 +323,27 @@
|
||||
#if K_HAS_STEALTHCHOP
|
||||
case K_AXIS: TMC_SET_PWMTHRS(K,K); break;
|
||||
#endif
|
||||
#if U_HAS_STEALTHCHOP
|
||||
case U_AXIS: TMC_SET_PWMTHRS(U,U); break;
|
||||
#endif
|
||||
#if V_HAS_STEALTHCHOP
|
||||
case V_AXIS: TMC_SET_PWMTHRS(V,V); break;
|
||||
#endif
|
||||
#if W_HAS_STEALTHCHOP
|
||||
case W_AXIS: TMC_SET_PWMTHRS(W,W); break;
|
||||
#endif
|
||||
|
||||
case Z_AXIS:
|
||||
TERN_(Z_HAS_STEALTHCHOP, if (index < 2) TMC_SET_PWMTHRS(Z,Z));
|
||||
TERN_(Z2_HAS_STEALTHCHOP, if (index == 0 || index == 2) TMC_SET_PWMTHRS(Z,Z2));
|
||||
TERN_(Z3_HAS_STEALTHCHOP, if (index == 0 || index == 3) TMC_SET_PWMTHRS(Z,Z3));
|
||||
TERN_(Z4_HAS_STEALTHCHOP, if (index == 0 || index == 4) TMC_SET_PWMTHRS(Z,Z4));
|
||||
break;
|
||||
#if E_STEPPERS
|
||||
#if E0_HAS_STEALTHCHOP || E1_HAS_STEALTHCHOP || E2_HAS_STEALTHCHOP || E3_HAS_STEALTHCHOP || E4_HAS_STEALTHCHOP || E5_HAS_STEALTHCHOP || E6_HAS_STEALTHCHOP || E7_HAS_STEALTHCHOP
|
||||
case E_AXIS: {
|
||||
const int8_t target_e_stepper = get_target_e_stepper_from_command();
|
||||
if (target_e_stepper < 0) return;
|
||||
switch (target_e_stepper) {
|
||||
TERN_(E0_HAS_STEALTHCHOP, case 0: TMC_SET_PWMTHRS_E(0); break;)
|
||||
TERN_(E1_HAS_STEALTHCHOP, case 1: TMC_SET_PWMTHRS_E(1); break;)
|
||||
TERN_(E2_HAS_STEALTHCHOP, case 2: TMC_SET_PWMTHRS_E(2); break;)
|
||||
TERN_(E3_HAS_STEALTHCHOP, case 3: TMC_SET_PWMTHRS_E(3); break;)
|
||||
TERN_(E4_HAS_STEALTHCHOP, case 4: TMC_SET_PWMTHRS_E(4); break;)
|
||||
TERN_(E5_HAS_STEALTHCHOP, case 5: TMC_SET_PWMTHRS_E(5); break;)
|
||||
TERN_(E6_HAS_STEALTHCHOP, case 6: TMC_SET_PWMTHRS_E(6); break;)
|
||||
TERN_(E7_HAS_STEALTHCHOP, case 7: TMC_SET_PWMTHRS_E(7); break;)
|
||||
}
|
||||
const int8_t eindex = get_target_e_stepper_from_command(-2);
|
||||
TERN_(E0_HAS_STEALTHCHOP, if (eindex < 0 || eindex == 0) TMC_SET_PWMTHRS_E(0));
|
||||
TERN_(E1_HAS_STEALTHCHOP, if (eindex < 0 || eindex == 1) TMC_SET_PWMTHRS_E(1));
|
||||
TERN_(E2_HAS_STEALTHCHOP, if (eindex < 0 || eindex == 2) TMC_SET_PWMTHRS_E(2));
|
||||
TERN_(E3_HAS_STEALTHCHOP, if (eindex < 0 || eindex == 3) TMC_SET_PWMTHRS_E(3));
|
||||
TERN_(E4_HAS_STEALTHCHOP, if (eindex < 0 || eindex == 4) TMC_SET_PWMTHRS_E(4));
|
||||
TERN_(E5_HAS_STEALTHCHOP, if (eindex < 0 || eindex == 5) TMC_SET_PWMTHRS_E(5));
|
||||
TERN_(E6_HAS_STEALTHCHOP, if (eindex < 0 || eindex == 6) TMC_SET_PWMTHRS_E(6));
|
||||
TERN_(E7_HAS_STEALTHCHOP, if (eindex < 0 || eindex == 7) TMC_SET_PWMTHRS_E(7));
|
||||
} break;
|
||||
#endif // E_STEPPERS
|
||||
}
|
||||
@@ -298,6 +362,9 @@
|
||||
TERN_( I_HAS_STEALTHCHOP, TMC_SAY_PWMTHRS(I,I));
|
||||
TERN_( J_HAS_STEALTHCHOP, TMC_SAY_PWMTHRS(J,J));
|
||||
TERN_( K_HAS_STEALTHCHOP, TMC_SAY_PWMTHRS(K,K));
|
||||
TERN_( U_HAS_STEALTHCHOP, TMC_SAY_PWMTHRS(U,U));
|
||||
TERN_( V_HAS_STEALTHCHOP, TMC_SAY_PWMTHRS(V,V));
|
||||
TERN_( W_HAS_STEALTHCHOP, TMC_SAY_PWMTHRS(W,W));
|
||||
|
||||
TERN_(E0_HAS_STEALTHCHOP, TMC_SAY_PWMTHRS_E(0));
|
||||
TERN_(E1_HAS_STEALTHCHOP, TMC_SAY_PWMTHRS_E(1));
|
||||
@@ -311,7 +378,7 @@
|
||||
}
|
||||
|
||||
void GcodeSuite::M913_report(const bool forReplay/*=true*/) {
|
||||
report_heading(forReplay, PSTR(STR_HYBRID_THRESHOLD));
|
||||
report_heading(forReplay, F(STR_HYBRID_THRESHOLD));
|
||||
|
||||
auto say_M913 = [](const bool forReplay) {
|
||||
report_echo_start(forReplay);
|
||||
@@ -334,7 +401,7 @@
|
||||
|
||||
#if X2_HAS_STEALTHCHOP || Y2_HAS_STEALTHCHOP || Z2_HAS_STEALTHCHOP
|
||||
say_M913(forReplay);
|
||||
SERIAL_ECHOPGM(" I1");
|
||||
SERIAL_ECHOPGM(" I2");
|
||||
#if X2_HAS_STEALTHCHOP
|
||||
SERIAL_ECHOPGM_P(SP_X_STR, stepperX2.get_pwm_thrs());
|
||||
#endif
|
||||
@@ -349,12 +416,12 @@
|
||||
|
||||
#if Z3_HAS_STEALTHCHOP
|
||||
say_M913(forReplay);
|
||||
SERIAL_ECHOLNPGM(" I2 Z", stepperZ3.get_pwm_thrs());
|
||||
SERIAL_ECHOLNPGM(" I3 Z", stepperZ3.get_pwm_thrs());
|
||||
#endif
|
||||
|
||||
#if Z4_HAS_STEALTHCHOP
|
||||
say_M913(forReplay);
|
||||
SERIAL_ECHOLNPGM(" I3 Z", stepperZ4.get_pwm_thrs());
|
||||
SERIAL_ECHOLNPGM(" I4 Z", stepperZ4.get_pwm_thrs());
|
||||
#endif
|
||||
|
||||
#if I_HAS_STEALTHCHOP
|
||||
@@ -369,6 +436,18 @@
|
||||
say_M913(forReplay);
|
||||
SERIAL_ECHOLNPGM_P(SP_K_STR, stepperK.get_pwm_thrs());
|
||||
#endif
|
||||
#if U_HAS_STEALTHCHOP
|
||||
say_M913(forReplay);
|
||||
SERIAL_ECHOLNPGM_P(SP_U_STR, stepperU.get_pwm_thrs());
|
||||
#endif
|
||||
#if V_HAS_STEALTHCHOP
|
||||
say_M913(forReplay);
|
||||
SERIAL_ECHOLNPGM_P(SP_V_STR, stepperV.get_pwm_thrs());
|
||||
#endif
|
||||
#if W_HAS_STEALTHCHOP
|
||||
say_M913(forReplay);
|
||||
SERIAL_ECHOLNPGM_P(SP_W_STR, stepperW.get_pwm_thrs());
|
||||
#endif
|
||||
|
||||
#if E0_HAS_STEALTHCHOP
|
||||
say_M913(forReplay);
|
||||
@@ -407,112 +486,87 @@
|
||||
|
||||
#endif // HYBRID_THRESHOLD
|
||||
|
||||
/**
|
||||
* M914: Set StallGuard sensitivity.
|
||||
*/
|
||||
#if USE_SENSORLESS
|
||||
|
||||
template<typename TMC>
|
||||
static void tmc_print_sgt(TMC &st) {
|
||||
st.printLabel();
|
||||
SERIAL_ECHOPGM(" homing sensitivity: ");
|
||||
SERIAL_PRINTLN(st.homing_threshold(), PrintBase::Dec);
|
||||
}
|
||||
|
||||
/**
|
||||
* M914: Set StallGuard sensitivity.
|
||||
*/
|
||||
void GcodeSuite::M914() {
|
||||
|
||||
bool report = true;
|
||||
const uint8_t index = parser.byteval('I');
|
||||
LOOP_LINEAR_AXES(i) if (parser.seen(AXIS_CHAR(i))) {
|
||||
LOOP_NUM_AXES(i) if (parser.seen(AXIS_CHAR(i))) {
|
||||
const int16_t value = parser.value_int();
|
||||
report = false;
|
||||
switch (i) {
|
||||
#if X_SENSORLESS
|
||||
case X_AXIS:
|
||||
#if AXIS_HAS_STALLGUARD(X)
|
||||
if (index < 2) stepperX.homing_threshold(value);
|
||||
#endif
|
||||
#if AXIS_HAS_STALLGUARD(X2)
|
||||
if (!(index & 1)) stepperX2.homing_threshold(value);
|
||||
#endif
|
||||
if (index < 2) stepperX.homing_threshold(value);
|
||||
TERN_(X2_SENSORLESS, if (!(index & 1)) stepperX2.homing_threshold(value));
|
||||
break;
|
||||
#endif
|
||||
#if Y_SENSORLESS
|
||||
case Y_AXIS:
|
||||
#if AXIS_HAS_STALLGUARD(Y)
|
||||
if (index < 2) stepperY.homing_threshold(value);
|
||||
#endif
|
||||
#if AXIS_HAS_STALLGUARD(Y2)
|
||||
if (!(index & 1)) stepperY2.homing_threshold(value);
|
||||
#endif
|
||||
if (index < 2) stepperY.homing_threshold(value);
|
||||
TERN_(Y2_SENSORLESS, if (!(index & 1)) stepperY2.homing_threshold(value));
|
||||
break;
|
||||
#endif
|
||||
#if Z_SENSORLESS
|
||||
case Z_AXIS:
|
||||
#if AXIS_HAS_STALLGUARD(Z)
|
||||
if (index < 2) stepperZ.homing_threshold(value);
|
||||
#endif
|
||||
#if AXIS_HAS_STALLGUARD(Z2)
|
||||
if (index == 0 || index == 2) stepperZ2.homing_threshold(value);
|
||||
#endif
|
||||
#if AXIS_HAS_STALLGUARD(Z3)
|
||||
if (index == 0 || index == 3) stepperZ3.homing_threshold(value);
|
||||
#endif
|
||||
#if AXIS_HAS_STALLGUARD(Z4)
|
||||
if (index == 0 || index == 4) stepperZ4.homing_threshold(value);
|
||||
#endif
|
||||
if (index < 2) stepperZ.homing_threshold(value);
|
||||
TERN_(Z2_SENSORLESS, if (!index || index == 2) stepperZ2.homing_threshold(value));
|
||||
TERN_(Z3_SENSORLESS, if (!index || index == 3) stepperZ3.homing_threshold(value));
|
||||
TERN_(Z4_SENSORLESS, if (!index || index == 4) stepperZ4.homing_threshold(value));
|
||||
break;
|
||||
#endif
|
||||
#if I_SENSORLESS && AXIS_HAS_STALLGUARD(I)
|
||||
#if I_SENSORLESS
|
||||
case I_AXIS: stepperI.homing_threshold(value); break;
|
||||
#endif
|
||||
#if J_SENSORLESS && AXIS_HAS_STALLGUARD(J)
|
||||
#if J_SENSORLESS
|
||||
case J_AXIS: stepperJ.homing_threshold(value); break;
|
||||
#endif
|
||||
#if K_SENSORLESS && AXIS_HAS_STALLGUARD(K)
|
||||
#if K_SENSORLESS
|
||||
case K_AXIS: stepperK.homing_threshold(value); break;
|
||||
#endif
|
||||
#if U_SENSORLESS && AXIS_HAS_STALLGUARD(U)
|
||||
case U_AXIS: stepperU.homing_threshold(value); break;
|
||||
#endif
|
||||
#if V_SENSORLESS && AXIS_HAS_STALLGUARD(V)
|
||||
case V_AXIS: stepperV.homing_threshold(value); break;
|
||||
#endif
|
||||
#if W_SENSORLESS && AXIS_HAS_STALLGUARD(W)
|
||||
case W_AXIS: stepperW.homing_threshold(value); break;
|
||||
#endif
|
||||
}
|
||||
}
|
||||
|
||||
if (report) {
|
||||
#if X_SENSORLESS
|
||||
#if AXIS_HAS_STALLGUARD(X)
|
||||
tmc_print_sgt(stepperX);
|
||||
#endif
|
||||
#if AXIS_HAS_STALLGUARD(X2)
|
||||
tmc_print_sgt(stepperX2);
|
||||
#endif
|
||||
#endif
|
||||
#if Y_SENSORLESS
|
||||
#if AXIS_HAS_STALLGUARD(Y)
|
||||
tmc_print_sgt(stepperY);
|
||||
#endif
|
||||
#if AXIS_HAS_STALLGUARD(Y2)
|
||||
tmc_print_sgt(stepperY2);
|
||||
#endif
|
||||
#endif
|
||||
#if Z_SENSORLESS
|
||||
#if AXIS_HAS_STALLGUARD(Z)
|
||||
tmc_print_sgt(stepperZ);
|
||||
#endif
|
||||
#if AXIS_HAS_STALLGUARD(Z2)
|
||||
tmc_print_sgt(stepperZ2);
|
||||
#endif
|
||||
#if AXIS_HAS_STALLGUARD(Z3)
|
||||
tmc_print_sgt(stepperZ3);
|
||||
#endif
|
||||
#if AXIS_HAS_STALLGUARD(Z4)
|
||||
tmc_print_sgt(stepperZ4);
|
||||
#endif
|
||||
#endif
|
||||
#if I_SENSORLESS && AXIS_HAS_STALLGUARD(I)
|
||||
tmc_print_sgt(stepperI);
|
||||
#endif
|
||||
#if J_SENSORLESS && AXIS_HAS_STALLGUARD(J)
|
||||
tmc_print_sgt(stepperJ);
|
||||
#endif
|
||||
#if K_SENSORLESS && AXIS_HAS_STALLGUARD(K)
|
||||
tmc_print_sgt(stepperK);
|
||||
#endif
|
||||
TERN_(X_SENSORLESS, tmc_print_sgt(stepperX));
|
||||
TERN_(X2_SENSORLESS, tmc_print_sgt(stepperX2));
|
||||
TERN_(Y_SENSORLESS, tmc_print_sgt(stepperY));
|
||||
TERN_(Y2_SENSORLESS, tmc_print_sgt(stepperY2));
|
||||
TERN_(Z_SENSORLESS, tmc_print_sgt(stepperZ));
|
||||
TERN_(Z2_SENSORLESS, tmc_print_sgt(stepperZ2));
|
||||
TERN_(Z3_SENSORLESS, tmc_print_sgt(stepperZ3));
|
||||
TERN_(Z4_SENSORLESS, tmc_print_sgt(stepperZ4));
|
||||
TERN_(I_SENSORLESS, tmc_print_sgt(stepperI));
|
||||
TERN_(J_SENSORLESS, tmc_print_sgt(stepperJ));
|
||||
TERN_(K_SENSORLESS, tmc_print_sgt(stepperK));
|
||||
TERN_(U_SENSORLESS, tmc_print_sgt(stepperU));
|
||||
TERN_(V_SENSORLESS, tmc_print_sgt(stepperV));
|
||||
TERN_(W_SENSORLESS, tmc_print_sgt(stepperW));
|
||||
}
|
||||
}
|
||||
|
||||
void GcodeSuite::M914_report(const bool forReplay/*=true*/) {
|
||||
report_heading(forReplay, PSTR(STR_STALLGUARD_THRESHOLD));
|
||||
report_heading(forReplay, F(STR_STALLGUARD_THRESHOLD));
|
||||
|
||||
auto say_M914 = [](const bool forReplay) {
|
||||
report_echo_start(forReplay);
|
||||
@@ -535,7 +589,7 @@
|
||||
|
||||
#if X2_SENSORLESS || Y2_SENSORLESS || Z2_SENSORLESS
|
||||
say_M914(forReplay);
|
||||
SERIAL_ECHOPGM(" I1");
|
||||
SERIAL_ECHOPGM(" I2");
|
||||
#if X2_SENSORLESS
|
||||
SERIAL_ECHOPGM_P(SP_X_STR, stepperX2.homing_threshold());
|
||||
#endif
|
||||
@@ -550,12 +604,12 @@
|
||||
|
||||
#if Z3_SENSORLESS
|
||||
say_M914(forReplay);
|
||||
SERIAL_ECHOLNPGM(" I2 Z", stepperZ3.homing_threshold());
|
||||
SERIAL_ECHOLNPGM(" I3 Z", stepperZ3.homing_threshold());
|
||||
#endif
|
||||
|
||||
#if Z4_SENSORLESS
|
||||
say_M914(forReplay);
|
||||
SERIAL_ECHOLNPGM(" I3 Z", stepperZ4.homing_threshold());
|
||||
SERIAL_ECHOLNPGM(" I4 Z", stepperZ4.homing_threshold());
|
||||
#endif
|
||||
|
||||
#if I_SENSORLESS
|
||||
@@ -570,6 +624,18 @@
|
||||
say_M914(forReplay);
|
||||
SERIAL_ECHOLNPGM_P(SP_K_STR, stepperK.homing_threshold());
|
||||
#endif
|
||||
#if U_SENSORLESS
|
||||
say_M914(forReplay);
|
||||
SERIAL_ECHOLNPGM_P(SP_U_STR, stepperU.homing_threshold());
|
||||
#endif
|
||||
#if V_SENSORLESS
|
||||
say_M914(forReplay);
|
||||
SERIAL_ECHOLNPGM_P(SP_V_STR, stepperV.homing_threshold());
|
||||
#endif
|
||||
#if W_SENSORLESS
|
||||
say_M914(forReplay);
|
||||
SERIAL_ECHOLNPGM_P(SP_W_STR, stepperW.homing_threshold());
|
||||
#endif
|
||||
}
|
||||
|
||||
#endif // USE_SENSORLESS
|
||||
|
284
Marlin/src/gcode/feature/trinamic/M919.cpp
Normal file
284
Marlin/src/gcode/feature/trinamic/M919.cpp
Normal file
@@ -0,0 +1,284 @@
|
||||
/**
|
||||
* Marlin 3D Printer Firmware
|
||||
* Copyright (c) 2021 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 <https://www.gnu.org/licenses/>.
|
||||
*
|
||||
*/
|
||||
|
||||
#include "../../../inc/MarlinConfig.h"
|
||||
|
||||
#if HAS_TRINAMIC_CONFIG
|
||||
|
||||
#if AXIS_COLLISION('I')
|
||||
#error "M919 parameter 'I' collision with axis name."
|
||||
#endif
|
||||
|
||||
#include "../../gcode.h"
|
||||
#include "../../../feature/tmc_util.h"
|
||||
#include "../../../module/stepper/indirection.h"
|
||||
|
||||
#define DEBUG_OUT ENABLED(MARLIN_DEV_MODE)
|
||||
#include "../../../core/debug_out.h"
|
||||
|
||||
template<typename TMC>
|
||||
static void tmc_print_chopper_time(TMC &st) {
|
||||
st.printLabel();
|
||||
SERIAL_ECHOLNPGM(" chopper .toff: ", st.toff(),
|
||||
" .hend: ", st.hysteresis_end(),
|
||||
" .hstrt: ", st.hysteresis_start());
|
||||
}
|
||||
|
||||
/**
|
||||
* M919: Set TMC stepper driver chopper times
|
||||
*
|
||||
* Parameters:
|
||||
* XYZ...E - Selected axes
|
||||
* I[index] - Axis sub-index (Omit for all XYZ steppers, 1 for X2, Y2, Z2; 2 for Z3; 3 for Z4)
|
||||
* T[index] - Extruder index (Zero-based. Omit for all extruders.)
|
||||
* O - time-off [ 1..15]
|
||||
* P - hysteresis_end [-3..12]
|
||||
* S - hysteresis_start [ 1...8]
|
||||
*
|
||||
* With no parameters report chopper times for all axes
|
||||
*/
|
||||
void GcodeSuite::M919() {
|
||||
bool err = false;
|
||||
|
||||
int8_t toff = int8_t(parser.intval('O', -127));
|
||||
if (toff != -127) {
|
||||
if (WITHIN(toff, 1, 15))
|
||||
DEBUG_ECHOLNPGM(".toff: ", toff);
|
||||
else {
|
||||
SERIAL_ECHOLNPGM("?O out of range (1..15)");
|
||||
err = true;
|
||||
}
|
||||
}
|
||||
|
||||
int8_t hend = int8_t(parser.intval('P', -127));
|
||||
if (hend != -127) {
|
||||
if (WITHIN(hend, -3, 12))
|
||||
DEBUG_ECHOLNPGM(".hend: ", hend);
|
||||
else {
|
||||
SERIAL_ECHOLNPGM("?P out of range (-3..12)");
|
||||
err = true;
|
||||
}
|
||||
}
|
||||
|
||||
int8_t hstrt = int8_t(parser.intval('S', -127));
|
||||
if (hstrt != -127) {
|
||||
if (WITHIN(hstrt, 1, 8))
|
||||
DEBUG_ECHOLNPGM(".hstrt: ", hstrt);
|
||||
else {
|
||||
SERIAL_ECHOLNPGM("?S out of range (1..8)");
|
||||
err = true;
|
||||
}
|
||||
}
|
||||
|
||||
if (err) return;
|
||||
|
||||
#if AXIS_IS_TMC(X2) || AXIS_IS_TMC(Y2) || AXIS_IS_TMC(Z2) || AXIS_IS_TMC(Z3) || AXIS_IS_TMC(Z4)
|
||||
const int8_t index = parser.byteval('I');
|
||||
#elif AXIS_IS_TMC(X) || AXIS_IS_TMC(Y) || AXIS_IS_TMC(Z)
|
||||
constexpr int8_t index = -1;
|
||||
#endif
|
||||
|
||||
auto make_chopper_timing = [](chopper_timing_t bct, const int8_t toff, const int8_t hend, const int8_t hstrt) {
|
||||
chopper_timing_t uct = bct;
|
||||
if (toff != -127) uct.toff = toff;
|
||||
if (hend != -127) uct.hend = hend;
|
||||
if (hstrt != -127) uct.hstrt = hstrt;
|
||||
return uct;
|
||||
};
|
||||
|
||||
#define TMC_SET_CHOPPER_TIME(Q) stepper##Q.set_chopper_times(make_chopper_timing(CHOPPER_TIMING_##Q, toff, hend, hstrt))
|
||||
|
||||
#if AXIS_IS_TMC(E0) || AXIS_IS_TMC(E1) || AXIS_IS_TMC(E2) || AXIS_IS_TMC(E3) || AXIS_IS_TMC(E4) || AXIS_IS_TMC(E5) || AXIS_IS_TMC(E6) || AXIS_IS_TMC(E7)
|
||||
#define HAS_E_CHOPPER 1
|
||||
int8_t eindex = -1;
|
||||
#endif
|
||||
bool report = true;
|
||||
LOOP_LOGICAL_AXES(i) if (parser.seen_test(AXIS_CHAR(i))) {
|
||||
report = false;
|
||||
|
||||
// Get the chopper timing for the specified axis and index
|
||||
switch (i) {
|
||||
default: // A specified axis isn't Trinamic
|
||||
SERIAL_ECHOLNPGM("?Axis ", AS_CHAR(AXIS_CHAR(i)), " has no TMC drivers.");
|
||||
break;
|
||||
|
||||
#if AXIS_IS_TMC(X) || AXIS_IS_TMC(X2)
|
||||
case X_AXIS:
|
||||
#if AXIS_IS_TMC(X)
|
||||
if (index <= 0) TMC_SET_CHOPPER_TIME(X);
|
||||
#endif
|
||||
#if AXIS_IS_TMC(X2)
|
||||
if (index < 0 || index == 1) TMC_SET_CHOPPER_TIME(X2);
|
||||
#endif
|
||||
break;
|
||||
#endif
|
||||
|
||||
#if AXIS_IS_TMC(Y) || AXIS_IS_TMC(Y2)
|
||||
case Y_AXIS:
|
||||
#if AXIS_IS_TMC(Y)
|
||||
if (index <= 0) TMC_SET_CHOPPER_TIME(Y);
|
||||
#endif
|
||||
#if AXIS_IS_TMC(Y2)
|
||||
if (index < 0 || index == 1) TMC_SET_CHOPPER_TIME(Y2);
|
||||
#endif
|
||||
break;
|
||||
#endif
|
||||
|
||||
#if AXIS_IS_TMC(Z) || AXIS_IS_TMC(Z2) || AXIS_IS_TMC(Z3) || AXIS_IS_TMC(Z4)
|
||||
case Z_AXIS:
|
||||
#if AXIS_IS_TMC(Z)
|
||||
if (index <= 0) TMC_SET_CHOPPER_TIME(Z);
|
||||
#endif
|
||||
#if AXIS_IS_TMC(Z2)
|
||||
if (index < 0 || index == 1) TMC_SET_CHOPPER_TIME(Z2);
|
||||
#endif
|
||||
#if AXIS_IS_TMC(Z3)
|
||||
if (index < 0 || index == 2) TMC_SET_CHOPPER_TIME(Z3);
|
||||
#endif
|
||||
#if AXIS_IS_TMC(Z4)
|
||||
if (index < 0 || index == 3) TMC_SET_CHOPPER_TIME(Z4);
|
||||
#endif
|
||||
break;
|
||||
#endif
|
||||
|
||||
#if AXIS_IS_TMC(I)
|
||||
case I_AXIS: TMC_SET_CHOPPER_TIME(I); break;
|
||||
#endif
|
||||
#if AXIS_IS_TMC(J)
|
||||
case J_AXIS: TMC_SET_CHOPPER_TIME(J); break;
|
||||
#endif
|
||||
#if AXIS_IS_TMC(K)
|
||||
case K_AXIS: TMC_SET_CHOPPER_TIME(K); break;
|
||||
#endif
|
||||
#if AXIS_IS_TMC(U)
|
||||
case U_AXIS: TMC_SET_CHOPPER_TIME(U); break;
|
||||
#endif
|
||||
#if AXIS_IS_TMC(V)
|
||||
case V_AXIS: TMC_SET_CHOPPER_TIME(V); break;
|
||||
#endif
|
||||
#if AXIS_IS_TMC(W)
|
||||
case W_AXIS: TMC_SET_CHOPPER_TIME(W); break;
|
||||
#endif
|
||||
|
||||
#if HAS_E_CHOPPER
|
||||
case E_AXIS: {
|
||||
#if AXIS_IS_TMC(E0)
|
||||
if (eindex <= 0) TMC_SET_CHOPPER_TIME(E0);
|
||||
#endif
|
||||
#if AXIS_IS_TMC(E1)
|
||||
if (eindex < 0 || eindex == 1) TMC_SET_CHOPPER_TIME(E1);
|
||||
#endif
|
||||
#if AXIS_IS_TMC(E2)
|
||||
if (eindex < 0 || eindex == 2) TMC_SET_CHOPPER_TIME(E2);
|
||||
#endif
|
||||
#if AXIS_IS_TMC(E3)
|
||||
if (eindex < 0 || eindex == 3) TMC_SET_CHOPPER_TIME(E3);
|
||||
#endif
|
||||
#if AXIS_IS_TMC(E4)
|
||||
if (eindex < 0 || eindex == 4) TMC_SET_CHOPPER_TIME(E4);
|
||||
#endif
|
||||
#if AXIS_IS_TMC(E5)
|
||||
if (eindex < 0 || eindex == 5) TMC_SET_CHOPPER_TIME(E5);
|
||||
#endif
|
||||
#if AXIS_IS_TMC(E6)
|
||||
if (eindex < 0 || eindex == 6) TMC_SET_CHOPPER_TIME(E6);
|
||||
#endif
|
||||
#if AXIS_IS_TMC(E7)
|
||||
if (eindex < 0 || eindex == 7) TMC_SET_CHOPPER_TIME(E7);
|
||||
#endif
|
||||
} break;
|
||||
#endif
|
||||
}
|
||||
}
|
||||
|
||||
if (report) {
|
||||
#define TMC_SAY_CHOPPER_TIME(Q) tmc_print_chopper_time(stepper##Q)
|
||||
#if AXIS_IS_TMC(X)
|
||||
TMC_SAY_CHOPPER_TIME(X);
|
||||
#endif
|
||||
#if AXIS_IS_TMC(X2)
|
||||
TMC_SAY_CHOPPER_TIME(X2);
|
||||
#endif
|
||||
#if AXIS_IS_TMC(Y)
|
||||
TMC_SAY_CHOPPER_TIME(Y);
|
||||
#endif
|
||||
#if AXIS_IS_TMC(Y2)
|
||||
TMC_SAY_CHOPPER_TIME(Y2);
|
||||
#endif
|
||||
#if AXIS_IS_TMC(Z)
|
||||
TMC_SAY_CHOPPER_TIME(Z);
|
||||
#endif
|
||||
#if AXIS_IS_TMC(Z2)
|
||||
TMC_SAY_CHOPPER_TIME(Z2);
|
||||
#endif
|
||||
#if AXIS_IS_TMC(Z3)
|
||||
TMC_SAY_CHOPPER_TIME(Z3);
|
||||
#endif
|
||||
#if AXIS_IS_TMC(Z4)
|
||||
TMC_SAY_CHOPPER_TIME(Z4);
|
||||
#endif
|
||||
#if AXIS_IS_TMC(I)
|
||||
TMC_SAY_CHOPPER_TIME(I);
|
||||
#endif
|
||||
#if AXIS_IS_TMC(J)
|
||||
TMC_SAY_CHOPPER_TIME(J);
|
||||
#endif
|
||||
#if AXIS_IS_TMC(K)
|
||||
TMC_SAY_CHOPPER_TIME(K);
|
||||
#endif
|
||||
#if AXIS_IS_TMC(U)
|
||||
TMC_SAY_CHOPPER_TIME(U);
|
||||
#endif
|
||||
#if AXIS_IS_TMC(V)
|
||||
TMC_SAY_CHOPPER_TIME(V);
|
||||
#endif
|
||||
#if AXIS_IS_TMC(W)
|
||||
TMC_SAY_CHOPPER_TIME(W);
|
||||
#endif
|
||||
#if AXIS_IS_TMC(E0)
|
||||
TMC_SAY_CHOPPER_TIME(E0);
|
||||
#endif
|
||||
#if AXIS_IS_TMC(E1)
|
||||
TMC_SAY_CHOPPER_TIME(E1);
|
||||
#endif
|
||||
#if AXIS_IS_TMC(E2)
|
||||
TMC_SAY_CHOPPER_TIME(E2);
|
||||
#endif
|
||||
#if AXIS_IS_TMC(E3)
|
||||
TMC_SAY_CHOPPER_TIME(E3);
|
||||
#endif
|
||||
#if AXIS_IS_TMC(E4)
|
||||
TMC_SAY_CHOPPER_TIME(E4);
|
||||
#endif
|
||||
#if AXIS_IS_TMC(E5)
|
||||
TMC_SAY_CHOPPER_TIME(E5);
|
||||
#endif
|
||||
#if AXIS_IS_TMC(E6)
|
||||
TMC_SAY_CHOPPER_TIME(E6);
|
||||
#endif
|
||||
#if AXIS_IS_TMC(E7)
|
||||
TMC_SAY_CHOPPER_TIME(E7);
|
||||
#endif
|
||||
}
|
||||
}
|
||||
|
||||
#endif // HAS_TRINAMIC_CONFIG
|
@@ -21,7 +21,7 @@
|
||||
*/
|
||||
|
||||
/**
|
||||
* gcode.cpp - Temporary container for all gcode handlers
|
||||
* gcode.cpp - Temporary container for all G-code handlers
|
||||
* Most will migrate to classes, by feature.
|
||||
*/
|
||||
|
||||
@@ -53,7 +53,7 @@ GcodeSuite gcode;
|
||||
#include "../feature/cancel_object.h"
|
||||
#endif
|
||||
|
||||
#if ENABLED(LASER_MOVE_POWER)
|
||||
#if ENABLED(LASER_FEATURE)
|
||||
#include "../feature/spindle_laser.h"
|
||||
#endif
|
||||
|
||||
@@ -65,12 +65,19 @@ GcodeSuite gcode;
|
||||
#include "../feature/password/password.h"
|
||||
#endif
|
||||
|
||||
#if HAS_FANCHECK
|
||||
#include "../feature/fancheck.h"
|
||||
#endif
|
||||
|
||||
#include "../MarlinCore.h" // for idle, kill
|
||||
|
||||
// Inactivity shutdown
|
||||
millis_t GcodeSuite::previous_move_ms = 0,
|
||||
GcodeSuite::max_inactive_time = 0,
|
||||
GcodeSuite::stepper_inactive_time = SEC_TO_MS(DEFAULT_STEPPER_DEACTIVE_TIME);
|
||||
GcodeSuite::max_inactive_time = 0;
|
||||
|
||||
#if HAS_DISABLE_INACTIVE_AXIS
|
||||
millis_t GcodeSuite::stepper_inactive_time = SEC_TO_MS(DEFAULT_STEPPER_DEACTIVE_TIME);
|
||||
#endif
|
||||
|
||||
// Relative motion mode for each logical axis
|
||||
static constexpr xyze_bool_t ar_init = AXIS_RELATIVE_MODES;
|
||||
@@ -81,7 +88,10 @@ axis_bits_t GcodeSuite::axis_relative = 0 LOGICAL_AXIS_GANG(
|
||||
| (ar_init.z << REL_Z),
|
||||
| (ar_init.i << REL_I),
|
||||
| (ar_init.j << REL_J),
|
||||
| (ar_init.k << REL_K)
|
||||
| (ar_init.k << REL_K),
|
||||
| (ar_init.u << REL_U),
|
||||
| (ar_init.v << REL_V),
|
||||
| (ar_init.w << REL_W)
|
||||
);
|
||||
|
||||
#if EITHER(HAS_AUTO_REPORTING, HOST_KEEPALIVE_FEATURE)
|
||||
@@ -103,12 +113,12 @@ axis_bits_t GcodeSuite::axis_relative = 0 LOGICAL_AXIS_GANG(
|
||||
#endif
|
||||
|
||||
void GcodeSuite::report_echo_start(const bool forReplay) { if (!forReplay) SERIAL_ECHO_START(); }
|
||||
void GcodeSuite::report_heading(const bool forReplay, PGM_P const pstr, const bool eol/*=true*/) {
|
||||
void GcodeSuite::report_heading(const bool forReplay, FSTR_P const fstr, const bool eol/*=true*/) {
|
||||
if (forReplay) return;
|
||||
if (pstr) {
|
||||
if (fstr) {
|
||||
SERIAL_ECHO_START();
|
||||
SERIAL_ECHOPGM("; ");
|
||||
SERIAL_ECHOPGM_P(pstr);
|
||||
SERIAL_ECHOF(fstr);
|
||||
}
|
||||
if (eol) { SERIAL_CHAR(':'); SERIAL_EOL(); }
|
||||
}
|
||||
@@ -137,12 +147,14 @@ int8_t GcodeSuite::get_target_extruder_from_command() {
|
||||
}
|
||||
|
||||
/**
|
||||
* Get the target e stepper from the T parameter
|
||||
* Return -1 if the T parameter is out of range or unspecified
|
||||
* Get the target E stepper from the 'T' parameter.
|
||||
* If there is no 'T' parameter then dval will be substituted.
|
||||
* Returns -1 if the resulting E stepper index is out of range.
|
||||
*/
|
||||
int8_t GcodeSuite::get_target_e_stepper_from_command() {
|
||||
const int8_t e = parser.intval('T', -1);
|
||||
int8_t GcodeSuite::get_target_e_stepper_from_command(const int8_t dval/*=-1*/) {
|
||||
const int8_t e = parser.intval('T', dval);
|
||||
if (WITHIN(e, 0, E_STEPPERS - 1)) return e;
|
||||
if (dval == -2) return dval;
|
||||
|
||||
SERIAL_ECHO_START();
|
||||
SERIAL_CHAR('M'); SERIAL_ECHO(parser.codenum);
|
||||
@@ -154,7 +166,7 @@ int8_t GcodeSuite::get_target_e_stepper_from_command() {
|
||||
}
|
||||
|
||||
/**
|
||||
* Set XYZIJKE destination and feedrate from the current GCode command
|
||||
* Set XYZ...E destination and feedrate from the current GCode command
|
||||
*
|
||||
* - Set destination from included axis codes
|
||||
* - Set to current for missing axis codes
|
||||
@@ -170,7 +182,7 @@ void GcodeSuite::get_destination_from_command() {
|
||||
#endif
|
||||
|
||||
// Get new XYZ position, whether absolute or relative
|
||||
LOOP_LINEAR_AXES(i) {
|
||||
LOOP_NUM_AXES(i) {
|
||||
if ( (seen[i] = parser.seenval(AXIS_CHAR(i))) ) {
|
||||
const float v = parser.value_axis_units((AxisEnum)i);
|
||||
if (skip_move)
|
||||
@@ -198,10 +210,13 @@ void GcodeSuite::get_destination_from_command() {
|
||||
recovery.save();
|
||||
#endif
|
||||
|
||||
if (parser.floatval('F') > 0)
|
||||
if (parser.floatval('F') > 0) {
|
||||
feedrate_mm_s = parser.value_feedrate();
|
||||
// Update the cutter feed rate for use by M4 I set inline moves.
|
||||
TERN_(LASER_FEATURE, cutter.feedrate_mm_m = MMS_TO_MMM(feedrate_mm_s));
|
||||
}
|
||||
|
||||
#if ENABLED(PRINTCOUNTER)
|
||||
#if BOTH(PRINTCOUNTER, HAS_EXTRUDERS)
|
||||
if (!DEBUGGING(DRYRUN) && !skip_move)
|
||||
print_job_timer.incFilamentUsed(destination.e - current_position.e);
|
||||
#endif
|
||||
@@ -211,15 +226,29 @@ void GcodeSuite::get_destination_from_command() {
|
||||
M165();
|
||||
#endif
|
||||
|
||||
#if ENABLED(LASER_MOVE_POWER)
|
||||
// Set the laser power in the planner to configure this move
|
||||
if (parser.seen('S')) {
|
||||
const float spwr = parser.value_float();
|
||||
cutter.inline_power(TERN(SPINDLE_LASER_USE_PWM, cutter.power_to_range(cutter_power_t(round(spwr))), spwr > 0 ? 255 : 0));
|
||||
#if ENABLED(LASER_FEATURE)
|
||||
if (cutter.cutter_mode == CUTTER_MODE_CONTINUOUS || cutter.cutter_mode == CUTTER_MODE_DYNAMIC) {
|
||||
// Set the cutter power in the planner to configure this move
|
||||
cutter.last_feedrate_mm_m = 0;
|
||||
if (WITHIN(parser.codenum, 1, TERN(ARC_SUPPORT, 3, 1)) || TERN0(BEZIER_CURVE_SUPPORT, parser.codenum == 5)) {
|
||||
planner.laser_inline.status.isPowered = true;
|
||||
if (parser.seen('I')) cutter.set_enabled(true); // This is set for backward LightBurn compatibility.
|
||||
if (parser.seenval('S')) {
|
||||
const float v = parser.value_float(),
|
||||
u = TERN(LASER_POWER_TRAP, v, cutter.power_to_range(v));
|
||||
cutter.menuPower = cutter.unitPower = u;
|
||||
cutter.inline_power(TERN(SPINDLE_LASER_USE_PWM, cutter.upower_to_ocr(u), u > 0 ? 255 : 0));
|
||||
}
|
||||
}
|
||||
else if (parser.codenum == 0) {
|
||||
// For dynamic mode we need to flag isPowered off, dynamic power is calculated in the stepper based on feedrate.
|
||||
if (cutter.cutter_mode == CUTTER_MODE_DYNAMIC) planner.laser_inline.status.isPowered = false;
|
||||
cutter.inline_power(0); // This is planner-based so only set power and do not disable inline control flags.
|
||||
}
|
||||
}
|
||||
else if (ENABLED(LASER_MOVE_G0_OFF) && parser.codenum == 0) // G0
|
||||
cutter.set_inline_enabled(false);
|
||||
#endif
|
||||
else if (parser.codenum == 0)
|
||||
cutter.apply_power(0);
|
||||
#endif // LASER_FEATURE
|
||||
}
|
||||
|
||||
/**
|
||||
@@ -237,12 +266,12 @@ void GcodeSuite::dwell(millis_t time) {
|
||||
#if ENABLED(G29_RETRY_AND_RECOVER)
|
||||
|
||||
void GcodeSuite::event_probe_recover() {
|
||||
TERN_(HOST_PROMPT_SUPPORT, host_prompt_do(PROMPT_INFO, PSTR("G29 Retrying"), DISMISS_STR));
|
||||
TERN_(HOST_PROMPT_SUPPORT, hostui.prompt_do(PROMPT_INFO, F("G29 Retrying"), FPSTR(DISMISS_STR)));
|
||||
#ifdef ACTION_ON_G29_RECOVER
|
||||
host_action(PSTR(ACTION_ON_G29_RECOVER));
|
||||
hostui.g29_recover();
|
||||
#endif
|
||||
#ifdef G29_RECOVER_COMMANDS
|
||||
process_subcommands_now_P(PSTR(G29_RECOVER_COMMANDS));
|
||||
process_subcommands_now(F(G29_RECOVER_COMMANDS));
|
||||
#endif
|
||||
}
|
||||
|
||||
@@ -252,16 +281,16 @@ void GcodeSuite::dwell(millis_t time) {
|
||||
|
||||
void GcodeSuite::event_probe_failure() {
|
||||
#ifdef ACTION_ON_G29_FAILURE
|
||||
host_action(PSTR(ACTION_ON_G29_FAILURE));
|
||||
hostui.g29_failure();
|
||||
#endif
|
||||
#ifdef G29_FAILURE_COMMANDS
|
||||
process_subcommands_now_P(PSTR(G29_FAILURE_COMMANDS));
|
||||
process_subcommands_now(F(G29_FAILURE_COMMANDS));
|
||||
#endif
|
||||
#if ENABLED(G29_HALT_ON_FAILURE)
|
||||
#ifdef ACTION_ON_CANCEL
|
||||
host_action_cancel();
|
||||
hostui.cancel();
|
||||
#endif
|
||||
kill(GET_TEXT(MSG_LCD_PROBING_FAILED));
|
||||
kill(GET_TEXT_F(MSG_LCD_PROBING_FAILED));
|
||||
#endif
|
||||
}
|
||||
|
||||
@@ -282,10 +311,10 @@ void GcodeSuite::dwell(millis_t time) {
|
||||
}
|
||||
}
|
||||
|
||||
TERN_(HOST_PROMPT_SUPPORT, host_action_prompt_end());
|
||||
TERN_(HOST_PROMPT_SUPPORT, hostui.prompt_end());
|
||||
|
||||
#ifdef G29_SUCCESS_COMMANDS
|
||||
process_subcommands_now_P(PSTR(G29_SUCCESS_COMMANDS));
|
||||
process_subcommands_now(F(G29_SUCCESS_COMMANDS));
|
||||
#endif
|
||||
}
|
||||
|
||||
@@ -295,6 +324,8 @@ void GcodeSuite::dwell(millis_t time) {
|
||||
* Process the parsed command and dispatch it to its handler
|
||||
*/
|
||||
void GcodeSuite::process_parsed_command(const bool no_ok/*=false*/) {
|
||||
TERN_(HAS_FANCHECK, fan_check.check_deferred_error());
|
||||
|
||||
KEEPALIVE_STATE(IN_HANDLER);
|
||||
|
||||
/**
|
||||
@@ -423,7 +454,7 @@ void GcodeSuite::process_parsed_command(const bool no_ok/*=false*/) {
|
||||
case 61: G61(); break; // G61: Apply/restore saved coordinates.
|
||||
#endif
|
||||
|
||||
#if ENABLED(PROBE_TEMP_COMPENSATION)
|
||||
#if BOTH(PTC_PROBE, PTC_BED)
|
||||
case 76: G76(); break; // G76: Calibrate first layer compensation values
|
||||
#endif
|
||||
|
||||
@@ -546,6 +577,10 @@ void GcodeSuite::process_parsed_command(const bool no_ok/*=false*/) {
|
||||
case 100: M100(); break; // M100: Free Memory Report
|
||||
#endif
|
||||
|
||||
#if ENABLED(BD_SENSOR)
|
||||
case 102: M102(); break; // M102: Configure Bed Distance Sensor
|
||||
#endif
|
||||
|
||||
#if HAS_EXTRUDERS
|
||||
case 104: M104(); break; // M104: Set hot end temperature
|
||||
case 109: M109(); break; // M109: Wait for hotend temperature to reach target
|
||||
@@ -576,6 +611,10 @@ void GcodeSuite::process_parsed_command(const bool no_ok/*=false*/) {
|
||||
case 113: M113(); break; // M113: Set Host Keepalive interval
|
||||
#endif
|
||||
|
||||
#if HAS_FANCHECK
|
||||
case 123: M123(); break; // M123: Report fan states or set fans auto-report interval
|
||||
#endif
|
||||
|
||||
#if HAS_HEATED_BED
|
||||
case 140: M140(); break; // M140: Set bed temperature
|
||||
case 190: M190(); break; // M190: Wait for bed temperature to reach target
|
||||
@@ -586,6 +625,10 @@ void GcodeSuite::process_parsed_command(const bool no_ok/*=false*/) {
|
||||
case 191: M191(); break; // M191: Wait for chamber temperature to reach target
|
||||
#endif
|
||||
|
||||
#if HAS_TEMP_PROBE
|
||||
case 192: M192(); break; // M192: Wait for probe temp
|
||||
#endif
|
||||
|
||||
#if HAS_COOLER
|
||||
case 143: M143(); break; // M143: Set cooler temperature
|
||||
case 193: M193(); break; // M193: Wait for cooler temperature to reach target
|
||||
@@ -639,7 +682,7 @@ void GcodeSuite::process_parsed_command(const bool no_ok/*=false*/) {
|
||||
case 120: M120(); break; // M120: Enable endstops
|
||||
case 121: M121(); break; // M121: Disable endstops
|
||||
|
||||
#if PREHEAT_COUNT
|
||||
#if HAS_PREHEAT
|
||||
case 145: M145(); break; // M145: Set material heatup parameters
|
||||
#endif
|
||||
|
||||
@@ -726,7 +769,7 @@ void GcodeSuite::process_parsed_command(const bool no_ok/*=false*/) {
|
||||
case 290: M290(); break; // M290: Babystepping
|
||||
#endif
|
||||
|
||||
#if HAS_BUZZER
|
||||
#if HAS_SOUND
|
||||
case 300: M300(); break; // M300: Play beep tone
|
||||
#endif
|
||||
|
||||
@@ -771,6 +814,10 @@ void GcodeSuite::process_parsed_command(const bool no_ok/*=false*/) {
|
||||
case 305: M305(); break; // M305: Set user thermistor parameters
|
||||
#endif
|
||||
|
||||
#if ENABLED(MPCTEMP)
|
||||
case 306: M306(); break; // M306: MPC autotune
|
||||
#endif
|
||||
|
||||
#if ENABLED(REPETIER_GCODE_M360)
|
||||
case 360: M360(); break; // M360: Firmware settings
|
||||
#endif
|
||||
@@ -822,6 +869,10 @@ void GcodeSuite::process_parsed_command(const bool no_ok/*=false*/) {
|
||||
case 421: M421(); break; // M421: Set a Mesh Bed Leveling Z coordinate
|
||||
#endif
|
||||
|
||||
#if ENABLED(X_AXIS_TWIST_COMPENSATION)
|
||||
case 423: M423(); break; // M423: Reset, modify, or report X-Twist Compensation data
|
||||
#endif
|
||||
|
||||
#if ENABLED(BACKLASH_GCODE)
|
||||
case 425: M425(); break; // M425: Tune backlash compensation
|
||||
#endif
|
||||
@@ -886,7 +937,7 @@ void GcodeSuite::process_parsed_command(const bool no_ok/*=false*/) {
|
||||
#endif
|
||||
|
||||
#if IS_KINEMATIC
|
||||
case 665: M665(); break; // M665: Set Delta/SCARA parameters
|
||||
case 665: M665(); break; // M665: Set Kinematics parameters
|
||||
#endif
|
||||
|
||||
#if ENABLED(DELTA) || HAS_EXTRA_ENDSTOPS
|
||||
@@ -920,8 +971,7 @@ void GcodeSuite::process_parsed_command(const bool no_ok/*=false*/) {
|
||||
case 852: M852(); break; // M852: Set Skew factors
|
||||
#endif
|
||||
|
||||
#if ENABLED(PROBE_TEMP_COMPENSATION)
|
||||
case 192: M192(); break; // M192: Wait for probe temp
|
||||
#if HAS_PTC
|
||||
case 871: M871(); break; // M871: Print/reset/clear first layer temperature offset values
|
||||
#endif
|
||||
|
||||
@@ -956,14 +1006,7 @@ void GcodeSuite::process_parsed_command(const bool no_ok/*=false*/) {
|
||||
#if USE_SENSORLESS
|
||||
case 914: M914(); break; // M914: Set StallGuard sensitivity.
|
||||
#endif
|
||||
#endif
|
||||
|
||||
#if HAS_L64XX
|
||||
case 122: M122(); break; // M122: Report status
|
||||
case 906: M906(); break; // M906: Set or get motor drive level
|
||||
case 916: M916(); break; // M916: L6470 tuning: Increase drive level until thermal warning
|
||||
case 917: M917(); break; // M917: L6470 tuning: Find minimum current thresholds
|
||||
case 918: M918(); break; // M918: L6470 tuning: Increase speed until max or error
|
||||
case 919: M919(); break; // M919: Set stepper Chopper Times
|
||||
#endif
|
||||
|
||||
#if HAS_MICROSTEPS
|
||||
@@ -1040,8 +1083,12 @@ void GcodeSuite::process_parsed_command(const bool no_ok/*=false*/) {
|
||||
case 7219: M7219(); break; // M7219: Set LEDs, columns, and rows
|
||||
#endif
|
||||
|
||||
#if ENABLED(HAS_MCP3426_ADC)
|
||||
case 3426: M3426(); break; // M3426: Read MCP3426 ADC (over i2c)
|
||||
#endif
|
||||
|
||||
#if BOTH(ANYCUBIC_TFT_DEBUG, KNUTWURST_DGUS2_TFT)
|
||||
case 9999: M9999(); break;
|
||||
case 9999: M9999(); break;
|
||||
#endif
|
||||
|
||||
default: parser.unknown_command_warning(); break;
|
||||
@@ -1071,7 +1118,7 @@ void GcodeSuite::process_parsed_command(const bool no_ok/*=false*/) {
|
||||
}
|
||||
|
||||
#if ENABLED(M100_FREE_MEMORY_DUMPER)
|
||||
void M100_dump_routine(PGM_P const title, const char * const start, const uintptr_t size);
|
||||
void M100_dump_routine(FSTR_P const title, const char * const start, const uintptr_t size);
|
||||
#endif
|
||||
|
||||
/**
|
||||
@@ -1090,7 +1137,7 @@ void GcodeSuite::process_next_command() {
|
||||
SERIAL_ECHOLN(command.buffer);
|
||||
#if ENABLED(M100_FREE_MEMORY_DUMPER)
|
||||
SERIAL_ECHOPGM("slot:", queue.ring_buffer.index_r);
|
||||
M100_dump_routine(PSTR(" Command Queue:"), (const char*)&queue.ring_buffer, sizeof(queue.ring_buffer));
|
||||
M100_dump_routine(F(" Command Queue:"), (const char*)&queue.ring_buffer, sizeof(queue.ring_buffer));
|
||||
#endif
|
||||
}
|
||||
|
||||
@@ -1099,12 +1146,17 @@ void GcodeSuite::process_next_command() {
|
||||
process_parsed_command();
|
||||
}
|
||||
|
||||
#pragma GCC diagnostic push
|
||||
#if GCC_VERSION >= 80000
|
||||
#pragma GCC diagnostic ignored "-Wstringop-truncation"
|
||||
#endif
|
||||
|
||||
/**
|
||||
* Run a series of commands, bypassing the command queue to allow
|
||||
* G-code "macros" to be called from within other G-code handlers.
|
||||
*/
|
||||
|
||||
void GcodeSuite::process_subcommands_now_P(PGM_P pgcode) {
|
||||
void GcodeSuite::process_subcommands_now(FSTR_P fgcode) {
|
||||
PGM_P pgcode = FTOP(fgcode);
|
||||
char * const saved_cmd = parser.command_ptr; // Save the parser state
|
||||
for (;;) {
|
||||
PGM_P const delim = strchr_P(pgcode, '\n'); // Get address of next newline
|
||||
@@ -1120,6 +1172,8 @@ void GcodeSuite::process_subcommands_now_P(PGM_P pgcode) {
|
||||
parser.parse(saved_cmd); // Restore the parser state
|
||||
}
|
||||
|
||||
#pragma GCC diagnostic pop
|
||||
|
||||
void GcodeSuite::process_subcommands_now(char * gcode) {
|
||||
char * const saved_cmd = parser.command_ptr; // Save the parser state
|
||||
for (;;) {
|
||||
|
@@ -66,7 +66,7 @@
|
||||
* G42 - Coordinated move to a mesh point (Requires MESH_BED_LEVELING, AUTO_BED_LEVELING_BLINEAR, or AUTO_BED_LEVELING_UBL)
|
||||
* G60 - Save current position. (Requires SAVED_POSITIONS)
|
||||
* G61 - Apply/restore saved coordinates. (Requires SAVED_POSITIONS)
|
||||
* G76 - Calibrate first layer temperature offsets. (Requires PROBE_TEMP_COMPENSATION)
|
||||
* G76 - Calibrate first layer temperature offsets. (Requires PTC_PROBE and PTC_BED)
|
||||
* G80 - Cancel current motion mode (Requires GCODE_MOTION_MODES)
|
||||
* G90 - Use Absolute Coordinates
|
||||
* G91 - Use Relative Coordinates
|
||||
@@ -88,8 +88,10 @@
|
||||
* M16 - Expected printer check. (Requires EXPECTED_PRINTER_CHECK)
|
||||
* M17 - Enable/Power all stepper motors
|
||||
* M18 - Disable all stepper motors; same as M84
|
||||
*
|
||||
*** Print from Media (SDSUPPORT) ***
|
||||
* M20 - List SD card. (Requires SDSUPPORT)
|
||||
* M21 - Init SD card. (Requires SDSUPPORT)
|
||||
* M21 - Init SD card. (Requires SDSUPPORT) With MULTI_VOLUME select a drive with `M21 Pn` / 'M21 S' / 'M21 U'.
|
||||
* M22 - Release SD card. (Requires SDSUPPORT)
|
||||
* M23 - Select SD file: "M23 /path/file.gco". (Requires SDSUPPORT)
|
||||
* M24 - Start/resume SD print. (Requires SDSUPPORT)
|
||||
@@ -100,30 +102,38 @@
|
||||
* OR, with 'C' get the current filename.
|
||||
* M28 - Start SD write: "M28 /path/file.gco". (Requires SDSUPPORT)
|
||||
* M29 - Stop SD write. (Requires SDSUPPORT)
|
||||
* M30 - Delete file from SD: "M30 /path/file.gco"
|
||||
* M30 - Delete file from SD: "M30 /path/file.gco" (Requires SDSUPPORT)
|
||||
* M31 - Report time since last M109 or SD card start to serial.
|
||||
* M32 - Select file and start SD print: "M32 [S<bytepos>] !/path/file.gco#". (Requires SDSUPPORT)
|
||||
* Use P to run other files as sub-programs: "M32 P !filename#"
|
||||
* The '#' is necessary when calling from within sd files, as it stops buffer prereading
|
||||
* M33 - Get the longname version of a path. (Requires LONG_FILENAME_HOST_SUPPORT)
|
||||
* M34 - Set SD Card sorting options. (Requires SDCARD_SORT_ALPHA)
|
||||
* M42 - Change pin status via gcode: M42 P<pin> S<value>. LED pin assumed if P is omitted. (Requires DIRECT_PIN_CONTROL)
|
||||
* M43 - Display pin status, watch pins for changes, watch endstops & toggle LED, Z servo probe test, toggle pins
|
||||
*
|
||||
* M42 - Change pin status via G-code: M42 P<pin> S<value>. LED pin assumed if P is omitted. (Requires DIRECT_PIN_CONTROL)
|
||||
* M43 - Display pin status, watch pins for changes, watch endstops & toggle LED, Z servo probe test, toggle pins (Requires PINS_DEBUGGING)
|
||||
* M48 - Measure Z Probe repeatability: M48 P<points> X<pos> Y<pos> V<level> E<engage> L<legs> S<chizoid>. (Requires Z_MIN_PROBE_REPEATABILITY_TEST)
|
||||
*
|
||||
* M73 - Set the progress percentage. (Requires LCD_SET_PROGRESS_MANUALLY)
|
||||
* M75 - Start the print job timer.
|
||||
* M76 - Pause the print job timer.
|
||||
* M77 - Stop the print job timer.
|
||||
* M78 - Show statistical information about the print jobs. (Requires PRINTCOUNTER)
|
||||
*
|
||||
* M80 - Turn on Power Supply. (Requires PSU_CONTROL)
|
||||
* M81 - Turn off Power Supply. (Requires PSU_CONTROL)
|
||||
*
|
||||
* M82 - Set E codes absolute (default).
|
||||
* M83 - Set E codes relative while in Absolute (G90) mode.
|
||||
* M84 - Disable steppers until next move, or use S<seconds> to specify an idle
|
||||
* duration after which steppers should turn off. S0 disables the timeout.
|
||||
* M85 - Set inactivity shutdown timer with parameter S<seconds>. To disable set zero (default)
|
||||
* M92 - Set planner.settings.axis_steps_per_mm for one or more axes.
|
||||
*
|
||||
* M100 - Watch Free Memory (for debugging) (Requires M100_FREE_MEMORY_WATCHER)
|
||||
*
|
||||
* M102 - Configure Bed Distance Sensor. (Requires BD_SENSOR)
|
||||
*
|
||||
* M104 - Set extruder target temp.
|
||||
* M105 - Report current temperatures.
|
||||
* M106 - Set print fan speed.
|
||||
@@ -132,23 +142,30 @@
|
||||
* M109 - S<temp> Wait for extruder current temp to reach target temp. ** Wait only when heating! **
|
||||
* R<temp> Wait for extruder current temp to reach target temp. ** Wait for heating or cooling. **
|
||||
* If AUTOTEMP is enabled, S<mintemp> B<maxtemp> F<factor>. Exit autotemp by any M109 without F
|
||||
*
|
||||
* M110 - Set the current line number. (Used by host printing)
|
||||
* M111 - Set debug flags: "M111 S<flagbits>". See flag bits defined in enum.h.
|
||||
* M112 - Full Shutdown.
|
||||
*
|
||||
* M113 - Get or set the timeout interval for Host Keepalive "busy" messages. (Requires HOST_KEEPALIVE_FEATURE)
|
||||
* M114 - Report current position.
|
||||
* M115 - Report capabilities. (Extended capabilities requires EXTENDED_CAPABILITIES_REPORT)
|
||||
* M117 - Display a message on the controller screen. (Requires an LCD)
|
||||
* M118 - Display a message in the host console.
|
||||
*
|
||||
* M119 - Report endstops status.
|
||||
* M120 - Enable endstops detection.
|
||||
* M121 - Disable endstops detection.
|
||||
* M122 - Debug stepper (Requires at least one _DRIVER_TYPE defined as TMC2130/2160/5130/5160/2208/2209/2660 or L6470)
|
||||
*
|
||||
* M122 - Debug stepper (Requires at least one _DRIVER_TYPE defined as TMC2130/2160/5130/5160/2208/2209/2660)
|
||||
* M123 - Report fan tachometers. (Requires En_FAN_TACHO_PIN) Optionally set auto-report interval. (Requires AUTO_REPORT_FANS)
|
||||
* M125 - Save current position and move to filament change position. (Requires PARK_HEAD_ON_PAUSE)
|
||||
*
|
||||
* M126 - Solenoid Air Valve Open. (Requires BARICUDA)
|
||||
* M127 - Solenoid Air Valve Closed. (Requires BARICUDA)
|
||||
* M128 - EtoP Open. (Requires BARICUDA)
|
||||
* M129 - EtoP Closed. (Requires BARICUDA)
|
||||
*
|
||||
* M140 - Set bed target temp. S<temp>
|
||||
* M141 - Set heated chamber target temp. S<temp> (Requires a chamber heater)
|
||||
* M143 - Set cooler target temp. S<temp> (Requires a laser cooling device)
|
||||
@@ -161,9 +178,9 @@
|
||||
* M164 - Commit the mix and save to a virtual tool (current, or as specified by 'S'). (Requires MIXING_EXTRUDER)
|
||||
* M165 - Set the mix for the mixing extruder (and current virtual tool) with parameters ABCDHI. (Requires MIXING_EXTRUDER and DIRECT_MIXING_IN_G1)
|
||||
* M166 - Set the Gradient Mix for the mixing extruder. (Requires GRADIENT_MIX)
|
||||
* M190 - S<temp> Wait for bed current temp to reach target temp. ** Wait only when heating! **
|
||||
* R<temp> Wait for bed current temp to reach target temp. ** Wait for heating or cooling. **
|
||||
* M193 - R<temp> Wait for cooler temp to reach target temp. ** Wait for cooling. **
|
||||
* M190 - Set bed target temperature and wait. R<temp> Set target temperature and wait. S<temp> Set, but only wait when heating. (Requires TEMP_SENSOR_BED)
|
||||
* M192 - Wait for probe to reach target temperature. (Requires TEMP_SENSOR_PROBE)
|
||||
* M193 - R<temp> Wait for cooler to reach target temp. ** Wait for cooling. **
|
||||
* M200 - Set filament diameter, D<diameter>, setting E axis units to cubic. (Use S0 to revert to linear units.)
|
||||
* M201 - Set max acceleration in units/s^2 for print moves: "M201 X<accel> Y<accel> Z<accel> E<accel>"
|
||||
* M202 - Set max acceleration in units/s^2 for travel moves: "M202 X<accel> Y<accel> Z<accel> E<accel>" ** UNUSED IN MARLIN! **
|
||||
@@ -183,10 +200,11 @@
|
||||
* M218 - Set/get a tool offset: "M218 T<index> X<offset> Y<offset>". (Requires 2 or more extruders)
|
||||
* M220 - Set Feedrate Percentage: "M220 S<percent>" (i.e., "FR" on the LCD)
|
||||
* Use "M220 B" to back up the Feedrate Percentage and "M220 R" to restore it. (Requires an MMU_MODEL version 2 or 2S)
|
||||
* M221 - Set Flow Percentage: "M221 S<percent>"
|
||||
* M221 - Set Flow Percentage: "M221 S<percent>" (Requires an extruder)
|
||||
* M226 - Wait until a pin is in a given state: "M226 P<pin> S<state>" (Requires DIRECT_PIN_CONTROL)
|
||||
* M240 - Trigger a camera to take a photograph. (Requires PHOTO_GCODE)
|
||||
* M250 - Set LCD contrast: "M250 C<contrast>" (0-63). (Requires LCD support)
|
||||
* M255 - Set LCD sleep time: "M255 S<minutes>" (0-99). (Requires an LCD with brightness or sleep/wake)
|
||||
* M256 - Set LCD brightness: "M256 B<brightness>" (0-255). (Requires an LCD with brightness control)
|
||||
* M260 - i2c Send Data (Requires EXPERIMENTAL_I2CBUS)
|
||||
* M261 - i2c Request Data (Requires EXPERIMENTAL_I2CBUS)
|
||||
@@ -200,12 +218,13 @@
|
||||
* M303 - PID relay autotune S<temperature> sets the target temperature. Default 150C. (Requires PIDTEMP)
|
||||
* M304 - Set bed PID parameters P I and D. (Requires PIDTEMPBED)
|
||||
* M305 - Set user thermistor parameters R T and P. (Requires TEMP_SENSOR_x 1000)
|
||||
* M306 - MPC autotune. (Requires MPCTEMP)
|
||||
* M309 - Set chamber PID parameters P I and D. (Requires PIDTEMPCHAMBER)
|
||||
* M350 - Set microstepping mode. (Requires digital microstepping pins.)
|
||||
* M351 - Toggle MS1 MS2 pins directly. (Requires digital microstepping pins.)
|
||||
* M355 - Set Case Light on/off and set brightness. (Requires CASE_LIGHT_PIN)
|
||||
* M380 - Activate solenoid on active extruder. (Requires EXT_SOLENOID)
|
||||
* M381 - Disable all solenoids. (Requires EXT_SOLENOID)
|
||||
* M380 - Activate solenoid on active tool (Requires EXT_SOLENOID) or the tool specified by 'S' (Requires MANUAL_SOLENOID_CONTROL).
|
||||
* M381 - Disable solenoids on all tools (Requires EXT_SOLENOID) or the tool specified by 'S' (Requires MANUAL_SOLENOID_CONTROL).
|
||||
* M400 - Finish all moves.
|
||||
* M401 - Deploy and activate Z probe. (Requires a probe)
|
||||
* M402 - Deactivate and stow Z probe. (Requires a probe)
|
||||
@@ -230,9 +249,9 @@
|
||||
* M502 - Revert to the default "factory settings". ** Does not write them to EEPROM! **
|
||||
* M503 - Print the current settings (in memory): "M503 S<verbose>". S0 specifies compact output.
|
||||
* M504 - Validate EEPROM contents. (Requires EEPROM_SETTINGS)
|
||||
* M510 - Lock Printer
|
||||
* M511 - Unlock Printer
|
||||
* M512 - Set/Change/Remove Password
|
||||
* M510 - Lock Printer (Requires PASSWORD_FEATURE)
|
||||
* M511 - Unlock Printer (Requires PASSWORD_UNLOCK_GCODE)
|
||||
* M512 - Set/Change/Remove Password (Requires PASSWORD_CHANGE_GCODE)
|
||||
* M524 - Abort the current SD print job started with M24. (Requires SDSUPPORT)
|
||||
* M540 - Enable/disable SD card abort on endstop hit: "M540 S<state>". (Requires SD_ABORT_ON_ENDSTOP_HIT)
|
||||
* M552 - Get or set IP address. Enable/disable network interface. (Requires enabled Ethernet port)
|
||||
@@ -245,6 +264,7 @@
|
||||
* M605 - Set Dual X-Carriage movement mode: "M605 S<mode> [X<x_offset>] [R<temp_offset>]". (Requires DUAL_X_CARRIAGE)
|
||||
* M665 - Set delta configurations: "M665 H<delta height> L<diagonal rod> R<delta radius> S<segments/s> B<calibration radius> X<Alpha angle trim> Y<Beta angle trim> Z<Gamma angle trim> (Requires DELTA)
|
||||
* Set SCARA configurations: "M665 S<segments-per-second> P<theta-psi-offset> T<theta-offset> Z<z-offset> (Requires MORGAN_SCARA or MP_SCARA)
|
||||
* Set Polargraph draw area and belt length: "M665 S<segments-per-second> L<draw-area-left> R<draw-area-right> T<draw-area-top> B<draw-area-bottom> H<max-belt-length>"
|
||||
* M666 - Set/get offsets for delta (Requires DELTA) or dual endstops. (Requires [XYZ]_DUAL_ENDSTOPS)
|
||||
* M672 - Set/Reset Duet Smart Effector's sensitivity. (Requires DUET_SMART_EFFECTOR and SMART_EFFECTOR_MOD_PIN)
|
||||
* M701 - Load filament (Requires FILAMENT_LOAD_UNLOAD_GCODES)
|
||||
@@ -252,7 +272,9 @@
|
||||
* M808 - Set or Goto a Repeat Marker (Requires GCODE_REPEAT_MARKERS)
|
||||
* M810-M819 - Define/execute a G-code macro (Requires GCODE_MACROS)
|
||||
* M851 - Set Z probe's XYZ offsets in current units. (Negative values: X=left, Y=front, Z=below)
|
||||
* M852 - Set skew factors: "M852 [I<xy>] [J<xz>] [K<yz>]". (Requires SKEW_CORRECTION_GCODE, and SKEW_CORRECTION_FOR_Z for IJ)
|
||||
* M852 - Set skew factors: "M852 [I<xy>] [J<xz>] [K<yz>]". (Requires SKEW_CORRECTION_GCODE, plus SKEW_CORRECTION_FOR_Z for IJ)
|
||||
*
|
||||
*** I2C_POSITION_ENCODERS ***
|
||||
* M860 - Report the position of position encoder modules.
|
||||
* M861 - Report the status of position encoder modules.
|
||||
* M862 - Perform an axis continuity test for position encoder modules.
|
||||
@@ -263,11 +285,11 @@
|
||||
* M867 - Enable/disable or toggle error correction for position encoder modules.
|
||||
* M868 - Report or set position encoder module error correction threshold.
|
||||
* M869 - Report position encoder module error.
|
||||
* M871 - Print/reset/clear first layer temperature offset values. (Requires PROBE_TEMP_COMPENSATION)
|
||||
* M192 - Wait for probe temp (Requires PROBE_TEMP_COMPENSATION)
|
||||
*
|
||||
* M871 - Print/reset/clear first layer temperature offset values. (Requires PTC_PROBE, PTC_BED, or PTC_HOTEND)
|
||||
* M876 - Handle Prompt Response. (Requires HOST_PROMPT_SUPPORT and not EMERGENCY_PARSER)
|
||||
* M900 - Get or Set Linear Advance K-factor. (Requires LIN_ADVANCE)
|
||||
* M906 - Set or get motor current in milliamps using axis codes X, Y, Z, E. Report values if no axis codes given. (Requires at least one _DRIVER_TYPE defined as TMC2130/2160/5130/5160/2208/2209/2660 or L6470)
|
||||
* M906 - Set or get motor current in milliamps using axis codes XYZE, etc. Report values if no axis codes given. (Requires at least one _DRIVER_TYPE defined as TMC2130/2160/5130/5160/2208/2209/2660)
|
||||
* M907 - Set digital trimpot motor current using axis codes. (Requires a board with digital trimpots)
|
||||
* M908 - Control digital trimpot directly. (Requires HAS_MOTOR_CURRENT_DAC or DIGIPOTSS_PIN)
|
||||
* M909 - Print digipot/DAC current value. (Requires HAS_MOTOR_CURRENT_DAC)
|
||||
@@ -276,19 +298,19 @@
|
||||
* M912 - Clear stepper driver overtemperature pre-warn condition flag. (Requires at least one _DRIVER_TYPE defined as TMC2130/2160/5130/5160/2208/2209/2660)
|
||||
* M913 - Set HYBRID_THRESHOLD speed. (Requires HYBRID_THRESHOLD)
|
||||
* M914 - Set StallGuard sensitivity. (Requires SENSORLESS_HOMING or SENSORLESS_PROBING)
|
||||
* M916 - L6470 tuning: Increase KVAL_HOLD until thermal warning. (Requires at least one _DRIVER_TYPE L6470)
|
||||
* M917 - L6470 tuning: Find minimum current thresholds. (Requires at least one _DRIVER_TYPE L6470)
|
||||
* M918 - L6470 tuning: Increase speed until max or error. (Requires at least one _DRIVER_TYPE L6470)
|
||||
* M919 - Get or Set motor Chopper Times (time_off, hysteresis_end, hysteresis_start) using axis codes XYZE, etc. If no parameters are given, report. (Requires at least one _DRIVER_TYPE defined as TMC2130/2160/5130/5160/2208/2209/2660)
|
||||
* M951 - Set Magnetic Parking Extruder parameters. (Requires MAGNETIC_PARKING_EXTRUDER)
|
||||
* M3426 - Read MCP3426 ADC over I2C. (Requires HAS_MCP3426_ADC)
|
||||
* M7219 - Control Max7219 Matrix LEDs. (Requires MAX7219_GCODE)
|
||||
*
|
||||
*** SCARA ***
|
||||
* M360 - SCARA calibration: Move to cal-position ThetaA (0 deg calibration)
|
||||
* M361 - SCARA calibration: Move to cal-position ThetaB (90 deg calibration - steps per degree)
|
||||
* M362 - SCARA calibration: Move to cal-position PsiA (0 deg calibration)
|
||||
* M363 - SCARA calibration: Move to cal-position PsiB (90 deg calibration - steps per degree)
|
||||
* M364 - SCARA calibration: Move to cal-position PSIC (90 deg to Theta calibration position)
|
||||
*
|
||||
* ************ Custom codes - This can change to suit future G-code regulations
|
||||
*** Custom codes (can be changed to suit future G-code standards) ***
|
||||
* G425 - Calibrate using a conductive object. (Requires CALIBRATION_GCODE)
|
||||
* M928 - Start SD logging: "M928 filename.gco". Stop with M29. (Requires SDSUPPORT)
|
||||
* M993 - Backup SPI Flash to SD
|
||||
@@ -296,10 +318,11 @@
|
||||
* M995 - Touch screen calibration for TFT display
|
||||
* M997 - Perform in-application firmware update
|
||||
* M999 - Restart after being stopped by error
|
||||
*
|
||||
* D... - Custom Development G-code. Add hooks to 'gcode_D.cpp' for developers to test features. (Requires MARLIN_DEV_MODE)
|
||||
* D576 - Set buffer monitoring options. (Requires BUFFER_MONITORING)
|
||||
*
|
||||
* "T" Codes
|
||||
*** "T" Codes ***
|
||||
*
|
||||
* T0-T3 - Select an extruder (tool) by index: "T<n> F<units/min>"
|
||||
*/
|
||||
@@ -316,7 +339,7 @@
|
||||
#endif
|
||||
|
||||
enum AxisRelative : uint8_t {
|
||||
LOGICAL_AXIS_LIST(REL_E, REL_X, REL_Y, REL_Z, REL_I, REL_J, REL_K)
|
||||
LOGICAL_AXIS_LIST(REL_E, REL_X, REL_Y, REL_Z, REL_I, REL_J, REL_K, REL_U, REL_V, REL_W)
|
||||
#if HAS_EXTRUDERS
|
||||
, E_MODE_ABS, E_MODE_REL
|
||||
#endif
|
||||
@@ -329,7 +352,7 @@ public:
|
||||
|
||||
static axis_bits_t axis_relative;
|
||||
|
||||
static inline bool axis_is_relative(const AxisEnum a) {
|
||||
static bool axis_is_relative(const AxisEnum a) {
|
||||
#if HAS_EXTRUDERS
|
||||
if (a == E_AXIS) {
|
||||
if (TEST(axis_relative, E_MODE_REL)) return true;
|
||||
@@ -338,19 +361,20 @@ public:
|
||||
#endif
|
||||
return TEST(axis_relative, a);
|
||||
}
|
||||
static inline void set_relative_mode(const bool rel) {
|
||||
static void set_relative_mode(const bool rel) {
|
||||
axis_relative = rel ? (0 LOGICAL_AXIS_GANG(
|
||||
| _BV(REL_E),
|
||||
| _BV(REL_X), | _BV(REL_Y), | _BV(REL_Z),
|
||||
| _BV(REL_I), | _BV(REL_J), | _BV(REL_K)
|
||||
| _BV(REL_I), | _BV(REL_J), | _BV(REL_K),
|
||||
| _BV(REL_U), | _BV(REL_V), | _BV(REL_W)
|
||||
)) : 0;
|
||||
}
|
||||
#if HAS_EXTRUDERS
|
||||
static inline void set_e_relative() {
|
||||
static void set_e_relative() {
|
||||
CBI(axis_relative, E_MODE_ABS);
|
||||
SBI(axis_relative, E_MODE_REL);
|
||||
}
|
||||
static inline void set_e_absolute() {
|
||||
static void set_e_absolute() {
|
||||
CBI(axis_relative, E_MODE_REL);
|
||||
SBI(axis_relative, E_MODE_ABS);
|
||||
}
|
||||
@@ -372,48 +396,54 @@ public:
|
||||
static bool select_coordinate_system(const int8_t _new);
|
||||
#endif
|
||||
|
||||
static millis_t previous_move_ms, max_inactive_time, stepper_inactive_time;
|
||||
FORCE_INLINE static void reset_stepper_timeout(const millis_t ms=millis()) { previous_move_ms = ms; }
|
||||
static millis_t previous_move_ms, max_inactive_time;
|
||||
FORCE_INLINE static bool stepper_max_timed_out(const millis_t ms=millis()) {
|
||||
return max_inactive_time && ELAPSED(ms, previous_move_ms + max_inactive_time);
|
||||
}
|
||||
FORCE_INLINE static bool stepper_inactive_timeout(const millis_t ms=millis()) {
|
||||
return ELAPSED(ms, previous_move_ms + stepper_inactive_time);
|
||||
}
|
||||
FORCE_INLINE static void reset_stepper_timeout(const millis_t ms=millis()) { previous_move_ms = ms; }
|
||||
|
||||
#if HAS_DISABLE_INACTIVE_AXIS
|
||||
static millis_t stepper_inactive_time;
|
||||
FORCE_INLINE static bool stepper_inactive_timeout(const millis_t ms=millis()) {
|
||||
return ELAPSED(ms, previous_move_ms + stepper_inactive_time);
|
||||
}
|
||||
#else
|
||||
static bool stepper_inactive_timeout(const millis_t) { return false; }
|
||||
#endif
|
||||
|
||||
static void report_echo_start(const bool forReplay);
|
||||
static void report_heading(const bool forReplay, PGM_P const pstr, const bool eol=true);
|
||||
static inline void report_heading_etc(const bool forReplay, PGM_P const pstr, const bool eol=true) {
|
||||
report_heading(forReplay, pstr, eol);
|
||||
static void report_heading(const bool forReplay, FSTR_P const fstr, const bool eol=true);
|
||||
static void report_heading_etc(const bool forReplay, FSTR_P const fstr, const bool eol=true) {
|
||||
report_heading(forReplay, fstr, eol);
|
||||
report_echo_start(forReplay);
|
||||
}
|
||||
static void say_units();
|
||||
|
||||
static int8_t get_target_extruder_from_command();
|
||||
static int8_t get_target_e_stepper_from_command();
|
||||
static int8_t get_target_e_stepper_from_command(const int8_t dval=-1);
|
||||
static void get_destination_from_command();
|
||||
|
||||
static void process_parsed_command(const bool no_ok=false);
|
||||
static void process_next_command();
|
||||
|
||||
// Execute G-code in-place, preserving current G-code parameters
|
||||
static void process_subcommands_now_P(PGM_P pgcode);
|
||||
static void process_subcommands_now(FSTR_P fgcode);
|
||||
static void process_subcommands_now(char * gcode);
|
||||
|
||||
static inline void home_all_axes(const bool keep_leveling=false) {
|
||||
process_subcommands_now_P(keep_leveling ? G28_STR : TERN(CAN_SET_LEVELING_AFTER_G28, PSTR("G28L0"), G28_STR));
|
||||
static void home_all_axes(const bool keep_leveling=false) {
|
||||
process_subcommands_now(keep_leveling ? FPSTR(G28_STR) : TERN(CAN_SET_LEVELING_AFTER_G28, F("G28L0"), FPSTR(G28_STR)));
|
||||
}
|
||||
|
||||
#if EITHER(HAS_AUTO_REPORTING, HOST_KEEPALIVE_FEATURE)
|
||||
static bool autoreport_paused;
|
||||
static inline bool set_autoreport_paused(const bool p) {
|
||||
static bool set_autoreport_paused(const bool p) {
|
||||
const bool was = autoreport_paused;
|
||||
autoreport_paused = p;
|
||||
return was;
|
||||
}
|
||||
#else
|
||||
static constexpr bool autoreport_paused = false;
|
||||
static inline bool set_autoreport_paused(const bool) { return false; }
|
||||
static bool set_autoreport_paused(const bool) { return false; }
|
||||
#endif
|
||||
|
||||
#if ENABLED(HOST_KEEPALIVE_FEATURE)
|
||||
@@ -433,7 +463,7 @@ public:
|
||||
static uint8_t host_keepalive_interval;
|
||||
|
||||
static void host_keepalive();
|
||||
static inline bool host_keepalive_is_paused() { return busy_state >= PAUSED_FOR_USER; }
|
||||
static bool host_keepalive_is_paused() { return busy_state >= PAUSED_FOR_USER; }
|
||||
|
||||
#define KEEPALIVE_STATE(N) REMEMBER(_KA_, gcode.busy_state, gcode.N)
|
||||
#else
|
||||
@@ -551,7 +581,7 @@ private:
|
||||
static void G59();
|
||||
#endif
|
||||
|
||||
#if ENABLED(PROBE_TEMP_COMPENSATION)
|
||||
#if BOTH(PTC_PROBE, PTC_BED)
|
||||
static void G76();
|
||||
#endif
|
||||
|
||||
@@ -677,6 +707,11 @@ private:
|
||||
static void M100();
|
||||
#endif
|
||||
|
||||
#if ENABLED(BD_SENSOR)
|
||||
static void M102();
|
||||
static void M102_report(const bool forReplay=true);
|
||||
#endif
|
||||
|
||||
#if HAS_EXTRUDERS
|
||||
static void M104_M109(const bool isM109);
|
||||
FORCE_INLINE static void M104() { M104_M109(false); }
|
||||
@@ -718,6 +753,10 @@ private:
|
||||
static void M120();
|
||||
static void M121();
|
||||
|
||||
#if HAS_FANCHECK
|
||||
static void M123();
|
||||
#endif
|
||||
|
||||
#if ENABLED(PARK_HEAD_ON_PAUSE)
|
||||
static void M125();
|
||||
#endif
|
||||
@@ -744,12 +783,16 @@ private:
|
||||
static void M191();
|
||||
#endif
|
||||
|
||||
#if HAS_TEMP_PROBE
|
||||
static void M192();
|
||||
#endif
|
||||
|
||||
#if HAS_COOLER
|
||||
static void M143();
|
||||
static void M193();
|
||||
#endif
|
||||
|
||||
#if PREHEAT_COUNT
|
||||
#if HAS_PREHEAT
|
||||
static void M145();
|
||||
static void M145_report(const bool forReplay=true);
|
||||
#endif
|
||||
@@ -848,6 +891,11 @@ private:
|
||||
static void M250_report(const bool forReplay=true);
|
||||
#endif
|
||||
|
||||
#if HAS_GCODE_M255
|
||||
static void M255();
|
||||
static void M255_report(const bool forReplay=true);
|
||||
#endif
|
||||
|
||||
#if HAS_LCD_BRIGHTNESS
|
||||
static void M256();
|
||||
static void M256_report(const bool forReplay=true);
|
||||
@@ -873,7 +921,7 @@ private:
|
||||
static void M290();
|
||||
#endif
|
||||
|
||||
#if HAS_BUZZER
|
||||
#if HAS_SOUND
|
||||
static void M300();
|
||||
#endif
|
||||
|
||||
@@ -899,6 +947,11 @@ private:
|
||||
static void M305();
|
||||
#endif
|
||||
|
||||
#if ENABLED(MPCTEMP)
|
||||
static void M306();
|
||||
static void M306_report(const bool forReplay=true);
|
||||
#endif
|
||||
|
||||
#if ENABLED(PIDTEMPCHAMBER)
|
||||
static void M309();
|
||||
static void M309_report(const bool forReplay=true);
|
||||
@@ -1087,8 +1140,7 @@ private:
|
||||
FORCE_INLINE static void M869() { I2CPEM.M869(); }
|
||||
#endif
|
||||
|
||||
#if ENABLED(PROBE_TEMP_COMPENSATION)
|
||||
static void M192();
|
||||
#if HAS_PTC
|
||||
static void M871();
|
||||
#endif
|
||||
|
||||
@@ -1109,18 +1161,11 @@ private:
|
||||
static void M913();
|
||||
static void M913_report(const bool forReplay=true);
|
||||
#endif
|
||||
#if ENABLED(USE_SENSORLESS)
|
||||
#if USE_SENSORLESS
|
||||
static void M914();
|
||||
static void M914_report(const bool forReplay=true);
|
||||
#endif
|
||||
#endif
|
||||
|
||||
#if HAS_L64XX
|
||||
static void M122();
|
||||
static void M906();
|
||||
static void M916();
|
||||
static void M917();
|
||||
static void M918();
|
||||
static void M919();
|
||||
#endif
|
||||
|
||||
#if HAS_MOTOR_CURRENT_SPI || HAS_MOTOR_CURRENT_PWM || HAS_MOTOR_CURRENT_I2C || HAS_MOTOR_CURRENT_DAC
|
||||
@@ -1166,6 +1211,11 @@ private:
|
||||
static void M1000();
|
||||
#endif
|
||||
|
||||
#if ENABLED(X_AXIS_TWIST_COMPENSATION)
|
||||
static void M423();
|
||||
static void M423_report(const bool forReplay=true);
|
||||
#endif
|
||||
|
||||
#if ENABLED(SDSUPPORT)
|
||||
static void M1001();
|
||||
#endif
|
||||
@@ -1178,6 +1228,10 @@ private:
|
||||
static void M1004();
|
||||
#endif
|
||||
|
||||
#if ENABLED(HAS_MCP3426_ADC)
|
||||
static void M3426();
|
||||
#endif
|
||||
|
||||
#if ENABLED(MAX7219_GCODE)
|
||||
static void M7219();
|
||||
#endif
|
||||
|
@@ -38,7 +38,7 @@
|
||||
#include "../sd/cardreader.h"
|
||||
#include "../MarlinCore.h" // for kill
|
||||
|
||||
extern void dump_delay_accuracy_check();
|
||||
void dump_delay_accuracy_check();
|
||||
|
||||
/**
|
||||
* Dn: G-code for development and testing
|
||||
@@ -54,11 +54,11 @@ void GcodeSuite::D(const int16_t dcode) {
|
||||
for (;;) { /* loop forever (watchdog reset) */ }
|
||||
|
||||
case 0:
|
||||
HAL_reboot();
|
||||
hal.reboot();
|
||||
break;
|
||||
|
||||
case 10:
|
||||
kill(PSTR("D10"), PSTR("KILL TEST"), parser.seen_test('P'));
|
||||
kill(F("D10"), F("KILL TEST"), parser.seen_test('P'));
|
||||
break;
|
||||
|
||||
case 1: {
|
||||
@@ -74,7 +74,7 @@ void GcodeSuite::D(const int16_t dcode) {
|
||||
settings.reset();
|
||||
settings.save();
|
||||
#endif
|
||||
HAL_reboot();
|
||||
hal.reboot();
|
||||
} break;
|
||||
|
||||
case 2: { // D2 Read / Write SRAM
|
||||
@@ -189,12 +189,12 @@ void GcodeSuite::D(const int16_t dcode) {
|
||||
SERIAL_ECHOLNPGM("(USE_WATCHDOG " TERN(USE_WATCHDOG, "ENABLED", "DISABLED") ")");
|
||||
thermalManager.disable_all_heaters();
|
||||
delay(1000); // Allow time to print
|
||||
DISABLE_ISRS();
|
||||
hal.isr_off();
|
||||
// Use a low-level delay that does not rely on interrupts to function
|
||||
// Do not spin forever, to avoid thermal risks if heaters are enabled and
|
||||
// watchdog does not work.
|
||||
for (int i = 10000; i--;) DELAY_US(1000UL);
|
||||
ENABLE_ISRS();
|
||||
hal.isr_on();
|
||||
SERIAL_ECHOLNPGM("FAILURE: Watchdog did not trigger board reset.");
|
||||
} break;
|
||||
|
||||
@@ -214,7 +214,7 @@ void GcodeSuite::D(const int16_t dcode) {
|
||||
|
||||
c = 1024 * 4;
|
||||
while (c--) {
|
||||
TERN_(USE_WATCHDOG, watchdog_refresh());
|
||||
hal.watchdog_refresh();
|
||||
card.write(buf, COUNT(buf));
|
||||
}
|
||||
SERIAL_ECHOLNPGM(" done");
|
||||
@@ -231,7 +231,7 @@ void GcodeSuite::D(const int16_t dcode) {
|
||||
__attribute__((aligned(sizeof(size_t)))) uint8_t buf[512];
|
||||
uint16_t c = 1024 * 4;
|
||||
while (c--) {
|
||||
TERN_(USE_WATCHDOG, watchdog_refresh());
|
||||
hal.watchdog_refresh();
|
||||
card.read(buf, COUNT(buf));
|
||||
bool error = false;
|
||||
for (uint16_t i = 0; i < COUNT(buf); i++) {
|
||||
|
@@ -29,10 +29,10 @@
|
||||
inline void report_workspace_plane() {
|
||||
SERIAL_ECHO_START();
|
||||
SERIAL_ECHOPGM("Workspace Plane ");
|
||||
SERIAL_ECHOPGM_P(
|
||||
gcode.workspace_plane == GcodeSuite::PLANE_YZ ? PSTR("YZ\n")
|
||||
: gcode.workspace_plane == GcodeSuite::PLANE_ZX ? PSTR("ZX\n")
|
||||
: PSTR("XY\n")
|
||||
SERIAL_ECHOF(
|
||||
gcode.workspace_plane == GcodeSuite::PLANE_YZ ? F("YZ\n")
|
||||
: gcode.workspace_plane == GcodeSuite::PLANE_ZX ? F("ZX\n")
|
||||
: F("XY\n")
|
||||
);
|
||||
}
|
||||
|
||||
|
@@ -25,8 +25,6 @@
|
||||
|
||||
#if ENABLED(CNC_COORDINATE_SYSTEMS)
|
||||
|
||||
#include "../../module/stepper.h"
|
||||
|
||||
//#define DEBUG_M53
|
||||
|
||||
/**
|
||||
@@ -39,7 +37,7 @@ bool GcodeSuite::select_coordinate_system(const int8_t _new) {
|
||||
xyz_float_t new_offset{0};
|
||||
if (WITHIN(_new, 0, MAX_COORDINATE_SYSTEMS - 1))
|
||||
new_offset = coordinate_system[_new];
|
||||
LOOP_LINEAR_AXES(i) {
|
||||
LOOP_NUM_AXES(i) {
|
||||
if (position_shift[i] != new_offset[i]) {
|
||||
position_shift[i] = new_offset[i];
|
||||
update_workspace_offset((AxisEnum)i);
|
||||
|
@@ -22,14 +22,13 @@
|
||||
|
||||
#include "../gcode.h"
|
||||
#include "../../module/motion.h"
|
||||
#include "../../module/stepper.h"
|
||||
|
||||
#if ENABLED(I2C_POSITION_ENCODERS)
|
||||
#include "../../feature/encoder_i2c.h"
|
||||
#endif
|
||||
|
||||
/**
|
||||
* G92: Set the Current Position to the given X Y Z E values.
|
||||
* G92: Set the Current Position to the given X [Y [Z [A [B [C [U [V [W ]]]]]]]] [E] values.
|
||||
*
|
||||
* Behind the scenes the G92 command may modify the Current Position
|
||||
* or the Position Shift depending on settings and sub-commands.
|
||||
@@ -37,14 +36,14 @@
|
||||
* Since E has no Workspace Offset, it is always set directly.
|
||||
*
|
||||
* Without Workspace Offsets (e.g., with NO_WORKSPACE_OFFSETS):
|
||||
* G92 : Set NATIVE Current Position to the given X Y Z E.
|
||||
* G92 : Set NATIVE Current Position to the given X [Y [Z [A [B [C [U [V [W ]]]]]]]] [E].
|
||||
*
|
||||
* Using Workspace Offsets (default Marlin behavior):
|
||||
* G92 : Modify Workspace Offsets so the reported position shows the given X Y Z E.
|
||||
* G92 : Modify Workspace Offsets so the reported position shows the given X [Y [Z [A [B [C [U [V [W ]]]]]]]] [E].
|
||||
* G92.1 : Zero XYZ Workspace Offsets (so the reported position = the native position).
|
||||
*
|
||||
* With POWER_LOSS_RECOVERY:
|
||||
* G92.9 : Set NATIVE Current Position to the given X Y Z E.
|
||||
* G92.9 : Set NATIVE Current Position to the given X [Y [Z [A [B [C [U [V [W ]]]]]]]] [E].
|
||||
*/
|
||||
void GcodeSuite::G92() {
|
||||
|
||||
@@ -64,7 +63,7 @@ void GcodeSuite::G92() {
|
||||
|
||||
#if ENABLED(CNC_COORDINATE_SYSTEMS) && !IS_SCARA
|
||||
case 1: // G92.1 - Zero the Workspace Offset
|
||||
LOOP_LINEAR_AXES(i) if (position_shift[i]) {
|
||||
LOOP_NUM_AXES(i) if (position_shift[i]) {
|
||||
position_shift[i] = 0;
|
||||
update_workspace_offset((AxisEnum)i);
|
||||
}
|
||||
@@ -74,7 +73,7 @@ void GcodeSuite::G92() {
|
||||
#if ENABLED(POWER_LOSS_RECOVERY)
|
||||
case 9: // G92.9 - Set Current Position directly (like Marlin 1.0)
|
||||
LOOP_LOGICAL_AXES(i) {
|
||||
if (parser.seenval(axis_codes[i])) {
|
||||
if (parser.seenval(AXIS_CHAR(i))) {
|
||||
if (TERN1(HAS_EXTRUDERS, i != E_AXIS))
|
||||
sync_XYZE = true;
|
||||
else {
|
||||
@@ -88,12 +87,12 @@ void GcodeSuite::G92() {
|
||||
|
||||
case 0:
|
||||
LOOP_LOGICAL_AXES(i) {
|
||||
if (parser.seenval(axis_codes[i])) {
|
||||
if (parser.seenval(AXIS_CHAR(i))) {
|
||||
const float l = parser.value_axis_units((AxisEnum)i), // Given axis coordinate value, converted to millimeters
|
||||
v = TERN0(HAS_EXTRUDERS, i == E_AXIS) ? l : LOGICAL_TO_NATIVE(l, i), // Axis position in NATIVE space (applying the existing offset)
|
||||
d = v - current_position[i]; // How much is the current axis position altered by?
|
||||
if (!NEAR_ZERO(d)) {
|
||||
#if HAS_POSITION_SHIFT && !IS_SCARA // When using workspaces...
|
||||
#if HAS_POSITION_SHIFT && NONE(IS_SCARA, POLARGRAPH) // When using workspaces...
|
||||
if (TERN1(HAS_EXTRUDERS, i != E_AXIS)) {
|
||||
position_shift[i] += d; // ...most axes offset the workspace...
|
||||
update_workspace_offset((AxisEnum)i);
|
||||
|
@@ -39,30 +39,30 @@
|
||||
*/
|
||||
void GcodeSuite::M206() {
|
||||
if (!parser.seen_any()) return M206_report();
|
||||
|
||||
LOOP_LINEAR_AXES(i)
|
||||
if (parser.seen(AXIS_CHAR(i)))
|
||||
set_home_offset((AxisEnum)i, parser.value_linear_units());
|
||||
|
||||
LOOP_NUM_AXES(a)
|
||||
if (parser.seenval(AXIS_CHAR(a))) set_home_offset((AxisEnum)a, parser.value_axis_units((AxisEnum)a));
|
||||
#if ENABLED(MORGAN_SCARA)
|
||||
if (parser.seen('T')) set_home_offset(A_AXIS, parser.value_float()); // Theta
|
||||
if (parser.seen('P')) set_home_offset(B_AXIS, parser.value_float()); // Psi
|
||||
if (parser.seenval('T')) set_home_offset(A_AXIS, parser.value_float()); // Theta
|
||||
if (parser.seenval('P')) set_home_offset(B_AXIS, parser.value_float()); // Psi
|
||||
#endif
|
||||
|
||||
report_current_position();
|
||||
}
|
||||
|
||||
void GcodeSuite::M206_report(const bool forReplay/*=true*/) {
|
||||
report_heading_etc(forReplay, PSTR(STR_HOME_OFFSET));
|
||||
report_heading_etc(forReplay, F(STR_HOME_OFFSET));
|
||||
SERIAL_ECHOLNPGM_P(
|
||||
#if IS_CARTESIAN
|
||||
LIST_N(DOUBLE(LINEAR_AXES),
|
||||
LIST_N(DOUBLE(NUM_AXES),
|
||||
PSTR(" M206 X"), LINEAR_UNIT(home_offset.x),
|
||||
SP_Y_STR, LINEAR_UNIT(home_offset.y),
|
||||
SP_Z_STR, LINEAR_UNIT(home_offset.z),
|
||||
SP_I_STR, LINEAR_UNIT(home_offset.i),
|
||||
SP_J_STR, LINEAR_UNIT(home_offset.j),
|
||||
SP_K_STR, LINEAR_UNIT(home_offset.k)
|
||||
SP_I_STR, I_AXIS_UNIT(home_offset.i),
|
||||
SP_J_STR, J_AXIS_UNIT(home_offset.j),
|
||||
SP_K_STR, K_AXIS_UNIT(home_offset.k),
|
||||
SP_U_STR, U_AXIS_UNIT(home_offset.u),
|
||||
SP_V_STR, V_AXIS_UNIT(home_offset.v),
|
||||
SP_W_STR, W_AXIS_UNIT(home_offset.w)
|
||||
)
|
||||
#else
|
||||
PSTR(" M206 Z"), LINEAR_UNIT(home_offset.z)
|
||||
@@ -85,23 +85,22 @@ void GcodeSuite::M428() {
|
||||
if (homing_needed_error()) return;
|
||||
|
||||
xyz_float_t diff;
|
||||
LOOP_LINEAR_AXES(i) {
|
||||
LOOP_NUM_AXES(i) {
|
||||
diff[i] = base_home_pos((AxisEnum)i) - current_position[i];
|
||||
if (!WITHIN(diff[i], -20, 20) && home_dir((AxisEnum)i) > 0)
|
||||
diff[i] = -current_position[i];
|
||||
if (!WITHIN(diff[i], -20, 20)) {
|
||||
SERIAL_ERROR_MSG(STR_ERR_M428_TOO_FAR);
|
||||
LCD_ALERTMESSAGEPGM_P(PSTR("Err: Too far!"));
|
||||
BUZZ(200, 40);
|
||||
LCD_ALERTMESSAGE_F("Err: Too far!");
|
||||
ERR_BUZZ();
|
||||
return;
|
||||
}
|
||||
}
|
||||
|
||||
LOOP_LINEAR_AXES(i) set_home_offset((AxisEnum)i, diff[i]);
|
||||
LOOP_NUM_AXES(i) set_home_offset((AxisEnum)i, diff[i]);
|
||||
report_current_position();
|
||||
LCD_MESSAGEPGM(MSG_HOME_OFFSETS_APPLIED);
|
||||
BUZZ(100, 659);
|
||||
BUZZ(100, 698);
|
||||
LCD_MESSAGE(MSG_HOME_OFFSETS_APPLIED);
|
||||
OKAY_BUZZ();
|
||||
}
|
||||
|
||||
#endif // HAS_M206_COMMAND
|
||||
|
@@ -28,16 +28,10 @@
|
||||
|
||||
#if ENABLED(M114_DETAIL)
|
||||
|
||||
#if HAS_L64XX
|
||||
#include "../../libs/L64XX/L64XX_Marlin.h"
|
||||
#define DEBUG_OUT ENABLED(L6470_CHITCHAT)
|
||||
#include "../../core/debug_out.h"
|
||||
#endif
|
||||
|
||||
void report_all_axis_pos(const xyze_pos_t &pos, const uint8_t n=XYZE, const uint8_t precision=3) {
|
||||
void report_all_axis_pos(const xyze_pos_t &pos, const uint8_t n=LOGICAL_AXES, const uint8_t precision=3) {
|
||||
char str[12];
|
||||
LOOP_L_N(a, n) {
|
||||
SERIAL_CHAR(' ', axis_codes[a], ':');
|
||||
SERIAL_ECHOPGM_P((PGM_P)pgm_read_ptr(&SP_AXIS_LBL[a]));
|
||||
if (pos[a] >= 0) SERIAL_CHAR(' ');
|
||||
SERIAL_ECHO(dtostrf(pos[a], 1, precision, str));
|
||||
}
|
||||
@@ -47,10 +41,7 @@
|
||||
|
||||
void report_linear_axis_pos(const xyz_pos_t &pos, const uint8_t precision=3) {
|
||||
char str[12];
|
||||
LOOP_LINEAR_AXES(a) {
|
||||
SERIAL_CHAR(' ', AXIS_CHAR(a), ':');
|
||||
SERIAL_ECHO(dtostrf(pos[a], 1, precision, str));
|
||||
}
|
||||
LOOP_NUM_AXES(a) SERIAL_ECHOPGM_P((PGM_P)pgm_read_ptr(&SP_AXIS_LBL[a]), dtostrf(pos[a], 1, precision, str));
|
||||
SERIAL_EOL();
|
||||
}
|
||||
|
||||
@@ -87,84 +78,9 @@
|
||||
|
||||
planner.synchronize();
|
||||
|
||||
#if HAS_L64XX
|
||||
char temp_buf[80];
|
||||
int32_t temp;
|
||||
//#define ABS_POS_SIGN_MASK 0b1111 1111 1110 0000 0000 0000 0000 0000
|
||||
#define ABS_POS_SIGN_MASK 0b11111111111000000000000000000000
|
||||
#define REPORT_ABSOLUTE_POS(Q) do{ \
|
||||
L64xxManager.say_axis(Q, false); \
|
||||
temp = L6470_GETPARAM(L6470_ABS_POS,Q); \
|
||||
if (temp & ABS_POS_SIGN_MASK) temp |= ABS_POS_SIGN_MASK; \
|
||||
sprintf_P(temp_buf, PSTR(":%8ld "), temp); \
|
||||
DEBUG_ECHO(temp_buf); \
|
||||
}while(0)
|
||||
|
||||
DEBUG_ECHOPGM("\nL6470:");
|
||||
#if AXIS_IS_L64XX(X)
|
||||
REPORT_ABSOLUTE_POS(X);
|
||||
#endif
|
||||
#if AXIS_IS_L64XX(X2)
|
||||
REPORT_ABSOLUTE_POS(X2);
|
||||
#endif
|
||||
#if AXIS_IS_L64XX(Y)
|
||||
REPORT_ABSOLUTE_POS(Y);
|
||||
#endif
|
||||
#if AXIS_IS_L64XX(Y2)
|
||||
REPORT_ABSOLUTE_POS(Y2);
|
||||
#endif
|
||||
#if AXIS_IS_L64XX(Z)
|
||||
REPORT_ABSOLUTE_POS(Z);
|
||||
#endif
|
||||
#if AXIS_IS_L64XX(Z2)
|
||||
REPORT_ABSOLUTE_POS(Z2);
|
||||
#endif
|
||||
#if AXIS_IS_L64XX(Z3)
|
||||
REPORT_ABSOLUTE_POS(Z3);
|
||||
#endif
|
||||
#if AXIS_IS_L64XX(Z4)
|
||||
REPORT_ABSOLUTE_POS(Z4);
|
||||
#endif
|
||||
#if AXIS_IS_L64XX(I)
|
||||
REPORT_ABSOLUTE_POS(I);
|
||||
#endif
|
||||
#if AXIS_IS_L64XX(J)
|
||||
REPORT_ABSOLUTE_POS(J);
|
||||
#endif
|
||||
#if AXIS_IS_L64XX(K)
|
||||
REPORT_ABSOLUTE_POS(K);
|
||||
#endif
|
||||
#if AXIS_IS_L64XX(E0)
|
||||
REPORT_ABSOLUTE_POS(E0);
|
||||
#endif
|
||||
#if AXIS_IS_L64XX(E1)
|
||||
REPORT_ABSOLUTE_POS(E1);
|
||||
#endif
|
||||
#if AXIS_IS_L64XX(E2)
|
||||
REPORT_ABSOLUTE_POS(E2);
|
||||
#endif
|
||||
#if AXIS_IS_L64XX(E3)
|
||||
REPORT_ABSOLUTE_POS(E3);
|
||||
#endif
|
||||
#if AXIS_IS_L64XX(E4)
|
||||
REPORT_ABSOLUTE_POS(E4);
|
||||
#endif
|
||||
#if AXIS_IS_L64XX(E5)
|
||||
REPORT_ABSOLUTE_POS(E5);
|
||||
#endif
|
||||
#if AXIS_IS_L64XX(E6)
|
||||
REPORT_ABSOLUTE_POS(E6);
|
||||
#endif
|
||||
#if AXIS_IS_L64XX(E7)
|
||||
REPORT_ABSOLUTE_POS(E7);
|
||||
#endif
|
||||
SERIAL_EOL();
|
||||
#endif // HAS_L64XX
|
||||
|
||||
SERIAL_ECHOPGM("Stepper:");
|
||||
LOOP_LOGICAL_AXES(i) {
|
||||
SERIAL_CHAR(' ', axis_codes[i], ':');
|
||||
SERIAL_ECHO(stepper.position((AxisEnum)i));
|
||||
SERIAL_ECHOPGM_P((PGM_P)pgm_read_ptr(&SP_AXIS_LBL[i]), stepper.position((AxisEnum)i));
|
||||
}
|
||||
SERIAL_EOL();
|
||||
|
||||
@@ -184,7 +100,10 @@
|
||||
cartes.x, cartes.y, cartes.z,
|
||||
planner.get_axis_position_mm(I_AXIS),
|
||||
planner.get_axis_position_mm(J_AXIS),
|
||||
planner.get_axis_position_mm(K_AXIS)
|
||||
planner.get_axis_position_mm(K_AXIS),
|
||||
planner.get_axis_position_mm(U_AXIS),
|
||||
planner.get_axis_position_mm(V_AXIS),
|
||||
planner.get_axis_position_mm(W_AXIS)
|
||||
);
|
||||
report_all_axis_pos(from_steppers);
|
||||
|
||||
|
@@ -24,7 +24,6 @@
|
||||
#include "../../inc/MarlinConfig.h"
|
||||
#include "../queue.h" // for getting the command port
|
||||
|
||||
|
||||
#if ENABLED(M115_GEOMETRY_REPORT)
|
||||
#include "../../module/motion.h"
|
||||
#endif
|
||||
@@ -33,13 +32,25 @@
|
||||
#include "../../feature/caselight.h"
|
||||
#endif
|
||||
|
||||
//#define MINIMAL_CAP_LINES // Don't even mention the disabled capabilities
|
||||
|
||||
#if ENABLED(EXTENDED_CAPABILITIES_REPORT)
|
||||
static void cap_line(PGM_P const name, bool ena=false) {
|
||||
SERIAL_ECHOPGM("Cap:");
|
||||
SERIAL_ECHOPGM_P(name);
|
||||
SERIAL_CHAR(':', '0' + ena);
|
||||
SERIAL_EOL();
|
||||
}
|
||||
#if ENABLED(MINIMAL_CAP_LINES)
|
||||
#define cap_line(S,C) if (C) _cap_line(S)
|
||||
static void _cap_line(FSTR_P const name) {
|
||||
SERIAL_ECHOPGM("Cap:");
|
||||
SERIAL_ECHOF(name);
|
||||
SERIAL_ECHOLNPGM(":1");
|
||||
}
|
||||
#else
|
||||
#define cap_line(V...) _cap_line(V)
|
||||
static void _cap_line(FSTR_P const name, bool ena=false) {
|
||||
SERIAL_ECHOPGM("Cap:");
|
||||
SERIAL_ECHOF(name);
|
||||
SERIAL_CHAR(':', '0' + ena);
|
||||
SERIAL_EOL();
|
||||
}
|
||||
#endif
|
||||
#endif
|
||||
|
||||
/**
|
||||
@@ -54,8 +65,8 @@ void GcodeSuite::M115() {
|
||||
"PROTOCOL_VERSION:" PROTOCOL_VERSION " "
|
||||
"MACHINE_TYPE:" MACHINE_NAME " "
|
||||
"EXTRUDER_COUNT:" STRINGIFY(EXTRUDERS) " "
|
||||
#if LINEAR_AXES != XYZ
|
||||
"AXIS_COUNT:" STRINGIFY(LINEAR_AXES) " "
|
||||
#if NUM_AXES != XYZ
|
||||
"AXIS_COUNT:" STRINGIFY(NUM_AXES) " "
|
||||
#endif
|
||||
#ifdef MACHINE_UUID
|
||||
"UUID:" MACHINE_UUID
|
||||
@@ -68,101 +79,118 @@ void GcodeSuite::M115() {
|
||||
serial_index_t port = queue.ring_buffer.command_port();
|
||||
|
||||
// PAREN_COMMENTS
|
||||
TERN_(PAREN_COMMENTS, cap_line(PSTR("PAREN_COMMENTS"), true));
|
||||
TERN_(PAREN_COMMENTS, cap_line(F("PAREN_COMMENTS"), true));
|
||||
|
||||
// QUOTED_STRINGS
|
||||
TERN_(GCODE_QUOTED_STRINGS, cap_line(PSTR("QUOTED_STRINGS"), true));
|
||||
TERN_(GCODE_QUOTED_STRINGS, cap_line(F("QUOTED_STRINGS"), true));
|
||||
|
||||
// SERIAL_XON_XOFF
|
||||
cap_line(PSTR("SERIAL_XON_XOFF"), ENABLED(SERIAL_XON_XOFF));
|
||||
cap_line(F("SERIAL_XON_XOFF"), ENABLED(SERIAL_XON_XOFF));
|
||||
|
||||
// BINARY_FILE_TRANSFER (M28 B1)
|
||||
cap_line(PSTR("BINARY_FILE_TRANSFER"), ENABLED(BINARY_FILE_TRANSFER)); // TODO: Use SERIAL_IMPL.has_feature(port, SerialFeature::BinaryFileTransfer) once implemented
|
||||
cap_line(F("BINARY_FILE_TRANSFER"), ENABLED(BINARY_FILE_TRANSFER)); // TODO: Use SERIAL_IMPL.has_feature(port, SerialFeature::BinaryFileTransfer) once implemented
|
||||
|
||||
// EEPROM (M500, M501)
|
||||
cap_line(PSTR("EEPROM"), ENABLED(EEPROM_SETTINGS));
|
||||
cap_line(F("EEPROM"), ENABLED(EEPROM_SETTINGS));
|
||||
|
||||
// Volumetric Extrusion (M200)
|
||||
cap_line(PSTR("VOLUMETRIC"), DISABLED(NO_VOLUMETRICS));
|
||||
cap_line(F("VOLUMETRIC"), DISABLED(NO_VOLUMETRICS));
|
||||
|
||||
// AUTOREPORT_POS (M154)
|
||||
cap_line(PSTR("AUTOREPORT_POS"), ENABLED(AUTO_REPORT_POSITION));
|
||||
cap_line(F("AUTOREPORT_POS"), ENABLED(AUTO_REPORT_POSITION));
|
||||
|
||||
// AUTOREPORT_TEMP (M155)
|
||||
cap_line(PSTR("AUTOREPORT_TEMP"), ENABLED(AUTO_REPORT_TEMPERATURES));
|
||||
cap_line(F("AUTOREPORT_TEMP"), ENABLED(AUTO_REPORT_TEMPERATURES));
|
||||
|
||||
// PROGRESS (M530 S L, M531 <file>, M532 X L)
|
||||
cap_line(PSTR("PROGRESS"));
|
||||
cap_line(F("PROGRESS"));
|
||||
|
||||
// Print Job timer M75, M76, M77
|
||||
cap_line(PSTR("PRINT_JOB"), true);
|
||||
cap_line(F("PRINT_JOB"), true);
|
||||
|
||||
// AUTOLEVEL (G29)
|
||||
cap_line(PSTR("AUTOLEVEL"), ENABLED(HAS_AUTOLEVEL));
|
||||
cap_line(F("AUTOLEVEL"), ENABLED(HAS_AUTOLEVEL));
|
||||
|
||||
// RUNOUT (M412, M600)
|
||||
cap_line(PSTR("RUNOUT"), ENABLED(FILAMENT_RUNOUT_SENSOR));
|
||||
cap_line(F("RUNOUT"), ENABLED(FILAMENT_RUNOUT_SENSOR));
|
||||
|
||||
// Z_PROBE (G30)
|
||||
cap_line(PSTR("Z_PROBE"), ENABLED(HAS_BED_PROBE));
|
||||
cap_line(F("Z_PROBE"), ENABLED(HAS_BED_PROBE));
|
||||
|
||||
// MESH_REPORT (M420 V)
|
||||
cap_line(PSTR("LEVELING_DATA"), ENABLED(HAS_LEVELING));
|
||||
cap_line(F("LEVELING_DATA"), ENABLED(HAS_LEVELING));
|
||||
|
||||
// BUILD_PERCENT (M73)
|
||||
cap_line(PSTR("BUILD_PERCENT"), ENABLED(LCD_SET_PROGRESS_MANUALLY));
|
||||
cap_line(F("BUILD_PERCENT"), ENABLED(LCD_SET_PROGRESS_MANUALLY));
|
||||
|
||||
// SOFTWARE_POWER (M80, M81)
|
||||
cap_line(PSTR("SOFTWARE_POWER"), ENABLED(PSU_CONTROL));
|
||||
cap_line(F("SOFTWARE_POWER"), ENABLED(PSU_CONTROL));
|
||||
|
||||
// TOGGLE_LIGHTS (M355)
|
||||
cap_line(PSTR("TOGGLE_LIGHTS"), ENABLED(CASE_LIGHT_ENABLE));
|
||||
cap_line(PSTR("CASE_LIGHT_BRIGHTNESS"), TERN0(CASE_LIGHT_ENABLE, caselight.has_brightness()));
|
||||
cap_line(F("TOGGLE_LIGHTS"), ENABLED(CASE_LIGHT_ENABLE));
|
||||
cap_line(F("CASE_LIGHT_BRIGHTNESS"), TERN0(CASE_LIGHT_ENABLE, caselight.has_brightness()));
|
||||
|
||||
// EMERGENCY_PARSER (M108, M112, M410, M876)
|
||||
cap_line(PSTR("EMERGENCY_PARSER"), ENABLED(EMERGENCY_PARSER));
|
||||
cap_line(F("EMERGENCY_PARSER"), ENABLED(EMERGENCY_PARSER));
|
||||
|
||||
// HOST ACTION COMMANDS (paused, resume, resumed, cancel, etc.)
|
||||
cap_line(PSTR("HOST_ACTION_COMMANDS"), ENABLED(HOST_ACTION_COMMANDS));
|
||||
cap_line(F("HOST_ACTION_COMMANDS"), ENABLED(HOST_ACTION_COMMANDS));
|
||||
|
||||
// PROMPT SUPPORT (M876)
|
||||
cap_line(PSTR("PROMPT_SUPPORT"), ENABLED(HOST_PROMPT_SUPPORT));
|
||||
cap_line(F("PROMPT_SUPPORT"), ENABLED(HOST_PROMPT_SUPPORT));
|
||||
|
||||
// SDCARD (M20, M23, M24, etc.)
|
||||
cap_line(PSTR("SDCARD"), ENABLED(SDSUPPORT));
|
||||
cap_line(F("SDCARD"), ENABLED(SDSUPPORT));
|
||||
|
||||
// MULTI_VOLUME (M21 S/M21 U)
|
||||
#if ENABLED(SDSUPPORT)
|
||||
cap_line(F("MULTI_VOLUME"), ENABLED(MULTI_VOLUME));
|
||||
#endif
|
||||
|
||||
// REPEAT (M808)
|
||||
cap_line(PSTR("REPEAT"), ENABLED(GCODE_REPEAT_MARKERS));
|
||||
cap_line(F("REPEAT"), ENABLED(GCODE_REPEAT_MARKERS));
|
||||
|
||||
// SD_WRITE (M928, M28, M29)
|
||||
cap_line(PSTR("SD_WRITE"), ENABLED(SDSUPPORT) && DISABLED(SDCARD_READONLY));
|
||||
cap_line(F("SD_WRITE"), ENABLED(SDSUPPORT) && DISABLED(SDCARD_READONLY));
|
||||
|
||||
// AUTOREPORT_SD_STATUS (M27 extension)
|
||||
cap_line(PSTR("AUTOREPORT_SD_STATUS"), ENABLED(AUTO_REPORT_SD_STATUS));
|
||||
cap_line(F("AUTOREPORT_SD_STATUS"), ENABLED(AUTO_REPORT_SD_STATUS));
|
||||
|
||||
// LONG_FILENAME_HOST_SUPPORT (M33)
|
||||
cap_line(PSTR("LONG_FILENAME"), ENABLED(LONG_FILENAME_HOST_SUPPORT));
|
||||
cap_line(F("LONG_FILENAME"), ENABLED(LONG_FILENAME_HOST_SUPPORT));
|
||||
|
||||
// LONG_FILENAME_WRITE_SUPPORT (M23, M28, M30...)
|
||||
cap_line(F("LFN_WRITE"), ENABLED(LONG_FILENAME_WRITE_SUPPORT));
|
||||
|
||||
// CUSTOM_FIRMWARE_UPLOAD (M20 F)
|
||||
cap_line(F("CUSTOM_FIRMWARE_UPLOAD"), ENABLED(CUSTOM_FIRMWARE_UPLOAD));
|
||||
|
||||
// EXTENDED_M20 (M20 L)
|
||||
cap_line(F("EXTENDED_M20"), ENABLED(LONG_FILENAME_HOST_SUPPORT));
|
||||
|
||||
// THERMAL_PROTECTION
|
||||
cap_line(PSTR("THERMAL_PROTECTION"), ENABLED(THERMALLY_SAFE));
|
||||
cap_line(F("THERMAL_PROTECTION"), ENABLED(THERMALLY_SAFE));
|
||||
|
||||
// MOTION_MODES (M80-M89)
|
||||
cap_line(PSTR("MOTION_MODES"), ENABLED(GCODE_MOTION_MODES));
|
||||
cap_line(F("MOTION_MODES"), ENABLED(GCODE_MOTION_MODES));
|
||||
|
||||
// ARC_SUPPORT (G2-G3)
|
||||
cap_line(PSTR("ARCS"), ENABLED(ARC_SUPPORT));
|
||||
cap_line(F("ARCS"), ENABLED(ARC_SUPPORT));
|
||||
|
||||
// BABYSTEPPING (M290)
|
||||
cap_line(PSTR("BABYSTEPPING"), ENABLED(BABYSTEPPING));
|
||||
cap_line(F("BABYSTEPPING"), ENABLED(BABYSTEPPING));
|
||||
|
||||
// CHAMBER_TEMPERATURE (M141, M191)
|
||||
cap_line(PSTR("CHAMBER_TEMPERATURE"), ENABLED(HAS_HEATED_CHAMBER));
|
||||
cap_line(F("CHAMBER_TEMPERATURE"), ENABLED(HAS_HEATED_CHAMBER));
|
||||
|
||||
// COOLER_TEMPERATURE (M143, M193)
|
||||
cap_line(PSTR("COOLER_TEMPERATURE"), ENABLED(HAS_COOLER));
|
||||
cap_line(F("COOLER_TEMPERATURE"), ENABLED(HAS_COOLER));
|
||||
|
||||
// MEATPACK Compression
|
||||
cap_line(PSTR("MEATPACK"), SERIAL_IMPL.has_feature(port, SerialFeature::MeatPack));
|
||||
cap_line(F("MEATPACK"), SERIAL_IMPL.has_feature(port, SerialFeature::MeatPack));
|
||||
|
||||
// CONFIG_EXPORT
|
||||
cap_line(F("CONFIG_EXPORT"), ENABLED(CONFIGURATION_EMBEDDING));
|
||||
|
||||
// Machine Geometry
|
||||
#if ENABLED(M115_GEOMETRY_REPORT)
|
||||
|
@@ -26,6 +26,7 @@
|
||||
|
||||
#include "../gcode.h"
|
||||
#include "../../MarlinCore.h"
|
||||
#include "../../lcd/marlinui.h"
|
||||
|
||||
/**
|
||||
* M16: Expected Printer Check
|
||||
@@ -33,8 +34,8 @@
|
||||
void GcodeSuite::M16() {
|
||||
|
||||
if (strcmp_P(parser.string_arg, PSTR(MACHINE_NAME)))
|
||||
kill(GET_TEXT(MSG_KILL_EXPECTED_PRINTER));
|
||||
kill(GET_TEXT_F(MSG_KILL_EXPECTED_PRINTER));
|
||||
|
||||
}
|
||||
|
||||
#endif
|
||||
#endif // EXPECTED_PRINTER_CHECK
|
||||
|
@@ -43,9 +43,15 @@ static void config_line(PGM_P const name, const float val, PGM_P const pref=null
|
||||
config_prefix(name, pref, ind);
|
||||
SERIAL_ECHOLN(val);
|
||||
}
|
||||
static void config_line(FSTR_P const name, const float val, FSTR_P const pref=nullptr, const int8_t ind=-1) {
|
||||
config_line(FTOP(name), val, FTOP(pref) , ind);
|
||||
}
|
||||
static void config_line_e(const int8_t e, PGM_P const name, const float val) {
|
||||
config_line(name, val, PSTR("Extr."), e + 1);
|
||||
}
|
||||
static void config_line_e(const int8_t e, FSTR_P const name, const float val) {
|
||||
config_line_e(e, FTOP(name), val);
|
||||
}
|
||||
|
||||
/**
|
||||
* M360: Report Firmware configuration
|
||||
@@ -60,19 +66,19 @@ void GcodeSuite::M360() {
|
||||
//
|
||||
// Basics and Enabled items
|
||||
//
|
||||
config_line(PSTR("Baudrate"), BAUDRATE);
|
||||
config_line(PSTR("InputBuffer"), MAX_CMD_SIZE);
|
||||
config_line(PSTR("PrintlineCache"), BUFSIZE);
|
||||
config_line(PSTR("MixingExtruder"), ENABLED(MIXING_EXTRUDER));
|
||||
config_line(PSTR("SDCard"), ENABLED(SDSUPPORT));
|
||||
config_line(PSTR("Fan"), ENABLED(HAS_FAN));
|
||||
config_line(PSTR("LCD"), ENABLED(HAS_DISPLAY));
|
||||
config_line(PSTR("SoftwarePowerSwitch"), 1);
|
||||
config_line(PSTR("SupportLocalFilamentchange"), ENABLED(ADVANCED_PAUSE_FEATURE));
|
||||
config_line(PSTR("CaseLights"), ENABLED(CASE_LIGHT_ENABLE));
|
||||
config_line(PSTR("ZProbe"), ENABLED(HAS_BED_PROBE));
|
||||
config_line(PSTR("Autolevel"), ENABLED(HAS_LEVELING));
|
||||
config_line(PSTR("EEPROM"), ENABLED(EEPROM_SETTINGS));
|
||||
config_line(F("Baudrate"), BAUDRATE);
|
||||
config_line(F("InputBuffer"), MAX_CMD_SIZE);
|
||||
config_line(F("PrintlineCache"), BUFSIZE);
|
||||
config_line(F("MixingExtruder"), ENABLED(MIXING_EXTRUDER));
|
||||
config_line(F("SDCard"), ENABLED(SDSUPPORT));
|
||||
config_line(F("Fan"), ENABLED(HAS_FAN));
|
||||
config_line(F("LCD"), ENABLED(HAS_DISPLAY));
|
||||
config_line(F("SoftwarePowerSwitch"), 1);
|
||||
config_line(F("SupportLocalFilamentchange"), ENABLED(ADVANCED_PAUSE_FEATURE));
|
||||
config_line(F("CaseLights"), ENABLED(CASE_LIGHT_ENABLE));
|
||||
config_line(F("ZProbe"), ENABLED(HAS_BED_PROBE));
|
||||
config_line(F("Autolevel"), ENABLED(HAS_LEVELING));
|
||||
config_line(F("EEPROM"), ENABLED(EEPROM_SETTINGS));
|
||||
|
||||
//
|
||||
// Homing Directions
|
||||
@@ -87,7 +93,7 @@ void GcodeSuite::M360() {
|
||||
//
|
||||
#if HAS_CLASSIC_JERK
|
||||
if (planner.max_jerk.x == planner.max_jerk.y)
|
||||
config_line(PSTR("XY"), planner.max_jerk.x, JERK_STR);
|
||||
config_line(F("XY"), planner.max_jerk.x, FPSTR(JERK_STR));
|
||||
else {
|
||||
config_line(X_STR, planner.max_jerk.x, JERK_STR);
|
||||
config_line(Y_STR, planner.max_jerk.y, JERK_STR);
|
||||
@@ -98,21 +104,21 @@ void GcodeSuite::M360() {
|
||||
//
|
||||
// Firmware Retraction
|
||||
//
|
||||
config_line(PSTR("SupportG10G11"), ENABLED(FWRETRACT));
|
||||
config_line(F("SupportG10G11"), ENABLED(FWRETRACT));
|
||||
#if ENABLED(FWRETRACT)
|
||||
PGMSTR(RET_STR, "Retraction");
|
||||
PGMSTR(UNRET_STR, "RetractionUndo");
|
||||
PGMSTR(SPEED_STR, "Speed");
|
||||
// M10 Retract with swap (long) moves
|
||||
config_line(PSTR("Length"), fwretract.settings.retract_length, RET_STR);
|
||||
config_line(SPEED_STR, fwretract.settings.retract_feedrate_mm_s, RET_STR);
|
||||
config_line(PSTR("ZLift"), fwretract.settings.retract_zraise, RET_STR);
|
||||
config_line(PSTR("LongLength"), fwretract.settings.swap_retract_length, RET_STR);
|
||||
config_line(F("Length"), fwretract.settings.retract_length, FPSTR(RET_STR));
|
||||
config_line(SPEED_STR, fwretract.settings.retract_feedrate_mm_s, RET_STR);
|
||||
config_line(F("ZLift"), fwretract.settings.retract_zraise, FPSTR(RET_STR));
|
||||
config_line(F("LongLength"), fwretract.settings.swap_retract_length, FPSTR(RET_STR));
|
||||
// M11 Recover (undo) with swap (long) moves
|
||||
config_line(SPEED_STR, fwretract.settings.retract_recover_feedrate_mm_s, UNRET_STR);
|
||||
config_line(PSTR("ExtraLength"), fwretract.settings.retract_recover_extra, UNRET_STR);
|
||||
config_line(PSTR("ExtraLongLength"), fwretract.settings.swap_retract_recover_extra, UNRET_STR);
|
||||
config_line(PSTR("LongSpeed"), fwretract.settings.swap_retract_recover_feedrate_mm_s, UNRET_STR);
|
||||
config_line(SPEED_STR, fwretract.settings.retract_recover_feedrate_mm_s, UNRET_STR);
|
||||
config_line(F("ExtraLength"), fwretract.settings.retract_recover_extra, FPSTR(UNRET_STR));
|
||||
config_line(F("ExtraLongLength"), fwretract.settings.swap_retract_recover_extra, FPSTR(UNRET_STR));
|
||||
config_line(F("LongSpeed"), fwretract.settings.swap_retract_recover_feedrate_mm_s, FPSTR(UNRET_STR));
|
||||
#endif
|
||||
|
||||
//
|
||||
@@ -156,29 +162,30 @@ void GcodeSuite::M360() {
|
||||
TERN_(DELTA, "Delta")
|
||||
TERN_(IS_SCARA, "SCARA")
|
||||
TERN_(IS_CORE, "Core")
|
||||
TERN_(MARKFORGED_XY, "MarkForged")
|
||||
TERN_(MARKFORGED_XY, "MarkForgedXY")
|
||||
TERN_(MARKFORGED_YX, "MarkForgedYX")
|
||||
TERN_(IS_CARTESIAN, "Cartesian")
|
||||
);
|
||||
|
||||
//
|
||||
// Heated Bed
|
||||
//
|
||||
config_line(PSTR("HeatedBed"), ENABLED(HAS_HEATED_BED));
|
||||
config_line(F("HeatedBed"), ENABLED(HAS_HEATED_BED));
|
||||
#if HAS_HEATED_BED
|
||||
config_line(PSTR("MaxBedTemp"), BED_MAX_TARGET);
|
||||
config_line(F("MaxBedTemp"), BED_MAX_TARGET);
|
||||
#endif
|
||||
|
||||
//
|
||||
// Per-Extruder settings
|
||||
//
|
||||
config_line(PSTR("NumExtruder"), EXTRUDERS);
|
||||
config_line(F("NumExtruder"), EXTRUDERS);
|
||||
#if HAS_EXTRUDERS
|
||||
LOOP_L_N(e, EXTRUDERS) {
|
||||
EXTRUDER_LOOP() {
|
||||
config_line_e(e, JERK_STR, TERN(HAS_LINEAR_E_JERK, planner.max_e_jerk[E_INDEX_N(e)], TERN(HAS_CLASSIC_JERK, planner.max_jerk.e, DEFAULT_EJERK)));
|
||||
config_line_e(e, PSTR("MaxSpeed"), planner.settings.max_feedrate_mm_s[E_AXIS_N(e)]);
|
||||
config_line_e(e, PSTR("Acceleration"), planner.settings.max_acceleration_mm_per_s2[E_AXIS_N(e)]);
|
||||
config_line_e(e, PSTR("Diameter"), TERN(NO_VOLUMETRICS, DEFAULT_NOMINAL_FILAMENT_DIA, planner.filament_size[e]));
|
||||
config_line_e(e, PSTR("MaxTemp"), thermalManager.hotend_maxtemp[e]);
|
||||
config_line_e(e, F("MaxSpeed"), planner.settings.max_feedrate_mm_s[E_AXIS_N(e)]);
|
||||
config_line_e(e, F("Acceleration"), planner.settings.max_acceleration_mm_per_s2[E_AXIS_N(e)]);
|
||||
config_line_e(e, F("Diameter"), TERN(NO_VOLUMETRICS, DEFAULT_NOMINAL_FILAMENT_DIA, planner.filament_size[e]));
|
||||
config_line_e(e, F("MaxTemp"), thermalManager.hotend_maxtemp[e]);
|
||||
}
|
||||
#endif
|
||||
}
|
||||
|
@@ -22,7 +22,7 @@
|
||||
|
||||
#include "../../inc/MarlinConfig.h"
|
||||
|
||||
#if ENABLED(HOST_PROMPT_SUPPORT) && DISABLED(EMERGENCY_PARSER)
|
||||
#if HAS_GCODE_M876
|
||||
|
||||
#include "../../feature/host_actions.h"
|
||||
#include "../gcode.h"
|
||||
@@ -33,8 +33,8 @@
|
||||
*/
|
||||
void GcodeSuite::M876() {
|
||||
|
||||
if (parser.seenval('S')) host_response_handler((uint8_t)parser.value_int());
|
||||
if (parser.seenval('S')) hostui.handle_response((uint8_t)parser.value_int());
|
||||
|
||||
}
|
||||
|
||||
#endif // HOST_PROMPT_SUPPORT && !EMERGENCY_PARSER
|
||||
#endif // HAS_GCODE_M876
|
||||
|
@@ -31,12 +31,13 @@
|
||||
#include "../../module/planner.h" // for synchronize()
|
||||
#include "../../MarlinCore.h" // for wait_for_user_response()
|
||||
|
||||
#if HAS_LCD_MENU
|
||||
#if HAS_MARLINUI_MENU
|
||||
#include "../../lcd/marlinui.h"
|
||||
#elif ENABLED(EXTENSIBLE_UI)
|
||||
#include "../../lcd/extui/ui_api.h"
|
||||
#elif ENABLED(DWIN_CREALITY_LCD_ENHANCED)
|
||||
#include "../../lcd/e3v2/enhanced/dwin.h"
|
||||
#elif ENABLED(DWIN_LCD_PROUI)
|
||||
#include "../../lcd/e3v2/proui/dwin_popup.h"
|
||||
#include "../../lcd/e3v2/proui/dwin.h"
|
||||
#endif
|
||||
|
||||
#if ENABLED(HOST_PROMPT_SUPPORT)
|
||||
@@ -54,12 +55,12 @@ void GcodeSuite::M0_M1() {
|
||||
|
||||
planner.synchronize();
|
||||
|
||||
#if HAS_LCD_MENU
|
||||
#if HAS_MARLINUI_MENU
|
||||
|
||||
if (parser.string_arg)
|
||||
ui.set_status(parser.string_arg, true);
|
||||
else {
|
||||
LCD_MESSAGEPGM(MSG_USERWAIT);
|
||||
LCD_MESSAGE(MSG_USERWAIT);
|
||||
#if ENABLED(LCD_PROGRESS_BAR) && PROGRESS_MSG_EXPIRE > 0
|
||||
ui.reset_progress_bar_timeout();
|
||||
#endif
|
||||
@@ -67,11 +68,14 @@ void GcodeSuite::M0_M1() {
|
||||
|
||||
#elif ENABLED(EXTENSIBLE_UI)
|
||||
if (parser.string_arg)
|
||||
ExtUI::onUserConfirmRequired(parser.string_arg); // Can this take an SRAM string??
|
||||
ExtUI::onUserConfirmRequired(parser.string_arg); // String in an SRAM buffer
|
||||
else
|
||||
ExtUI::onUserConfirmRequired_P(GET_TEXT(MSG_USERWAIT));
|
||||
#elif ENABLED(DWIN_CREALITY_LCD_ENHANCED)
|
||||
DWIN_Popup_Confirm(ICON_BLTouch, parser.string_arg ?: GET_TEXT(MSG_STOPPED), GET_TEXT(MSG_USERWAIT));
|
||||
ExtUI::onUserConfirmRequired(GET_TEXT_F(MSG_USERWAIT));
|
||||
#elif ENABLED(DWIN_LCD_PROUI)
|
||||
if (parser.string_arg)
|
||||
DWIN_Popup_Confirm(ICON_BLTouch, parser.string_arg, GET_TEXT_F(MSG_USERWAIT));
|
||||
else
|
||||
DWIN_Popup_Confirm(ICON_BLTouch, GET_TEXT_F(MSG_STOPPED), GET_TEXT_F(MSG_USERWAIT));
|
||||
#else
|
||||
|
||||
if (parser.string_arg) {
|
||||
@@ -81,11 +85,11 @@ void GcodeSuite::M0_M1() {
|
||||
|
||||
#endif
|
||||
|
||||
TERN_(HOST_PROMPT_SUPPORT, host_prompt_do(PROMPT_USER_CONTINUE, parser.codenum ? PSTR("M1 Stop") : PSTR("M0 Stop"), CONTINUE_STR));
|
||||
TERN_(HOST_PROMPT_SUPPORT, hostui.prompt_do(PROMPT_USER_CONTINUE, parser.codenum ? F("M1 Stop") : F("M0 Stop"), FPSTR(CONTINUE_STR)));
|
||||
|
||||
TERN_(HAS_RESUME_CONTINUE, wait_for_user_response(ms));
|
||||
|
||||
TERN_(HAS_LCD_MENU, ui.reset_status());
|
||||
TERN_(HAS_MARLINUI_MENU, ui.reset_status());
|
||||
}
|
||||
|
||||
#endif // HAS_RESUME_CONTINUE
|
||||
|
@@ -33,7 +33,7 @@
|
||||
void GcodeSuite::M117() {
|
||||
|
||||
if (parser.string_arg && parser.string_arg[0])
|
||||
ui.set_status(parser.string_arg);
|
||||
ui.set_status(parser.string_arg, true);
|
||||
else
|
||||
ui.reset_status();
|
||||
|
||||
|
@@ -22,7 +22,7 @@
|
||||
|
||||
#include "../../inc/MarlinConfig.h"
|
||||
|
||||
#if PREHEAT_COUNT
|
||||
#if HAS_PREHEAT
|
||||
|
||||
#include "../gcode.h"
|
||||
#include "../../lcd/marlinui.h"
|
||||
@@ -61,7 +61,7 @@ void GcodeSuite::M145() {
|
||||
}
|
||||
|
||||
void GcodeSuite::M145_report(const bool forReplay/*=true*/) {
|
||||
report_heading(forReplay, PSTR(STR_MATERIAL_HEATUP));
|
||||
report_heading(forReplay, F(STR_MATERIAL_HEATUP));
|
||||
LOOP_L_N(i, PREHEAT_COUNT) {
|
||||
report_echo_start(forReplay);
|
||||
SERIAL_ECHOLNPGM_P(
|
||||
@@ -79,4 +79,4 @@ void GcodeSuite::M145_report(const bool forReplay/*=true*/) {
|
||||
}
|
||||
}
|
||||
|
||||
#endif // PREHEAT_COUNT
|
||||
#endif // HAS_PREHEAT
|
||||
|
@@ -31,14 +31,14 @@
|
||||
* M250: Read and optionally set the LCD contrast
|
||||
*/
|
||||
void GcodeSuite::M250() {
|
||||
if (parser.seenval('C'))
|
||||
if (LCD_CONTRAST_MIN < LCD_CONTRAST_MAX && parser.seenval('C'))
|
||||
ui.set_contrast(parser.value_byte());
|
||||
else
|
||||
M250_report();
|
||||
}
|
||||
|
||||
void GcodeSuite::M250_report(const bool forReplay/*=true*/) {
|
||||
report_heading_etc(forReplay, PSTR(STR_LCD_CONTRAST));
|
||||
report_heading_etc(forReplay, F(STR_LCD_CONTRAST));
|
||||
SERIAL_ECHOLNPGM(" M250 C", ui.contrast);
|
||||
}
|
||||
|
||||
|
58
Marlin/src/gcode/lcd/M255.cpp
Normal file
58
Marlin/src/gcode/lcd/M255.cpp
Normal file
@@ -0,0 +1,58 @@
|
||||
/**
|
||||
* Marlin 3D Printer Firmware
|
||||
* Copyright (c) 2022 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 <https://www.gnu.org/licenses/>.
|
||||
*
|
||||
*/
|
||||
#include "../../inc/MarlinConfig.h"
|
||||
|
||||
#if HAS_GCODE_M255
|
||||
|
||||
#include "../gcode.h"
|
||||
#include "../../lcd/marlinui.h"
|
||||
|
||||
/**
|
||||
* M255: Set the LCD sleep timeout (in minutes)
|
||||
* S<minutes> - Period of inactivity required for display / backlight sleep
|
||||
*/
|
||||
void GcodeSuite::M255() {
|
||||
if (parser.seenval('S')) {
|
||||
#if HAS_DISPLAY_SLEEP
|
||||
const int m = parser.value_int();
|
||||
ui.sleep_timeout_minutes = constrain(m, SLEEP_TIMEOUT_MIN, SLEEP_TIMEOUT_MAX);
|
||||
#else
|
||||
const unsigned int s = parser.value_ushort() * 60;
|
||||
ui.lcd_backlight_timeout = constrain(s, LCD_BKL_TIMEOUT_MIN, LCD_BKL_TIMEOUT_MAX);
|
||||
#endif
|
||||
}
|
||||
else
|
||||
M255_report();
|
||||
}
|
||||
|
||||
void GcodeSuite::M255_report(const bool forReplay/*=true*/) {
|
||||
report_heading_etc(forReplay, F(STR_DISPLAY_SLEEP));
|
||||
SERIAL_ECHOLNPGM(" M255 S",
|
||||
#if HAS_DISPLAY_SLEEP
|
||||
ui.sleep_timeout_minutes, " ; (minutes)"
|
||||
#else
|
||||
ui.lcd_backlight_timeout, " ; (seconds)"
|
||||
#endif
|
||||
);
|
||||
}
|
||||
|
||||
#endif // HAS_GCODE_M255
|
@@ -37,7 +37,7 @@ void GcodeSuite::M256() {
|
||||
}
|
||||
|
||||
void GcodeSuite::M256_report(const bool forReplay/*=true*/) {
|
||||
report_heading_etc(forReplay, PSTR(STR_LCD_BRIGHTNESS));
|
||||
report_heading_etc(forReplay, F(STR_LCD_BRIGHTNESS));
|
||||
SERIAL_ECHOLNPGM(" M256 B", ui.brightness);
|
||||
}
|
||||
|
||||
|
Some files were not shown because too many files have changed in this diff Show More
Reference in New Issue
Block a user