Use a separate serial line buffer

This commit is contained in:
Scott Lahteine 2016-02-20 17:35:35 -08:00
parent 7d25c107a8
commit 8fe7420310
6 changed files with 119 additions and 105 deletions

View file

@ -223,8 +223,8 @@ extern bool Running;
inline bool IsRunning() { return Running; } inline bool IsRunning() { return Running; }
inline bool IsStopped() { return !Running; } inline bool IsStopped() { return !Running; }
bool enqueuecommand(const char* cmd); //put a single ASCII command at the end of the current buffer or return false when it is full bool enqueue_and_echo_command(const char* cmd, bool say_ok=false); //put a single ASCII command at the end of the current buffer or return false when it is full
void enqueuecommands_P(const char* cmd); //put one or many ASCII commands at the end of the current buffer, read from flash void enqueue_and_echo_commands_P(const char* cmd); //put one or many ASCII commands at the end of the current buffer, read from flash
void prepare_arc_move(char isclockwise); void prepare_arc_move(char isclockwise);
void clamp_to_software_endstops(float target[3]); void clamp_to_software_endstops(float target[3]);

View file

@ -276,9 +276,7 @@ const char echomagic[] PROGMEM = "echo:";
const char axis_codes[NUM_AXIS] = {'X', 'Y', 'Z', 'E'}; const char axis_codes[NUM_AXIS] = {'X', 'Y', 'Z', 'E'};
static bool relative_mode = false; //Determines Absolute or Relative Coordinates static bool relative_mode = false; //Determines Absolute or Relative Coordinates
static char serial_char;
static int serial_count = 0; static int serial_count = 0;
static boolean comment_mode = false;
static char* seen_pointer; ///< A pointer to find chars in the command string (X, Y, Z, E, etc.) static char* seen_pointer; ///< A pointer to find chars in the command string (X, Y, Z, E, etc.)
const char* queued_commands_P = NULL; /* pointer to the current line in the active sequence of commands, or NULL when none */ const char* queued_commands_P = NULL; /* pointer to the current line in the active sequence of commands, or NULL when none */
const int sensitive_pins[] = SENSITIVE_PINS; ///< Sensitive pin list for M42 const int sensitive_pins[] = SENSITIVE_PINS; ///< Sensitive pin list for M42
@ -409,9 +407,7 @@ static uint8_t target_extruder;
static bool filrunoutEnqueued = false; static bool filrunoutEnqueued = false;
#endif #endif
#if ENABLED(SDSUPPORT) static bool send_ok[BUFSIZE];
static bool fromsd[BUFSIZE];
#endif
#if HAS_SERVOS #if HAS_SERVOS
Servo servo[NUM_SERVOS]; Servo servo[NUM_SERVOS];
@ -483,7 +479,7 @@ static bool drain_queued_commands_P() {
char c; char c;
while ((c = cmd[i]) && c != '\n') i++; // find the end of this gcode command while ((c = cmd[i]) && c != '\n') i++; // find the end of this gcode command
cmd[i] = '\0'; cmd[i] = '\0';
if (enqueuecommand(cmd)) { // buffer was not full (else we will retry later) if (enqueue_and_echo_command(cmd)) { // buffer was not full (else we will retry later)
if (c) if (c)
queued_commands_P += i + 1; // move to next command queued_commands_P += i + 1; // move to next command
else else
@ -497,32 +493,45 @@ static bool drain_queued_commands_P() {
* Aborts the current queue, if any. * Aborts the current queue, if any.
* Note: drain_queued_commands_P() must be called repeatedly to drain the commands afterwards * Note: drain_queued_commands_P() must be called repeatedly to drain the commands afterwards
*/ */
void enqueuecommands_P(const char* pgcode) { void enqueue_and_echo_commands_P(const char* pgcode) {
queued_commands_P = pgcode; queued_commands_P = pgcode;
drain_queued_commands_P(); // first command executed asap (when possible) drain_queued_commands_P(); // first command executed asap (when possible)
} }
/** /**
* Copy a command directly into the main command buffer, from RAM. * Once a new command is in the ring buffer, call this to commit it
*
* This is done in a non-safe way and needs a rework someday.
* Returns false if it doesn't add any command
*/ */
bool enqueuecommand(const char* cmd) { inline void _commit_command(bool say_ok) {
if (*cmd == ';' || commands_in_queue >= BUFSIZE) return false; send_ok[cmd_queue_index_w] = say_ok;
// This is dangerous if a mixing of serial and this happens
char* command = command_queue[cmd_queue_index_w];
strcpy(command, cmd);
SERIAL_ECHO_START;
SERIAL_ECHOPGM(MSG_Enqueueing);
SERIAL_ECHO(command);
SERIAL_ECHOLNPGM("\"");
cmd_queue_index_w = (cmd_queue_index_w + 1) % BUFSIZE; cmd_queue_index_w = (cmd_queue_index_w + 1) % BUFSIZE;
commands_in_queue++; commands_in_queue++;
}
/**
* Copy a command directly into the main command buffer, from RAM.
* Returns true if successfully adds the command
*/
inline bool _enqueuecommand(const char* cmd, bool say_ok=false) {
if (*cmd == ';' || commands_in_queue >= BUFSIZE) return false;
strcpy(command_queue[cmd_queue_index_w], cmd);
_commit_command(say_ok);
return true; return true;
} }
/**
* Enqueue with Serial Echo
*/
bool enqueue_and_echo_command(const char* cmd, bool say_ok/*=false*/) {
if (_enqueuecommand(cmd, say_ok)) {
SERIAL_ECHO_START;
SERIAL_ECHOPGM(MSG_Enqueueing);
SERIAL_ECHO(cmd);
SERIAL_ECHOLNPGM("\"");
return true;
}
return false;
}
void setup_killpin() { void setup_killpin() {
#if HAS_KILL #if HAS_KILL
SET_INPUT(KILL_PIN); SET_INPUT(KILL_PIN);
@ -679,9 +688,8 @@ void setup() {
SERIAL_ECHOPGM(MSG_PLANNER_BUFFER_BYTES); SERIAL_ECHOPGM(MSG_PLANNER_BUFFER_BYTES);
SERIAL_ECHOLN((int)sizeof(block_t)*BLOCK_BUFFER_SIZE); SERIAL_ECHOLN((int)sizeof(block_t)*BLOCK_BUFFER_SIZE);
#if ENABLED(SDSUPPORT) // Send "ok" after commands by default
for (int8_t i = 0; i < BUFSIZE; i++) fromsd[i] = false; for (int8_t i = 0; i < BUFSIZE; i++) send_ok[i] = true;
#endif
// loads data from EEPROM if available else uses defaults (and resets step acceleration rate) // loads data from EEPROM if available else uses defaults (and resets step acceleration rate)
Config_RetrieveSettings(); Config_RetrieveSettings();
@ -740,7 +748,7 @@ void setup() {
* - Call LCD update * - Call LCD update
*/ */
void loop() { void loop() {
if (commands_in_queue < BUFSIZE - 1) get_command(); if (commands_in_queue < BUFSIZE) get_command();
#if ENABLED(SDSUPPORT) #if ENABLED(SDSUPPORT)
card.checkautostart(false); card.checkautostart(false);
@ -800,9 +808,12 @@ void gcode_line_error(const char* err, bool doFlush = true) {
*/ */
void get_command() { void get_command() {
static char serial_line_buffer[MAX_CMD_SIZE];
static boolean serial_comment_mode = false;
if (drain_queued_commands_P()) return; // priority is given to non-serial commands if (drain_queued_commands_P()) return; // priority is given to non-serial commands
#if ENABLED(NO_TIMEOUTS) #if defined(NO_TIMEOUTS) && NO_TIMEOUTS > 0
static millis_t last_command_time = 0; static millis_t last_command_time = 0;
millis_t ms = millis(); millis_t ms = millis();
@ -817,29 +828,21 @@ void get_command() {
// //
while (commands_in_queue < BUFSIZE && MYSERIAL.available() > 0) { while (commands_in_queue < BUFSIZE && MYSERIAL.available() > 0) {
#if ENABLED(NO_TIMEOUTS) char serial_char = MYSERIAL.read();
last_command_time = ms;
#endif
serial_char = MYSERIAL.read();
// //
// If the character ends the line, or the line is full... // If the character ends the line
// //
if (serial_char == '\n' || serial_char == '\r' || serial_count >= MAX_CMD_SIZE - 1) { if (serial_char == '\n' || serial_char == '\r') {
// end of line == end of comment serial_comment_mode = false; // end of line == end of comment
comment_mode = false;
if (!serial_count) return; // empty lines just exit if (!serial_count) return; // empty lines just exit
char* command = command_queue[cmd_queue_index_w]; serial_line_buffer[serial_count] = 0; // terminate string
command[serial_count] = 0; // terminate string serial_count = 0; //reset buffer
// this item in the queue is not from sd char* command = serial_line_buffer;
#if ENABLED(SDSUPPORT)
fromsd[cmd_queue_index_w] = false;
#endif
while (*command == ' ') command++; // skip any leading spaces while (*command == ' ') command++; // skip any leading spaces
char* npos = (*command == 'N') ? command : NULL; // Require the N parameter to start the line char* npos = (*command == 'N') ? command : NULL; // Require the N parameter to start the line
@ -904,44 +907,56 @@ void get_command() {
// If command was e-stop process now // If command was e-stop process now
if (strcmp(command, "M112") == 0) kill(PSTR(MSG_KILLED)); if (strcmp(command, "M112") == 0) kill(PSTR(MSG_KILLED));
cmd_queue_index_w = (cmd_queue_index_w + 1) % BUFSIZE; #if defined(NO_TIMEOUTS) && NO_TIMEOUTS > 0
commands_in_queue += 1; last_command_time = ms;
#endif
serial_count = 0; //clear buffer // Add the command to the queue
_enqueuecommand(serial_line_buffer, true);
}
else if (serial_count >= MAX_CMD_SIZE - 1) {
// Keep fetching, but ignore normal characters beyond the max length
// The command will be injected when EOL is reached
} }
else if (serial_char == '\\') { // Handle escapes else if (serial_char == '\\') { // Handle escapes
if (MYSERIAL.available() > 0 && commands_in_queue < BUFSIZE) { if (MYSERIAL.available() > 0) {
// if we have one more character, copy it over // if we have one more character, copy it over
serial_char = MYSERIAL.read(); serial_char = MYSERIAL.read();
command_queue[cmd_queue_index_w][serial_count++] = serial_char; serial_line_buffer[serial_count++] = serial_char;
} }
// otherwise do nothing // otherwise do nothing
} }
else { // its not a newline, carriage return or escape char else { // it's not a newline, carriage return or escape char
if (serial_char == ';') comment_mode = true; if (serial_char == ';') serial_comment_mode = true;
if (!comment_mode) command_queue[cmd_queue_index_w][serial_count++] = serial_char; if (!serial_comment_mode) serial_line_buffer[serial_count++] = serial_char;
}
} }
} // queue has space, serial has data
#if ENABLED(SDSUPPORT) #if ENABLED(SDSUPPORT)
if (!card.sdprinting || serial_count) return; static bool stop_buffering = false,
sd_comment_mode = false;
if (!card.sdprinting) return;
// '#' stops reading from SD to the buffer prematurely, so procedural macro calls are possible // '#' stops reading from SD to the buffer prematurely, so procedural macro calls are possible
// if it occurs, stop_buffering is triggered and the buffer is ran dry. // if it occurs, stop_buffering is triggered and the buffer is run dry.
// this character _can_ occur in serial com, due to checksums. however, no checksums are used in SD printing // this character _can_ occur in serial com, due to checksums. however, no checksums are used in SD printing
static bool stop_buffering = false;
if (commands_in_queue == 0) stop_buffering = false; if (commands_in_queue == 0) stop_buffering = false;
while (!card.eof() && commands_in_queue < BUFSIZE && !stop_buffering) { uint16_t sd_count = 0;
bool card_eof = card.eof();
while (commands_in_queue < BUFSIZE && !card_eof && !stop_buffering) {
int16_t n = card.get(); int16_t n = card.get();
serial_char = (char)n; char sd_char = (char)n;
if (serial_char == '\n' || serial_char == '\r' || card_eof = card.eof();
((serial_char == '#' || serial_char == ':') && !comment_mode) || if (card_eof || n == -1
serial_count >= (MAX_CMD_SIZE - 1) || n == -1 || sd_char == '\n' || sd_char == '\r'
|| ((sd_char == '#' || sd_char == ':') && !sd_comment_mode)
) { ) {
if (card.eof()) { if (card_eof) {
SERIAL_PROTOCOLLNPGM(MSG_FILE_PRINTED); SERIAL_PROTOCOLLNPGM(MSG_FILE_PRINTED);
print_job_stop_ms = millis(); print_job_stop_ms = millis();
char time[30]; char time[30];
@ -954,24 +969,24 @@ void get_command() {
card.printingHasFinished(); card.printingHasFinished();
card.checkautostart(true); card.checkautostart(true);
} }
if (serial_char == '#') stop_buffering = true; if (sd_char == '#') stop_buffering = true;
if (!serial_count) { sd_comment_mode = false; //for new command
comment_mode = false; //for new command
return; //if empty line if (!sd_count) continue; //skip empty lines
command_queue[cmd_queue_index_w][sd_count] = '\0'; //terminate string
sd_count = 0; //clear buffer
_commit_command(false);
} }
command_queue[cmd_queue_index_w][serial_count] = 0; //terminate string else if (sd_count >= MAX_CMD_SIZE - 1) {
// if (!comment_mode) { // Keep fetching, but ignore normal characters beyond the max length
fromsd[cmd_queue_index_w] = true; // The command will be injected when EOL is reached
commands_in_queue += 1;
cmd_queue_index_w = (cmd_queue_index_w + 1) % BUFSIZE;
// }
comment_mode = false; //for new command
serial_count = 0; //clear buffer
} }
else { else {
if (serial_char == ';') comment_mode = true; if (sd_char == ';') sd_comment_mode = true;
if (!comment_mode) command_queue[cmd_queue_index_w][serial_count++] = serial_char; if (!sd_comment_mode) command_queue[cmd_queue_index_w][sd_count++] = sd_char;
} }
} }
@ -2654,7 +2669,7 @@ inline void gcode_G28() {
case MeshStart: case MeshStart:
mbl.reset(); mbl.reset();
probe_point = 0; probe_point = 0;
enqueuecommands_P(PSTR("G28\nG29 S2")); enqueue_and_echo_commands_P(PSTR("G28\nG29 S2"));
break; break;
case MeshNext: case MeshNext:
@ -2693,7 +2708,7 @@ inline void gcode_G28() {
SERIAL_PROTOCOLLNPGM("Mesh probing done."); SERIAL_PROTOCOLLNPGM("Mesh probing done.");
probe_point = -1; probe_point = -1;
mbl.active = 1; mbl.active = 1;
enqueuecommands_P(PSTR("G28")); enqueue_and_echo_commands_P(PSTR("G28"));
} }
break; break;
@ -3215,7 +3230,7 @@ inline void gcode_G28() {
SERIAL_ECHOLNPGM(Z_PROBE_END_SCRIPT); SERIAL_ECHOLNPGM(Z_PROBE_END_SCRIPT);
} }
#endif #endif
enqueuecommands_P(PSTR(Z_PROBE_END_SCRIPT)); enqueue_and_echo_commands_P(PSTR(Z_PROBE_END_SCRIPT));
st_synchronize(); st_synchronize();
#endif #endif
@ -3374,7 +3389,7 @@ inline void gcode_M17() {
} }
/** /**
* M23: Select a file * M23: Open a file
*/ */
inline void gcode_M23() { inline void gcode_M23() {
card.openFile(current_command_args, true); card.openFile(current_command_args, true);
@ -5244,7 +5259,7 @@ inline void gcode_M428() {
SERIAL_ERRORLNPGM(MSG_ERR_M428_TOO_FAR); SERIAL_ERRORLNPGM(MSG_ERR_M428_TOO_FAR);
LCD_ALERTMESSAGEPGM("Err: Too far!"); LCD_ALERTMESSAGEPGM("Err: Too far!");
#if HAS_BUZZER #if HAS_BUZZER
enqueuecommands_P(PSTR("M300 S40 P200")); enqueue_and_echo_commands_P(PSTR("M300 S40 P200"));
#endif #endif
err = true; err = true;
break; break;
@ -5258,7 +5273,7 @@ inline void gcode_M428() {
sync_plan_position(); sync_plan_position();
LCD_ALERTMESSAGEPGM("Offset applied."); LCD_ALERTMESSAGEPGM("Offset applied.");
#if HAS_BUZZER #if HAS_BUZZER
enqueuecommands_P(PSTR("M300 S659 P200\nM300 S698 P200")); enqueue_and_echo_commands_P(PSTR("M300 S659 P200\nM300 S698 P200"));
#endif #endif
} }
} }
@ -6304,9 +6319,7 @@ void FlushSerialRequestResend() {
void ok_to_send() { void ok_to_send() {
refresh_cmd_timeout(); refresh_cmd_timeout();
#if ENABLED(SDSUPPORT) if (!send_ok[cmd_queue_index_r]) return;
if (fromsd[cmd_queue_index_r]) return;
#endif
SERIAL_PROTOCOLPGM(MSG_OK); SERIAL_PROTOCOLPGM(MSG_OK);
#if ENABLED(ADVANCED_OK) #if ENABLED(ADVANCED_OK)
char* p = command_queue[cmd_queue_index_r]; char* p = command_queue[cmd_queue_index_r];
@ -6997,7 +7010,7 @@ void manage_inactivity(bool ignore_stepper_queue/*=false*/) {
filrunout(); filrunout();
#endif #endif
if (commands_in_queue < BUFSIZE - 1) get_command(); if (commands_in_queue < BUFSIZE) get_command();
millis_t ms = millis(); millis_t ms = millis();
@ -7054,7 +7067,7 @@ void manage_inactivity(bool ignore_stepper_queue/*=false*/) {
const int HOME_DEBOUNCE_DELAY = 2500; const int HOME_DEBOUNCE_DELAY = 2500;
if (!READ(HOME_PIN)) { if (!READ(HOME_PIN)) {
if (!homeDebounceCount) { if (!homeDebounceCount) {
enqueuecommands_P(PSTR("G28")); enqueue_and_echo_commands_P(PSTR("G28"));
LCD_MESSAGEPGM(MSG_AUTO_HOME); LCD_MESSAGEPGM(MSG_AUTO_HOME);
} }
if (homeDebounceCount < HOME_DEBOUNCE_DELAY) if (homeDebounceCount < HOME_DEBOUNCE_DELAY)
@ -7180,7 +7193,7 @@ void kill(const char* lcd_msg) {
void filrunout() { void filrunout() {
if (!filrunoutEnqueued) { if (!filrunoutEnqueued) {
filrunoutEnqueued = true; filrunoutEnqueued = true;
enqueuecommands_P(PSTR(FILAMENT_RUNOUT_SCRIPT)); enqueue_and_echo_commands_P(PSTR(FILAMENT_RUNOUT_SCRIPT));
st_synchronize(); st_synchronize();
} }
} }

View file

@ -243,6 +243,14 @@ void CardReader::release() {
cardOK = false; cardOK = false;
} }
void CardReader::openAndPrintFile(const char *name) {
char cmd[4 + (FILENAME_LENGTH + 1) * MAX_DIR_DEPTH + 2]; // Room for "M23 ", names with slashes, a null, and one extra
sprintf_P(cmd, PSTR("M23 %s"), name);
for (char *c = &cmd[4]; *c; c++) *c = tolower(*c);
enqueue_and_echo_command(cmd);
enqueue_and_echo_commands_P(PSTR("M24"));
}
void CardReader::startFileprint() { void CardReader::startFileprint() {
if (cardOK) if (cardOK)
sdprinting = true; sdprinting = true;
@ -500,10 +508,7 @@ void CardReader::checkautostart(bool force) {
while (root.readDir(p, NULL) > 0) { while (root.readDir(p, NULL) > 0) {
for (int8_t i = 0; i < (int8_t)strlen((char*)p.name); i++) p.name[i] = tolower(p.name[i]); for (int8_t i = 0; i < (int8_t)strlen((char*)p.name); i++) p.name[i] = tolower(p.name[i]);
if (p.name[9] != '~' && strncmp((char*)p.name, autoname, 5) == 0) { if (p.name[9] != '~' && strncmp((char*)p.name, autoname, 5) == 0) {
char cmd[4 + (FILENAME_LENGTH + 1) * (MAX_DIR_DEPTH) + 2]; openAndPrintFile(autoname);
sprintf_P(cmd, PSTR("M23 %s"), autoname);
enqueuecommand(cmd);
enqueuecommands_P(PSTR("M24"));
found = true; found = true;
} }
} }
@ -589,7 +594,7 @@ void CardReader::printingHasFinished() {
sdprinting = false; sdprinting = false;
if (SD_FINISHED_STEPPERRELEASE) { if (SD_FINISHED_STEPPERRELEASE) {
//finishAndDisableSteppers(); //finishAndDisableSteppers();
enqueuecommands_P(PSTR(SD_FINISHED_RELEASECOMMAND)); enqueue_and_echo_commands_P(PSTR(SD_FINISHED_RELEASECOMMAND));
} }
autotempShutdown(); autotempShutdown();
} }

View file

@ -23,6 +23,7 @@ public:
void removeFile(char* name); void removeFile(char* name);
void closefile(bool store_location=false); void closefile(bool store_location=false);
void release(); void release();
void openAndPrintFile(const char *name);
void startFileprint(); void startFileprint();
void pauseSDPrint(); void pauseSDPrint();
void getStatus(); void getStatus();

View file

@ -617,7 +617,7 @@ ISR(TIMER1_COMPA_vect) {
current_block = NULL; current_block = NULL;
plan_discard_current_block(); plan_discard_current_block();
#ifdef SD_FINISHED_RELEASECOMMAND #ifdef SD_FINISHED_RELEASECOMMAND
if ((cleaning_buffer_counter == 1) && (SD_FINISHED_STEPPERRELEASE)) enqueuecommands_P(PSTR(SD_FINISHED_RELEASECOMMAND)); if ((cleaning_buffer_counter == 1) && (SD_FINISHED_STEPPERRELEASE)) enqueue_and_echo_commands_P(PSTR(SD_FINISHED_RELEASECOMMAND));
#endif #endif
cleaning_buffer_counter--; cleaning_buffer_counter--;
OCR1A = 200; OCR1A = 200;

View file

@ -479,7 +479,7 @@ static void lcd_main_menu() {
*/ */
void lcd_set_home_offsets() { void lcd_set_home_offsets() {
// M428 Command // M428 Command
enqueuecommands_P(PSTR("M428")); enqueue_and_echo_commands_P(PSTR("M428"));
lcd_return_to_status(); lcd_return_to_status();
} }
@ -1504,7 +1504,7 @@ menu_edit_type(unsigned long, long5, ftostr5, 0.01)
lcd_move_y(); lcd_move_y();
} }
static void reprapworld_keypad_move_home() { static void reprapworld_keypad_move_home() {
enqueuecommands_P((PSTR("G28"))); // move all axis home enqueue_and_echo_commands_P((PSTR("G28"))); // move all axis home
} }
#endif // REPRAPWORLD_KEYPAD #endif // REPRAPWORLD_KEYPAD
@ -1556,18 +1556,13 @@ void lcd_quick_feedback() {
*/ */
static void menu_action_back(menuFunc_t func) { lcd_goto_menu(func); } static void menu_action_back(menuFunc_t func) { lcd_goto_menu(func); }
static void menu_action_submenu(menuFunc_t func) { lcd_save_previous_menu(); lcd_goto_menu(func); } static void menu_action_submenu(menuFunc_t func) { lcd_save_previous_menu(); lcd_goto_menu(func); }
static void menu_action_gcode(const char* pgcode) { enqueuecommands_P(pgcode); } static void menu_action_gcode(const char* pgcode) { enqueue_and_echo_commands_P(pgcode); }
static void menu_action_function(menuFunc_t func) { (*func)(); } static void menu_action_function(menuFunc_t func) { (*func)(); }
#if ENABLED(SDSUPPORT) #if ENABLED(SDSUPPORT)
static void menu_action_sdfile(const char* filename, char* longFilename) { static void menu_action_sdfile(const char* filename, char* longFilename) {
char cmd[30]; card.openAndPrintFile(filename);
char* c;
sprintf_P(cmd, PSTR("M23 %s"), filename);
for (c = &cmd[4]; *c; c++) *c = tolower(*c);
enqueuecommand(cmd);
enqueuecommands_P(PSTR("M24"));
lcd_return_to_status(); lcd_return_to_status();
} }
@ -2313,7 +2308,7 @@ char* ftostr52(const float& x) {
current_position[Z_AXIS] = MESH_HOME_SEARCH_Z; current_position[Z_AXIS] = MESH_HOME_SEARCH_Z;
line_to_current(Z_AXIS); line_to_current(Z_AXIS);
mbl.active = 1; mbl.active = 1;
enqueuecommands_P(PSTR("G28")); enqueue_and_echo_commands_P(PSTR("G28"));
lcd_return_to_status(); lcd_return_to_status();
} }
else { else {
@ -2357,7 +2352,7 @@ char* ftostr52(const float& x) {
static void lcd_level_bed() { static void lcd_level_bed() {
axis_known_position[X_AXIS] = axis_known_position[Y_AXIS] = axis_known_position[Z_AXIS] = false; axis_known_position[X_AXIS] = axis_known_position[Y_AXIS] = axis_known_position[Z_AXIS] = false;
mbl.reset(); mbl.reset();
enqueuecommands_P(PSTR("G28")); enqueue_and_echo_commands_P(PSTR("G28"));
lcdDrawUpdate = 2; lcdDrawUpdate = 2;
lcd_goto_menu(_lcd_level_bed_homing); lcd_goto_menu(_lcd_level_bed_homing);
} }