mirror of
https://github.com/bdring/Grbl_Esp32.git
synced 2025-09-02 19:02:35 +02:00
The approach was a) Split up the CoolantMode enum, which had become complicated because it was trying to solve two incompatible requirements, into two enums GCodeCoolant (a pure enumeration for the use of the GCode parser) and CoolantState (a bitfield for runtime use where independent turn-off is possible via overrides) b) Fixed coolant_set_state() so it can turn off coolant bits independently. Previously it could turn them on independently, but only turn them off simultaneously. That was fine for M7 M8 M9, but inadequate for realtime coolant overrides. c) In the process, I refactored the code in CoolantControl.cpp with the goal of "saying things once", thus reducing the number of ifdefs. When we have the Pin class, the ifdefs will be reduced even more, perhaps even eliminated. Meanwhile, this cleans up the code and probably makes the transition to Pins easier. d) I also fixed a bug in Report.cpp in which it was not possible to report both M7 and M8 at the same time.
This commit is contained in:
@@ -34,87 +34,84 @@ void coolant_init() {
|
||||
}
|
||||
|
||||
// Returns current coolant output state. Overrides may alter it from programmed state.
|
||||
CoolantMode coolant_get_state() {
|
||||
CoolantMode cl_state = {};
|
||||
CoolantState coolant_get_state() {
|
||||
CoolantState cl_state = {};
|
||||
bool pinState;
|
||||
|
||||
#ifdef COOLANT_FLOOD_PIN
|
||||
pinState = digitalRead(COOLANT_FLOOD_PIN);
|
||||
# ifdef INVERT_COOLANT_FLOOD_PIN
|
||||
if (!digitalRead(COOLANT_FLOOD_PIN)) {
|
||||
# else
|
||||
if (digitalRead(COOLANT_FLOOD_PIN)) {
|
||||
pinState = !pinState;
|
||||
# endif
|
||||
if (pinState) {
|
||||
cl_state.Flood = 1;
|
||||
}
|
||||
#endif
|
||||
|
||||
#ifdef COOLANT_MIST_PIN
|
||||
pinState = digitalRead(COOLANT_MIST_PIN);
|
||||
# ifdef INVERT_COOLANT_MIST_PIN
|
||||
if (!digitalRead(COOLANT_MIST_PIN)) {
|
||||
# else
|
||||
if (digitalRead(COOLANT_MIST_PIN)) {
|
||||
pinState = !pinState;
|
||||
# endif
|
||||
if (pinState) {
|
||||
cl_state.Mist = 1;
|
||||
}
|
||||
#endif
|
||||
|
||||
return cl_state;
|
||||
}
|
||||
|
||||
static inline void coolant_write(CoolantState state) {
|
||||
bool pinState;
|
||||
|
||||
#ifdef COOLANT_FLOOD_PIN
|
||||
pinState = state.Flood;
|
||||
# ifdef INVERT_COOLANT_FLOOD_PIN
|
||||
pinState = !pinState;
|
||||
# endif
|
||||
digitalWrite(COOLANT_FLOOD_PIN, pinState);
|
||||
#endif
|
||||
|
||||
#ifdef COOLANT_MIST_PIN
|
||||
pinState = state.Mist;
|
||||
# ifdef INVERT_COOLANT_MIST_PIN
|
||||
pinState = !pinState;
|
||||
# endif
|
||||
digitalWrite(COOLANT_MIST_PIN, pinState);
|
||||
#endif
|
||||
}
|
||||
|
||||
// Directly called by coolant_init(), coolant_set_state(), and mc_reset(), which can be at
|
||||
// an interrupt-level. No report flag set, but only called by routines that don't need it.
|
||||
void coolant_stop() {
|
||||
#ifdef COOLANT_FLOOD_PIN
|
||||
# ifdef INVERT_COOLANT_FLOOD_PIN
|
||||
digitalWrite(COOLANT_FLOOD_PIN, 1);
|
||||
# else
|
||||
digitalWrite(COOLANT_FLOOD_PIN, 0);
|
||||
# endif
|
||||
#endif
|
||||
#ifdef COOLANT_MIST_PIN
|
||||
# ifdef INVERT_COOLANT_MIST_PIN
|
||||
digitalWrite(COOLANT_MIST_PIN, 1);
|
||||
# else
|
||||
digitalWrite(COOLANT_MIST_PIN, 0);
|
||||
# endif
|
||||
#endif
|
||||
CoolantState disable = {};
|
||||
coolant_write(disable);
|
||||
}
|
||||
|
||||
// Main program only. Immediately sets flood coolant running state and also mist coolant,
|
||||
// if enabled. Also sets a flag to report an update to a coolant state.
|
||||
// Called by coolant toggle override, parking restore, parking retract, sleep mode, g-code
|
||||
// parser program end, and g-code parser coolant_sync().
|
||||
void coolant_set_state(CoolantMode mode) {
|
||||
|
||||
void coolant_set_state(CoolantState state) {
|
||||
if (sys.abort) {
|
||||
return; // Block during abort.
|
||||
}
|
||||
if (mode.IsDisabled()) {
|
||||
coolant_stop();
|
||||
} else {
|
||||
#ifdef COOLANT_FLOOD_PIN
|
||||
if (mode.Flood) {
|
||||
# ifdef INVERT_COOLANT_FLOOD_PIN
|
||||
digitalWrite(COOLANT_FLOOD_PIN, 0);
|
||||
# else
|
||||
digitalWrite(COOLANT_FLOOD_PIN, 1);
|
||||
# endif
|
||||
}
|
||||
#endif
|
||||
#ifdef COOLANT_MIST_PIN
|
||||
if (mode.Mist) {
|
||||
# ifdef INVERT_COOLANT_MIST_PIN
|
||||
digitalWrite(COOLANT_MIST_PIN, 0);
|
||||
# else
|
||||
digitalWrite(COOLANT_MIST_PIN, 1);
|
||||
# endif
|
||||
}
|
||||
#endif
|
||||
}
|
||||
coolant_write(state);
|
||||
sys.report_ovr_counter = 0; // Set to report change immediately
|
||||
}
|
||||
|
||||
void coolant_off() {
|
||||
CoolantState disable = {};
|
||||
coolant_set_state(disable);
|
||||
}
|
||||
|
||||
// G-code parser entry-point for setting coolant state. Forces a planner buffer sync and bails
|
||||
// if an abort or check-mode is active.
|
||||
void coolant_sync(CoolantMode mode) {
|
||||
void coolant_sync(CoolantState state) {
|
||||
if (sys.state == STATE_CHECK_MODE) {
|
||||
return;
|
||||
}
|
||||
protocol_buffer_synchronize(); // Ensure coolant turns on when specified in program.
|
||||
coolant_set_state(mode);
|
||||
coolant_set_state(state);
|
||||
}
|
||||
|
@@ -27,13 +27,14 @@
|
||||
void coolant_init();
|
||||
|
||||
// Returns current coolant output state. Overrides may alter it from programmed state.
|
||||
CoolantMode coolant_get_state();
|
||||
CoolantState coolant_get_state();
|
||||
|
||||
// Immediately disables coolant pins.
|
||||
void coolant_stop();
|
||||
|
||||
// Sets the coolant pins according to state specified.
|
||||
void coolant_set_state(CoolantMode mode);
|
||||
void coolant_off();
|
||||
void coolant_set_state(CoolantState state);
|
||||
|
||||
// G-code parser entry-point for setting coolant states. Checks for and executes additional conditions.
|
||||
void coolant_sync(CoolantMode mode);
|
||||
void coolant_sync(CoolantState state);
|
||||
|
@@ -454,17 +454,17 @@ uint8_t gc_execute_line(char* line, uint8_t client) {
|
||||
switch (int_value) {
|
||||
#ifdef COOLANT_MIST_PIN
|
||||
case 7:
|
||||
gc_block.modal.coolant = {};
|
||||
gc_block.modal.coolant.Mist = 1;
|
||||
gc_block.coolant = GCodeCoolant::M7;
|
||||
break;
|
||||
#endif
|
||||
#ifdef COOLANT_FLOOD_PIN
|
||||
case 8:
|
||||
gc_block.modal.coolant = {};
|
||||
gc_block.modal.coolant.Flood = 1;
|
||||
gc_block.coolant = GCodeCoolant::M8;
|
||||
break;
|
||||
#endif
|
||||
case 9: gc_block.modal.coolant = {}; break;
|
||||
case 9:
|
||||
gc_block.coolant = GCodeCoolant::M9;
|
||||
break;
|
||||
}
|
||||
mg_word_bit = ModalGroup::MM8;
|
||||
break;
|
||||
@@ -1270,15 +1270,25 @@ uint8_t gc_execute_line(char* line, uint8_t client) {
|
||||
}
|
||||
pl_data->spindle = gc_state.modal.spindle;
|
||||
// [8. Coolant control ]:
|
||||
if (gc_state.modal.coolant != gc_block.modal.coolant) {
|
||||
// NOTE: Coolant M-codes are modal. Only one command per line is allowed. But, multiple states
|
||||
// can exist at the same time, while coolant disable clears all states.
|
||||
coolant_sync(gc_block.modal.coolant);
|
||||
if (gc_block.modal.coolant.IsDisabled()) {
|
||||
// At most one of M7, M8, M9 can appear in a GCode block, but the overall coolant
|
||||
// state can have both mist (M7) and flood (M8) on at once, by issuing M7 and M8
|
||||
// in separate blocks. There is no GCode way to turn them off separately, but
|
||||
// you can turn them off simultaneously with M9. You can turn them off separately
|
||||
// with real-time overrides, but that is out of the scope of GCode.
|
||||
switch (gc_block.coolant) {
|
||||
case GCodeCoolant::None: break;
|
||||
case GCodeCoolant::M7:
|
||||
gc_state.modal.coolant.Mist = 1;
|
||||
coolant_sync(gc_state.modal.coolant);
|
||||
break;
|
||||
case GCodeCoolant::M8:
|
||||
gc_state.modal.coolant.Flood = 1;
|
||||
coolant_sync(gc_state.modal.coolant);
|
||||
break;
|
||||
case GCodeCoolant::M9:
|
||||
gc_state.modal.coolant = {};
|
||||
} else {
|
||||
gc_state.modal.coolant = CoolantMode(gc_state.modal.coolant, gc_block.modal.coolant);
|
||||
}
|
||||
coolant_sync(gc_state.modal.coolant);
|
||||
break;
|
||||
}
|
||||
pl_data->coolant = gc_state.modal.coolant; // Set state for planner use.
|
||||
// turn on/off an i/o pin
|
||||
@@ -1474,7 +1484,7 @@ uint8_t gc_execute_line(char* line, uint8_t client) {
|
||||
}
|
||||
system_flag_wco_change(); // Set to refresh immediately just in case something altered.
|
||||
spindle->set_state(SpindleState::Disable, 0);
|
||||
coolant_set_state(CoolantMode());
|
||||
coolant_off();
|
||||
}
|
||||
report_feedback_message(MESSAGE_PROGRAM_END);
|
||||
#ifdef USE_M30
|
||||
|
@@ -24,12 +24,12 @@
|
||||
along with Grbl. If not, see <http://www.gnu.org/licenses/>.
|
||||
*/
|
||||
|
||||
// Define modal group internal numbers for checking multiple command violations and tracking the
|
||||
// Modal group internal numbers for checking multiple command violations and tracking the
|
||||
// type of command that is called in the block. A modal group is a group of g-code commands that are
|
||||
// mutually exclusive, or cannot exist on the same line, because they each toggle a state or execute
|
||||
// a unique motion. These are defined in the NIST RS274-NGC v3 g-code standard, available online,
|
||||
// and are similar/identical to other g-code interpreters by manufacturers (Haas,Fanuc,Mazak,etc).
|
||||
// NOTE: Modal group define values must be sequential and starting from zero.
|
||||
// NOTE: Modal group values must be sequential and starting from zero.
|
||||
|
||||
enum class ModalGroup : uint8_t {
|
||||
MG0 = 0, // [G4,G10,G28,G28.1,G30,G30.1,G53,G92,G92.1] Non-modal
|
||||
@@ -51,7 +51,7 @@ enum class ModalGroup : uint8_t {
|
||||
MM10 = 15, // [M62, M63] User Defined http://linuxcnc.org/docs/html/gcode/overview.html#_modal_groups
|
||||
};
|
||||
|
||||
// Define command actions for within execution-type modal groups (motion, stopping, non-modal). Used
|
||||
// Command actions for within execution-type modal groups (motion, stopping, non-modal). Used
|
||||
// internally by the parser to know which command to execute.
|
||||
// NOTE: Some macro values are assigned specific values to make g-code state reporting and parsing
|
||||
// compile a litte smaller. Necessary due to being completely out of flash on the 328p. Although not
|
||||
@@ -144,21 +144,24 @@ enum class SpindleState : uint8_t {
|
||||
Ccw = 2, // M4
|
||||
};
|
||||
|
||||
// Modal Group M8: Coolant control
|
||||
class CoolantMode {
|
||||
public:
|
||||
inline CoolantMode() : Flood(0), Mist(0) {} // M9 (Default: Must be zero)
|
||||
inline CoolantMode(CoolantMode lhs, CoolantMode rhs) : Flood(lhs.Flood | rhs.Flood), Mist(lhs.Mist | rhs.Mist) {}
|
||||
|
||||
uint8_t Flood : 1; // M8
|
||||
uint8_t Mist : 1; // M7
|
||||
|
||||
inline bool IsDisabled() const { return Flood == 0 && Mist == 0; }
|
||||
|
||||
inline bool operator==(const CoolantMode& o) const { return Flood == o.Flood && Mist == o.Mist; }
|
||||
inline bool operator!=(const CoolantMode& o) const { return !operator==(o); }
|
||||
// GCodeCoolant is used by the parser, where at most one of
|
||||
// M7, M8, M9 may be present in a GCode block
|
||||
enum class GCodeCoolant : uint8_t {
|
||||
None = 0,
|
||||
M7,
|
||||
M8,
|
||||
M9,
|
||||
};
|
||||
|
||||
// CoolantState is used for the runtime state, where either of
|
||||
// the Mist and Flood state bits can be set independently.
|
||||
// Unlike GCode, overrides permit individual turn-off.
|
||||
struct CoolantState {
|
||||
uint8_t Mist : 1;
|
||||
uint8_t Flood : 1;
|
||||
};
|
||||
|
||||
// Modal Group M8: Coolant control
|
||||
// Modal Group M9: Override control
|
||||
enum class Override : uint8_t {
|
||||
#ifdef DEACTIVATE_PARKING_UPON_INIT
|
||||
@@ -170,7 +173,7 @@ enum class Override : uint8_t {
|
||||
#endif
|
||||
};
|
||||
|
||||
// modal Group M10: User I/O control
|
||||
// Modal Group M10: User I/O control
|
||||
enum class IoControl : uint8_t {
|
||||
Enable = 1,
|
||||
Disable = 2,
|
||||
@@ -192,7 +195,7 @@ enum class ToolChange : uint8_t {
|
||||
// Modal Group G12: Active work coordinate system
|
||||
// N/A: Stores coordinate system value (54-59) to change to.
|
||||
|
||||
// Define parameter word mapping.
|
||||
// Parameter word mapping.
|
||||
enum class GCodeWord : uint8_t {
|
||||
F = 0,
|
||||
I = 1,
|
||||
@@ -212,14 +215,14 @@ enum class GCodeWord : uint8_t {
|
||||
C = 15,
|
||||
};
|
||||
|
||||
// Define g-code parser position updating flags
|
||||
// GCode parser position updating flags
|
||||
enum class GCUpdatePos : uint8_t {
|
||||
Target = 0, // Must be zero
|
||||
System = 1,
|
||||
None = 2,
|
||||
};
|
||||
|
||||
// Define gcode parser flags for handling special cases.
|
||||
// GCode parser flags for handling special cases.
|
||||
enum GCParserFlags {
|
||||
GCParserNone = 0, // Must be zero.
|
||||
GCParserJogMotion = bit(0),
|
||||
@@ -232,7 +235,7 @@ enum GCParserFlags {
|
||||
GCParserLaserIsMotion = bit(7),
|
||||
};
|
||||
|
||||
// NOTE: When this struct is zeroed, the above defines set the defaults for the system.
|
||||
// NOTE: When this struct is zeroed, the 0 values in the above types set the system defaults.
|
||||
typedef struct {
|
||||
Motion motion; // {G0,G1,G2,G3,G38.2,G80}
|
||||
FeedRate feed_rate; // {G93,G94}
|
||||
@@ -245,7 +248,7 @@ typedef struct {
|
||||
uint8_t coord_select; // {G54,G55,G56,G57,G58,G59}
|
||||
// uint8_t control; // {G61} NOTE: Don't track. Only default supported.
|
||||
ProgramFlow program_flow; // {M0,M1,M2,M30}
|
||||
CoolantMode coolant; // {M7,M8,M9}
|
||||
CoolantState coolant; // {M7,M8,M9}
|
||||
SpindleState spindle; // {M3,M4,M5}
|
||||
ToolChange tool_change; // {M6}
|
||||
IoControl io_control; // {M62, M63}
|
||||
@@ -284,9 +287,10 @@ typedef struct {
|
||||
extern parser_state_t gc_state;
|
||||
|
||||
typedef struct {
|
||||
NonModal non_modal_command;
|
||||
gc_modal_t modal;
|
||||
gc_values_t values;
|
||||
NonModal non_modal_command;
|
||||
gc_modal_t modal;
|
||||
gc_values_t values;
|
||||
GCodeCoolant coolant;
|
||||
} parser_block_t;
|
||||
|
||||
enum class AxisCommand : uint8_t {
|
||||
|
@@ -55,7 +55,7 @@ typedef struct {
|
||||
// Block condition data to ensure correct execution depending on states and overrides.
|
||||
uint8_t motion; // Block bitflag motion conditions. Copied from pl_line_data.
|
||||
SpindleState spindle; // Spindle enable state
|
||||
CoolantMode coolant; // Coolant state
|
||||
CoolantState coolant; // Coolant state
|
||||
#ifdef USE_LINE_NUMBERS
|
||||
int32_t line_number; // Block line number for real-time reporting. Copied from pl_line_data.
|
||||
#endif
|
||||
@@ -85,7 +85,7 @@ typedef struct {
|
||||
uint32_t spindle_speed; // Desired spindle speed through line motion.
|
||||
uint8_t motion; // Bitflag variable to indicate motion conditions. See defines above.
|
||||
SpindleState spindle; // Spindle enable state
|
||||
CoolantMode coolant; // Coolant state
|
||||
CoolantState coolant; // Coolant state
|
||||
#ifdef USE_LINE_NUMBERS
|
||||
int32_t line_number; // Desired line number to report when executing.
|
||||
#endif
|
||||
|
@@ -519,7 +519,7 @@ void protocol_exec_rt_system() {
|
||||
// run state can be determined by checking the parser state.
|
||||
if (rt_exec & (EXEC_COOLANT_FLOOD_OVR_TOGGLE | EXEC_COOLANT_MIST_OVR_TOGGLE)) {
|
||||
if ((sys.state == STATE_IDLE) || (sys.state & (STATE_CYCLE | STATE_HOLD))) {
|
||||
CoolantMode coolant_state = gc_state.modal.coolant;
|
||||
CoolantState coolant_state = gc_state.modal.coolant;
|
||||
#ifdef COOLANT_FLOOD_PIN
|
||||
if (rt_exec & EXEC_COOLANT_FLOOD_OVR_TOGGLE) {
|
||||
if (coolant_state.Flood) {
|
||||
@@ -575,7 +575,7 @@ static void protocol_exec_rt_suspend() {
|
||||
# endif
|
||||
#endif
|
||||
plan_block_t* block = plan_get_current_block();
|
||||
CoolantMode restore_coolant;
|
||||
CoolantState restore_coolant;
|
||||
SpindleState restore_spindle;
|
||||
float restore_spindle_speed;
|
||||
if (block == NULL) {
|
||||
@@ -608,7 +608,7 @@ static void protocol_exec_rt_suspend() {
|
||||
sys.spindle_stop_ovr = SPINDLE_STOP_OVR_DISABLED;
|
||||
#ifndef PARKING_ENABLE
|
||||
spindle->set_state(SpindleState::Disable, 0); // De-energize
|
||||
coolant_set_state(CoolantMode()); // De-energize
|
||||
coolant_off();
|
||||
#else
|
||||
// Get current position and store restore location and spindle retract waypoint.
|
||||
system_convert_array_steps_to_mpos(parking_target, sys_position);
|
||||
@@ -633,11 +633,11 @@ static void protocol_exec_rt_suspend() {
|
||||
}
|
||||
// NOTE: Clear accessory state after retract and after an aborted restore motion.
|
||||
pl_data->spindle = SpindleState::Disable;
|
||||
pl_data->coolant = CoolantMode();
|
||||
pl_data->coolant = {};
|
||||
pl_data->motion = (PL_MOTION_SYSTEM_MOTION | PL_MOTION_NO_FEED_OVERRIDE);
|
||||
pl_data->spindle_speed = 0.0;
|
||||
spindle->set_state(SpindleState::Disable, 0); // De-energize
|
||||
coolant_set_state(CoolantMode()); // De-energize
|
||||
spindle->set_state(pl_data->spindle, 0); // De-energize
|
||||
coolant_set_state(pl_data->coolant);
|
||||
// Execute fast parking retract motion to parking target location.
|
||||
if (parking_target[PARKING_AXIS] < PARKING_TARGET) {
|
||||
parking_target[PARKING_AXIS] = PARKING_TARGET;
|
||||
@@ -648,7 +648,7 @@ static void protocol_exec_rt_suspend() {
|
||||
// Parking motion not possible. Just disable the spindle and coolant.
|
||||
// NOTE: Laser mode does not start a parking motion to ensure the laser stops immediately.
|
||||
spindle->set_state(SpindleState::Disable, 0); // De-energize
|
||||
coolant_set_state(CoolantMode()); // De-energize
|
||||
coolant_off();
|
||||
}
|
||||
#endif
|
||||
sys.suspend &= ~(SUSPEND_RESTART_RETRACT);
|
||||
@@ -658,7 +658,7 @@ static void protocol_exec_rt_suspend() {
|
||||
report_feedback_message(MESSAGE_SLEEP_MODE);
|
||||
// Spindle and coolant should already be stopped, but do it again just to be sure.
|
||||
spindle->set_state(SpindleState::Disable, 0); // De-energize
|
||||
coolant_set_state(CoolantMode()); // De-energize
|
||||
coolant_off();
|
||||
st_go_idle(); // Disable steppers
|
||||
while (!(sys.abort)) {
|
||||
protocol_exec_rt_system(); // Do nothing until reset.
|
||||
@@ -698,7 +698,7 @@ static void protocol_exec_rt_suspend() {
|
||||
}
|
||||
}
|
||||
}
|
||||
if (!gc_state.modal.coolant.IsDisabled()) {
|
||||
if (gc_state.modal.coolant.Flood || gc_state.modal.coolant.Mist) {
|
||||
// Block if safety door re-opened during prior restore actions.
|
||||
if (bit_isfalse(sys.suspend, SUSPEND_RESTART_RETRACT)) {
|
||||
// NOTE: Laser mode will honor this delay. An exhaust system is often controlled by this pin.
|
||||
|
@@ -417,19 +417,18 @@ void report_gcode_modes(uint8_t client) {
|
||||
strcat(modes_rpt, mode);
|
||||
|
||||
//report_util_gcode_modes_M(); // optional M7 and M8 should have been dealt with by here
|
||||
if (gc_state.modal.coolant.IsDisabled()) {
|
||||
mode = " M9";
|
||||
auto coolant = gc_state.modal.coolant;
|
||||
if (!coolant.Mist && !coolant.Flood) {
|
||||
strcat(modes_rpt, " M9");
|
||||
} else {
|
||||
auto coolant = gc_state.modal.coolant;
|
||||
// Note: Multiple coolant states may be active at the same time.
|
||||
if (coolant.Mist) {
|
||||
mode = " M7";
|
||||
strcat(modes_rpt, " M7");
|
||||
}
|
||||
if (coolant.Flood) {
|
||||
mode = " M8";
|
||||
strcat(modes_rpt, " M8");
|
||||
}
|
||||
}
|
||||
strcat(modes_rpt, mode);
|
||||
|
||||
#ifdef ENABLE_PARKING_OVERRIDE_CONTROL
|
||||
if (sys.override_ctrl == OVERRIDE_PARKING_MOTION) {
|
||||
@@ -736,8 +735,8 @@ void report_realtime_status(uint8_t client) {
|
||||
sprintf(temp, "|Ov:%d,%d,%d", sys.f_override, sys.r_override, sys.spindle_speed_ovr);
|
||||
strcat(status, temp);
|
||||
SpindleState sp_state = spindle->get_state();
|
||||
CoolantMode coolant_state = coolant_get_state();
|
||||
if (sp_state != SpindleState::Disable || !coolant_state.IsDisabled()) {
|
||||
CoolantState coolant_state = coolant_get_state();
|
||||
if (sp_state != SpindleState::Disable || coolant_state.Mist || coolant_state.Flood) {
|
||||
strcat(status, "|A:");
|
||||
switch (sp_state) {
|
||||
case SpindleState::Disable: break;
|
||||
|
Reference in New Issue
Block a user