mirror of
https://github.com/MarlinFirmware/Marlin.git
synced 2025-01-22 17:52:57 +00:00
🧑💻 Use "enum class"
This commit is contained in:
parent
d0e110d666
commit
4aff10785e
11 changed files with 36 additions and 38 deletions
|
@ -263,7 +263,7 @@
|
|||
|
||||
PGMSTR(M112_KILL_STR, "M112 Shutdown");
|
||||
|
||||
MarlinState marlin_state = MF_INITIALIZING;
|
||||
MarlinState marlin_state = MarlinState::MF_INITIALIZING;
|
||||
|
||||
// For M109 and M190, this flag may be cleared (by M108) to exit the wait loop
|
||||
bool wait_for_heatup = false;
|
||||
|
@ -377,8 +377,8 @@ void startOrResumeJob() {
|
|||
}
|
||||
|
||||
inline void finishSDPrinting() {
|
||||
if (queue.enqueue_one(F("M1001"))) { // Keep trying until it gets queued
|
||||
marlin_state = MF_RUNNING; // Signal to stop trying
|
||||
if (queue.enqueue_one(F("M1001"))) { // Keep trying until it gets queued
|
||||
marlin_state = MarlinState::MF_RUNNING; // Signal to stop trying
|
||||
TERN_(PASSWORD_AFTER_SD_PRINT_END, password.lock_machine());
|
||||
TERN_(DGUS_LCD_UI_MKS, screen.sdPrintingFinished());
|
||||
}
|
||||
|
@ -773,7 +773,7 @@ void idle(const bool no_stepper_sleep/*=false*/) {
|
|||
TERN_(MAX7219_DEBUG, max7219.idle_tasks());
|
||||
|
||||
// Return if setup() isn't completed
|
||||
if (marlin_state == MF_INITIALIZING) goto IDLE_DONE;
|
||||
if (marlin_state == MarlinState::MF_INITIALIZING) goto IDLE_DONE;
|
||||
|
||||
// TODO: Still causing errors
|
||||
TERN_(TOOL_SENSOR, (void)check_tool_sensor_stats(active_extruder, true));
|
||||
|
@ -959,7 +959,7 @@ void stop() {
|
|||
SERIAL_ERROR_MSG(STR_ERR_STOPPED);
|
||||
LCD_MESSAGE(MSG_STOPPED);
|
||||
safe_delay(350); // allow enough time for messages to get out before stopping
|
||||
marlin_state = MF_STOPPED;
|
||||
marlin_state = MarlinState::MF_STOPPED;
|
||||
}
|
||||
}
|
||||
|
||||
|
@ -1646,7 +1646,7 @@ void setup() {
|
|||
SETUP_RUN(ftMotion.init());
|
||||
#endif
|
||||
|
||||
marlin_state = MF_RUNNING;
|
||||
marlin_state = MarlinState::MF_RUNNING;
|
||||
|
||||
#ifdef STARTUP_TUNE
|
||||
// Play a short startup tune before continuing.
|
||||
|
@ -1678,7 +1678,7 @@ void loop() {
|
|||
|
||||
#if HAS_MEDIA
|
||||
if (card.flag.abort_sd_printing) abortSDPrinting();
|
||||
if (marlin_state == MF_SD_COMPLETE) finishSDPrinting();
|
||||
if (marlin_state == MarlinState::MF_SD_COMPLETE) finishSDPrinting();
|
||||
#endif
|
||||
|
||||
queue.advance();
|
||||
|
|
|
@ -42,7 +42,7 @@ void kill(FSTR_P const lcd_error=nullptr, FSTR_P const lcd_component=nullptr, co
|
|||
void minkill(const bool steppers_off=false);
|
||||
|
||||
// Global State of the firmware
|
||||
enum MarlinState : uint8_t {
|
||||
enum class MarlinState : uint8_t {
|
||||
MF_INITIALIZING = 0,
|
||||
MF_STOPPED,
|
||||
MF_KILLED,
|
||||
|
@ -53,8 +53,8 @@ enum MarlinState : uint8_t {
|
|||
};
|
||||
|
||||
extern MarlinState marlin_state;
|
||||
inline bool IsRunning() { return marlin_state >= MF_RUNNING; }
|
||||
inline bool IsStopped() { return marlin_state == MF_STOPPED; }
|
||||
inline bool IsRunning() { return marlin_state >= MarlinState::MF_RUNNING; }
|
||||
inline bool IsStopped() { return marlin_state == MarlinState::MF_STOPPED; }
|
||||
|
||||
bool printingIsActive();
|
||||
bool printJobOngoing();
|
||||
|
|
|
@ -36,7 +36,7 @@
|
|||
* existing command buffer.
|
||||
*/
|
||||
void GcodeSuite::M999() {
|
||||
marlin_state = MF_RUNNING;
|
||||
marlin_state = MarlinState::MF_RUNNING;
|
||||
ui.reset_alert_level();
|
||||
|
||||
if (parser.boolval('S')) return;
|
||||
|
|
|
@ -294,7 +294,7 @@ void setProBarRate() {
|
|||
lv_label_set_text(bar1ValueText, public_buf_l);
|
||||
lv_obj_align(bar1ValueText, bar1, LV_ALIGN_CENTER, 0, 0);
|
||||
|
||||
if (marlin_state == MF_SD_COMPLETE) {
|
||||
if (marlin_state == MarlinState::MF_SD_COMPLETE) {
|
||||
if (once_flag == 0) {
|
||||
stop_print_time();
|
||||
|
||||
|
@ -309,7 +309,7 @@ void setProBarRate() {
|
|||
if (gCfgItems.finish_power_off) {
|
||||
gcode.process_subcommands_now(F("M1001"));
|
||||
queue.inject(F("M81"));
|
||||
marlin_state = MF_RUNNING;
|
||||
marlin_state = MarlinState::MF_RUNNING;
|
||||
}
|
||||
#endif
|
||||
}
|
||||
|
|
|
@ -766,7 +766,7 @@ void GUI_RefreshPage() {
|
|||
disp_print_time();
|
||||
disp_fan_Zpos();
|
||||
}
|
||||
if (printing_rate_update_flag || marlin_state == MF_SD_COMPLETE) {
|
||||
if (printing_rate_update_flag || marlin_state == MarlinState::MF_SD_COMPLETE) {
|
||||
printing_rate_update_flag = false;
|
||||
if (!gcode_preview_over) setProBarRate();
|
||||
}
|
||||
|
|
|
@ -1219,7 +1219,7 @@ namespace ExtUI {
|
|||
void onSurviveInKilled() {
|
||||
thermalManager.disable_all_heaters();
|
||||
flags.printer_killed = 0;
|
||||
marlin_state = MF_RUNNING;
|
||||
marlin_state = MarlinState::MF_RUNNING;
|
||||
//SERIAL_ECHOLNPGM("survived at: ", millis());
|
||||
}
|
||||
|
||||
|
|
|
@ -257,7 +257,7 @@ void report_current_position_projected() {
|
|||
AutoReporter<PositionReport> position_auto_reporter;
|
||||
#endif
|
||||
|
||||
#if ANY(FULL_REPORT_TO_HOST_FEATURE, REALTIME_REPORTING_COMMANDS)
|
||||
#if ENABLED(REALTIME_REPORTING_COMMANDS)
|
||||
|
||||
M_StateEnum M_State_grbl = M_INIT;
|
||||
|
||||
|
@ -299,18 +299,18 @@ void report_current_position_projected() {
|
|||
*/
|
||||
M_StateEnum grbl_state_for_marlin_state() {
|
||||
switch (marlin_state) {
|
||||
case MF_INITIALIZING: return M_INIT;
|
||||
case MF_SD_COMPLETE: return M_ALARM;
|
||||
case MF_WAITING: return M_IDLE;
|
||||
case MF_STOPPED: return M_END;
|
||||
case MF_RUNNING: return M_RUNNING;
|
||||
case MF_PAUSED: return M_HOLD;
|
||||
case MF_KILLED: return M_ERROR;
|
||||
default: return M_IDLE;
|
||||
case MarlinState::MF_INITIALIZING: return M_INIT;
|
||||
case MarlinState::MF_SD_COMPLETE: return M_ALARM;
|
||||
case MarlinState::MF_WAITING: return M_IDLE;
|
||||
case MarlinState::MF_STOPPED: return M_END;
|
||||
case MarlinState::MF_RUNNING: return M_RUNNING;
|
||||
case MarlinState::MF_PAUSED: return M_HOLD;
|
||||
case MarlinState::MF_KILLED: return M_ERROR;
|
||||
default: return M_IDLE;
|
||||
}
|
||||
}
|
||||
|
||||
#endif
|
||||
#endif // REALTIME_REPORTING_COMMANDS
|
||||
|
||||
#if IS_KINEMATIC
|
||||
|
||||
|
|
|
@ -272,7 +272,7 @@ void report_current_position_projected();
|
|||
extern AutoReporter<PositionReport> position_auto_reporter;
|
||||
#endif
|
||||
|
||||
#if ANY(FULL_REPORT_TO_HOST_FEATURE, REALTIME_REPORTING_COMMANDS)
|
||||
#if ENABLED(REALTIME_REPORTING_COMMANDS)
|
||||
#define HAS_GRBL_STATE 1
|
||||
/**
|
||||
* Machine states for GRBL or TinyG
|
||||
|
@ -305,11 +305,9 @@ void report_current_position_projected();
|
|||
}
|
||||
#endif
|
||||
|
||||
#if ENABLED(REALTIME_REPORTING_COMMANDS)
|
||||
void quickpause_stepper();
|
||||
void quickresume_stepper();
|
||||
#endif
|
||||
#endif
|
||||
void quickpause_stepper();
|
||||
void quickresume_stepper();
|
||||
#endif // REALTIME_REPORTING_COMMANDS
|
||||
|
||||
float get_move_distance(const xyze_pos_t &diff OPTARG(HAS_ROTATIONAL_AXES, bool &is_cartesian_move));
|
||||
|
||||
|
|
|
@ -799,8 +799,8 @@ void Planner::calculate_trapezoid_for_block(block_t * const block, const_float_t
|
|||
// Removing code to constrain values produces judder in direction-switching moves because the
|
||||
// current discrete stepping math diverges from physical motion under constant acceleration
|
||||
// when acceleration_steps_per_s2 is large compared to initial/final_rate.
|
||||
NOLESS(initial_rate, long(MINIMAL_STEP_RATE));
|
||||
NOLESS(final_rate, long(MINIMAL_STEP_RATE));
|
||||
NOLESS(initial_rate, uint32_t(MINIMAL_STEP_RATE));
|
||||
NOLESS(final_rate, uint32_t(MINIMAL_STEP_RATE));
|
||||
NOMORE(initial_rate, block->nominal_rate); // NOTE: The nominal rate may be less than MINIMAL_STEP_RATE!
|
||||
NOMORE(final_rate, block->nominal_rate);
|
||||
|
||||
|
|
|
@ -1430,7 +1430,7 @@ int16_t Temperature::getHeaterPower(const heater_id_t heater_id) {
|
|||
//
|
||||
|
||||
inline void loud_kill(FSTR_P const lcd_msg, const heater_id_t heater_id) {
|
||||
marlin_state = MF_KILLED;
|
||||
marlin_state = MarlinState::MF_KILLED;
|
||||
thermalManager.disable_all_heaters();
|
||||
#if HAS_BEEPER
|
||||
for (uint8_t i = 20; i--;) {
|
||||
|
@ -2077,7 +2077,7 @@ void Temperature::mintemp_error(const heater_id_t heater_id OPTARG(ERR_INCLUDE_T
|
|||
* - Update the heated bed PID output value
|
||||
*/
|
||||
void Temperature::task() {
|
||||
if (marlin_state == MF_INITIALIZING) return hal.watchdog_refresh(); // If Marlin isn't started, at least reset the watchdog!
|
||||
if (marlin_state == MarlinState::MF_INITIALIZING) return hal.watchdog_refresh(); // If Marlin isn't started, at least reset the watchdog!
|
||||
|
||||
static bool no_reentry = false; // Prevent recursion
|
||||
if (no_reentry) return;
|
||||
|
|
|
@ -497,7 +497,7 @@ void CardReader::mount() {
|
|||
cdroot();
|
||||
else {
|
||||
#if ANY(HAS_SD_DETECT, USB_FLASH_DRIVE_SUPPORT)
|
||||
if (marlin_state != MF_INITIALIZING) LCD_ALERTMESSAGE(MSG_MEDIA_INIT_FAIL);
|
||||
if (marlin_state != MarlinState::MF_INITIALIZING) LCD_ALERTMESSAGE(MSG_MEDIA_INIT_FAIL);
|
||||
#endif
|
||||
}
|
||||
|
||||
|
@ -1412,8 +1412,8 @@ void CardReader::fileHasFinished() {
|
|||
|
||||
endFilePrintNow(TERN_(SD_RESORT, true));
|
||||
|
||||
flag.sdprintdone = true; // Stop getting bytes from the SD card
|
||||
marlin_state = MF_SD_COMPLETE; // Tell Marlin to enqueue M1001 soon
|
||||
flag.sdprintdone = true; // Stop getting bytes from the SD card
|
||||
marlin_state = MarlinState::MF_SD_COMPLETE; // Tell Marlin to enqueue M1001 soon
|
||||
}
|
||||
|
||||
#if ENABLED(AUTO_REPORT_SD_STATUS)
|
||||
|
|
Loading…
Reference in a new issue