🐛 Fix M_State_grbl when G29 calls G28
This commit is contained in:
parent
9b17699b9b
commit
43d4e30668
|
@ -77,7 +77,12 @@
|
|||
#endif
|
||||
#endif
|
||||
|
||||
#define G29_RETURN(b) return TERN_(G29_RETRY_AND_RECOVER, b)
|
||||
#define G29_RETURN(retry) do{ \
|
||||
if (TERN(G29_RETRY_AND_RECOVER, !retry, true)) { \
|
||||
TERN_(FULL_REPORT_TO_HOST_FEATURE, set_and_report_grblstate(M_IDLE, false)); \
|
||||
} \
|
||||
return TERN_(G29_RETRY_AND_RECOVER, retry); \
|
||||
}while(0)
|
||||
|
||||
// For manual probing values persist over multiple G29
|
||||
class G29_State {
|
||||
|
@ -218,12 +223,13 @@ 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
|
||||
|
@ -232,11 +238,14 @@ G29_TYPE GcodeSuite::G29() {
|
|||
if (DISABLED(PROBE_MANUALLY) && seenQ) G29_RETURN(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);
|
||||
}
|
||||
|
@ -248,15 +257,20 @@ G29_TYPE GcodeSuite::G29() {
|
|||
// Don't allow auto-leveling without homing first
|
||||
if (homing_needed_error()) G29_RETURN(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.
|
||||
*/
|
||||
|
@ -429,10 +443,10 @@ G29_TYPE GcodeSuite::G29() {
|
|||
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);
|
||||
}
|
||||
|
@ -483,6 +497,7 @@ G29_TYPE GcodeSuite::G29() {
|
|||
SERIAL_ECHOLNPGM("idle");
|
||||
}
|
||||
|
||||
// For 'A' or 'Q' exit with success state
|
||||
if (no_action) G29_RETURN(false);
|
||||
|
||||
if (abl.abl_probe_index == 0) {
|
||||
|
@ -893,8 +908,6 @@ G29_TYPE GcodeSuite::G29() {
|
|||
|
||||
report_current_position();
|
||||
|
||||
TERN_(FULL_REPORT_TO_HOST_FEATURE, set_and_report_grblstate(M_IDLE));
|
||||
|
||||
G29_RETURN(isnan(abl.measured_z));
|
||||
|
||||
}
|
||||
|
|
|
@ -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;
|
||||
|
||||
|
|
|
@ -213,8 +213,6 @@ void GcodeSuite::G28() {
|
|||
|
||||
TERN_(LASER_MOVE_G28_OFF, cutter.set_inline_enabled(false)); // turn off laser
|
||||
|
||||
TERN_(FULL_REPORT_TO_HOST_FEATURE, set_and_report_grblstate(M_HOMING));
|
||||
|
||||
#if ENABLED(DUAL_X_CARRIAGE)
|
||||
bool IDEX_saved_duplication_state = extruder_duplication_enabled;
|
||||
DualXMode IDEX_saved_mode = dual_x_carriage_mode;
|
||||
|
@ -236,6 +234,11 @@ void GcodeSuite::G28() {
|
|||
return;
|
||||
}
|
||||
|
||||
#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_StartHoming());
|
||||
TERN_(EXTENSIBLE_UI, ExtUI::onHomingStart());
|
||||
|
||||
|
@ -557,7 +560,7 @@ void GcodeSuite::G28() {
|
|||
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
|
||||
|
|
|
@ -265,9 +265,11 @@ void report_current_position_projected();
|
|||
void report_current_position_moving();
|
||||
|
||||
#if ENABLED(FULL_REPORT_TO_HOST_FEATURE)
|
||||
inline void set_and_report_grblstate(const M_StateEnum state) {
|
||||
M_State_grbl = state;
|
||||
report_current_grblstate_moving();
|
||||
inline void set_and_report_grblstate(const M_StateEnum state, const bool force=true) {
|
||||
if (force || M_State_grbl != state) {
|
||||
M_State_grbl = state;
|
||||
report_current_grblstate_moving();
|
||||
}
|
||||
}
|
||||
#endif
|
||||
|
||||
|
|
Loading…
Reference in a new issue