/*
report.c - reporting and messaging methods
Part of Grbl
Copyright (c) 2012-2016 Sungeun K. Jeon for Gnea Research LLC
Grbl 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.
Grbl 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 Grbl. If not, see .
*/
/*
This file functions as the primary feedback interface for Grbl. Any outgoing data, such
as the protocol status messages, feedback messages, and status reports, are stored here.
For the most part, these functions primarily are called from protocol.c methods. If a
different style feedback is desired (i.e. JSON), then a user can change these following
methods to accomodate their needs.
*/
#include "grbl.h"
// Internal report utilities to reduce flash with repetitive tasks turned into functions.
void report_util_setting_prefix(uint8_t n) { serial_write('$'); print_uint8_base10(n); serial_write('='); }
static void report_util_line_feed() { printPgmString(PSTR("\r\n")); }
static void report_util_feedback_line_feed() { serial_write(']'); report_util_line_feed(); }
// static void report_util_comment_line_feed() { serial_write(')'); report_util_line_feed(); }
static void report_util_axis_values(float *axis_value) {
uint8_t idx;
for (idx=0; idx 30kHz")); break;
#endif
case STATUS_CHECK_DOOR:
printPgmString(PSTR("Check Door")); break;
// case STATUS_LINE_LENGTH_EXCEEDED: // Supported on Grbl-Mega only.
// printPgmString(PSTR("Line length exceeded")); break;
case STATUS_TRAVEL_EXCEEDED:
printPgmString(PSTR("Travel exceeded")); break;
case STATUS_INVALID_JOG_COMMAND:
printPgmString(PSTR("Invalid jog command")); break;
// Common g-code parser errors.
case STATUS_GCODE_UNSUPPORTED_COMMAND:
printPgmString(PSTR("Unsupported command")); break;
case STATUS_GCODE_MODAL_GROUP_VIOLATION:
printPgmString(PSTR("Modal group violation")); break;
case STATUS_GCODE_UNDEFINED_FEED_RATE:
printPgmString(PSTR("Undefined feed rate")); break;
default:
// Remaining g-code parser errors with error codes
printPgmString(PSTR("Invalid gcode ID:"));
print_uint8_base10(status_code); // Print error code for user reference
}
#else
printPgmString(PSTR("error:"));
print_uint8_base10(status_code);
#endif
report_util_line_feed();
}
}
// Prints alarm messages.
void report_alarm_message(int8_t alarm_code)
{
#ifdef USE_CLASSIC_GRBL_INTERFACE
printPgmString(PSTR("ALARM: "));
switch (alarm_code) {
case ALARM_HARD_LIMIT_ERROR:
printPgmString(PSTR("Hard limit")); break;
case ALARM_SOFT_LIMIT_ERROR:
printPgmString(PSTR("Soft limit")); break;
case ALARM_ABORT_CYCLE:
printPgmString(PSTR("Abort during cycle")); break;
case ALARM_PROBE_FAIL_INITIAL:
case ALARM_PROBE_FAIL_CONTACT:
printPgmString(PSTR("Probe fail")); break;
case ALARM_HOMING_FAIL_RESET:
case ALARM_HOMING_FAIL_DOOR:
case ALARM_HOMING_FAIL_PULLOFF:
case ALARM_HOMING_FAIL_APPROACH:
printPgmString(PSTR("Homing fail")); break;
}
#else
printPgmString(PSTR("ALARM:"));
print_uint8_base10(alarm_code);
#endif
report_util_line_feed();
delay_ms(500); // Force delay to ensure message clears serial write buffer.
}
// Prints feedback messages. This serves as a centralized method to provide additional
// user feedback for things that are not of the status/alarm message protocol. These are
// messages such as setup warnings, switch toggling, and how to exit alarms.
// NOTE: For interfaces, messages are always placed within brackets. And if silent mode
// is installed, the message number codes are less than zero.
void report_feedback_message(uint8_t message_code)
{
#ifdef USE_CLASSIC_GRBL_INTERFACE
serial_write('[');
#else
printPgmString(PSTR("[MSG:"));
#endif
switch(message_code) {
case MESSAGE_CRITICAL_EVENT:
printPgmString(PSTR("Reset to continue")); break;
case MESSAGE_ALARM_LOCK:
printPgmString(PSTR("'$H'|'$X' to unlock")); break;
case MESSAGE_ALARM_UNLOCK:
printPgmString(PSTR("Caution: Unlocked")); break;
case MESSAGE_ENABLED:
printPgmString(PSTR("Enabled")); break;
case MESSAGE_DISABLED:
printPgmString(PSTR("Disabled")); break;
case MESSAGE_SAFETY_DOOR_AJAR:
printPgmString(PSTR("Check Door")); break;
case MESSAGE_CHECK_LIMITS:
printPgmString(PSTR("Check Limits")); break;
case MESSAGE_PROGRAM_END:
printPgmString(PSTR("Pgm End")); break;
case MESSAGE_RESTORE_DEFAULTS:
printPgmString(PSTR("Restoring defaults")); break;
case MESSAGE_SPINDLE_RESTORE:
printPgmString(PSTR("Restoring spindle")); break;
case MESSAGE_SLEEP_MODE:
printPgmString(PSTR("Sleeping")); break;
}
report_util_feedback_line_feed();
}
// Welcome message
void report_init_message()
{
printPgmString(PSTR("\r\nGrbl " GRBL_VERSION " ['$' for help]\r\n"));
}
// Grbl help message
void report_grbl_help() {
#ifdef USE_CLASSIC_GRBL_INTERFACE
printPgmString(PSTR("$$ (view Grbl settings)\r\n"
"$# (view # parameters)\r\n"
"$G (view parser state)\r\n"
"$I (view build info)\r\n"
"$N (view startup blocks)\r\n"
"$x=value (save Grbl setting)\r\n"
"$Nx=line (save startup block)\r\n"
"$J=line (jog)\r\n"
"$SLP (sleep mode)\r\n"
"$C (check gcode mode)\r\n"
"$X (kill alarm lock)\r\n"
"$H (run homing cycle)\r\n"
"~ (cycle start)\r\n"
"! (feed hold)\r\n"
"? (current status)\r\n"
"ctrl-x (reset Grbl)\r\n"));
#else
printPgmString(PSTR("[HLP:$$ $# $G $I $N $x=val $Nx=line $J=line $SLP $C $X $H ~ ! ? ctrl-x]\r\n"));
#endif
}
// Grbl global settings print out.
// NOTE: The numbering scheme here must correlate to storing in settings.c
void report_grbl_settings() {
// Print Grbl settings.
#ifdef USE_CLASSIC_GRBL_INTERFACE
printPgmString(PSTR("$0=")); print_uint8_base10(settings.pulse_microseconds);
printPgmString(PSTR(" (step pulse, usec)\r\n$1=")); print_uint8_base10(settings.stepper_idle_lock_time);
printPgmString(PSTR(" (step idle delay, msec)\r\n$2=")); print_uint8_base10(settings.step_invert_mask);
printPgmString(PSTR(" (step port invert mask)\r\n$3=")); print_uint8_base10(settings.dir_invert_mask);
printPgmString(PSTR(" (dir port invert mask)\r\n$4=")); print_uint8_base10(bit_istrue(settings.flags,BITFLAG_INVERT_ST_ENABLE));
printPgmString(PSTR(" (step enable invert, bool)\r\n$5=")); print_uint8_base10(bit_istrue(settings.flags,BITFLAG_INVERT_LIMIT_PINS));
printPgmString(PSTR(" (limit pins invert, bool)\r\n$6=")); print_uint8_base10(bit_istrue(settings.flags,BITFLAG_INVERT_PROBE_PIN));
printPgmString(PSTR(" (probe pin invert, bool)\r\n$10=")); print_uint8_base10(settings.status_report_mask);
printPgmString(PSTR(" (status report mask)\r\n$11=")); printFloat(settings.junction_deviation,N_DECIMAL_SETTINGVALUE);
printPgmString(PSTR(" (junction deviation, mm)\r\n$12=")); printFloat(settings.arc_tolerance,N_DECIMAL_SETTINGVALUE);
printPgmString(PSTR(" (arc tolerance, mm)\r\n$13=")); print_uint8_base10(bit_istrue(settings.flags,BITFLAG_REPORT_INCHES));
printPgmString(PSTR(" (report inches, bool)\r\n$20=")); print_uint8_base10(bit_istrue(settings.flags,BITFLAG_SOFT_LIMIT_ENABLE));
printPgmString(PSTR(" (soft limits, bool)\r\n$21=")); print_uint8_base10(bit_istrue(settings.flags,BITFLAG_HARD_LIMIT_ENABLE));
printPgmString(PSTR(" (hard limits, bool)\r\n$22=")); print_uint8_base10(bit_istrue(settings.flags,BITFLAG_HOMING_ENABLE));
printPgmString(PSTR(" (homing cycle, bool)\r\n$23=")); print_uint8_base10(settings.homing_dir_mask);
printPgmString(PSTR(" (homing dir invert mask\r\n$24=")); printFloat(settings.homing_feed_rate,N_DECIMAL_SETTINGVALUE);
printPgmString(PSTR(" (homing feed, mm/min)\r\n$25=")); printFloat(settings.homing_seek_rate,N_DECIMAL_SETTINGVALUE);
printPgmString(PSTR(" (homing seek, mm/min)\r\n$26=")); print_uint8_base10(settings.homing_debounce_delay);
printPgmString(PSTR(" (homing debounce, msec)\r\n$27=")); printFloat(settings.homing_pulloff,N_DECIMAL_SETTINGVALUE);
printPgmString(PSTR(" (homing pull-off, mm)\r\n$30=")); printFloat(settings.rpm_max,N_DECIMAL_RPMVALUE);
printPgmString(PSTR(" (rpm max)\r\n$31=")); printFloat(settings.rpm_min,N_DECIMAL_RPMVALUE);
#ifdef VARIABLE_SPINDLE
printPgmString(PSTR(" (rpm min)\r\n$32=")); print_uint8_base10(bit_istrue(settings.flags,BITFLAG_LASER_MODE));
printPgmString(PSTR(" (laser mode, bool)\r\n"));
#else
printPgmString(PSTR(" (rpm min)\r\n$32=0 (laser mode, bool)\r\n"));
#endif
// Print axis settings
uint8_t idx, set_idx;
uint8_t val = AXIS_SETTINGS_START_VAL;
for (set_idx=0; set_idx');
printString(line);
serial_write(':');
report_status_message(status_code);
#endif
}
// Prints build info line
void report_build_info(char *line)
{
#ifdef USE_CLASSIC_GRBL_INTERFACE
printPgmString(PSTR("[" GRBL_VERSION "." GRBL_VERSION_BUILD ":"));
printString(line);
#else
printPgmString(PSTR("[VER:" GRBL_VERSION "." GRBL_VERSION_BUILD ":"));
printString(line);
report_util_feedback_line_feed();
printPgmString(PSTR("[OPT:")); // Generate compile-time build option list
#ifdef VARIABLE_SPINDLE
serial_write('V');
#endif
#ifdef USE_LINE_NUMBERS
serial_write('N');
#endif
#ifdef ENABLE_M7
serial_write('M');
#endif
#ifdef COREXY
serial_write('C');
#endif
#ifdef PARKING_ENABLE
serial_write('P');
#endif
#ifdef HOMING_FORCE_SET_ORIGIN
serial_write('Z');
#endif
#ifdef HOMING_SINGLE_AXIS_COMMANDS
serial_write('H');
#endif
#ifdef LIMITS_TWO_SWITCHES_ON_AXES
serial_write('L');
#endif
#ifdef USE_CLASSIC_GRBL_INTERFACE
serial_write('R');
#endif
#ifndef ENABLE_RESTORE_EEPROM_WIPE_ALL // NOTE: Shown when disabled.
serial_write('*');
#endif
#ifndef ENABLE_RESTORE_EEPROM_DEFAULT_SETTINGS // NOTE: Shown when disabled.
serial_write('$');
#endif
#ifndef ENABLE_RESTORE_EEPROM_CLEAR_PARAMETERS // NOTE: Shown when disabled.
serial_write('#');
#endif
#ifndef ENABLE_BUILD_INFO_WRITE_COMMAND // NOTE: Shown when disabled.
serial_write('I');
#endif
#ifndef FORCE_BUFFER_SYNC_DURING_EEPROM_WRITE // NOTE: Shown when disabled.
serial_write('E');
#endif
#ifndef FORCE_BUFFER_SYNC_DURING_WCO_CHANGE // NOTE: Shown when disabled.
serial_write('W');
#endif
// NOTE: Compiled values, like override increments/max/min values, may be added at some point later.
// These will likely have a comma delimiter to separate them.
#endif
report_util_feedback_line_feed();
}
// Prints the character string line Grbl has received from the user, which has been pre-parsed,
// and has been sent into protocol_execute_line() routine to be executed by Grbl.
void report_echo_line_received(char *line)
{
printPgmString(PSTR("[echo: ")); printString(line);
report_util_feedback_line_feed();
}
// Prints real-time data. This function grabs a real-time snapshot of the stepper subprogram
// and the actual location of the CNC machine. Users may change the following function to their
// specific needs, but the desired real-time data report must be as short as possible. This is
// requires as it minimizes the computational overhead and allows grbl to keep running smoothly,
// especially during g-code programs with fast, short line segments and high frequency reports (5-20Hz).
void report_realtime_status()
{
#ifdef USE_CLASSIC_GRBL_INTERFACE
uint8_t idx;
int32_t current_position[N_AXIS]; // Copy current state of the system position variable
memcpy(current_position,sys_position,sizeof(sys_position));
float print_position[N_AXIS];
// Report current machine state
switch (sys.state) {
case STATE_IDLE: printPgmString(PSTR("line_number;
}
printInteger(ln);
#endif
#ifdef REPORT_REALTIME_RATE
// Report realtime rate
printPgmString(PSTR(",F:"));
printFloat_RateValue(st_get_realtime_rate());
#endif
#ifdef REPORT_ALL_PIN_STATES
if (bit_istrue(settings.status_report_mask,
( BITFLAG_RT_STATUS_LIMIT_PINS| BITFLAG_RT_STATUS_PROBE_PIN | BITFLAG_RT_STATUS_CONTROL_PINS ))) {
printPgmString(PSTR(",Pin:"));
if (bit_istrue(settings.status_report_mask,BITFLAG_RT_STATUS_LIMIT_PINS)) {
print_uint8_base2_ndigit(limits_get_state(),N_AXIS);
}
printPgmString(PSTR("|"));
if (bit_istrue(settings.status_report_mask,BITFLAG_RT_STATUS_PROBE_PIN)) {
if (probe_get_state()) { printPgmString(PSTR("1")); }
else { printPgmString(PSTR("0")); }
}
printPgmString(PSTR("|"));
if (bit_istrue(settings.status_report_mask,BITFLAG_RT_STATUS_CONTROL_PINS)) {
print_uint8_base2_ndigit(system_control_get_state(),N_CONTROL_PIN);
}
}
#else
if (bit_istrue(settings.status_report_mask,BITFLAG_RT_STATUS_LIMIT_PINS)) {
printPgmString(PSTR(",Lim:"));
print_uint8_base2_ndigit(limits_get_state(),N_AXIS);
}
#endif
if (bit_istrue(settings.status_report_mask,BITFLAG_RT_STATUS_OVERRIDES)) {
printPgmString(PSTR(",Ov:"));
print_uint8_base10(sys.f_override);
serial_write(',');
print_uint8_base10(sys.r_override);
serial_write(',');
print_uint8_base10(sys.spindle_speed_ovr);
uint8_t sp_state = spindle_get_state();
uint8_t cl_state = coolant_get_state();
if (sp_state | cl_state) {
printPgmString(PSTR(",A:"));
if (sp_state) { // != SPINDLE_STATE_DISABLE
#ifdef VARIABLE_SPINDLE
#ifdef USE_SPINDLE_DIR_AS_ENABLE_PIN
serial_write('S'); // CW
#else
if (sp_state == SPINDLE_STATE_CW) { serial_write('S'); } // CW
else { serial_write('C'); } // CCW
#endif
#else
if (sp_state & SPINDLE_STATE_CW) { serial_write('S'); } // CW
else { serial_write('C'); } // CCW
#endif
}
if (cl_state & COOLANT_STATE_FLOOD) { serial_write('F'); }
#ifdef ENABLE_M7
if (cl_state & COOLANT_STATE_MIST) { serial_write('M'); }
#endif
}
}
printPgmString(PSTR(">\r\n"));
#else
uint8_t idx;
int32_t current_position[N_AXIS]; // Copy current state of the system position variable
memcpy(current_position,sys_position,sizeof(sys_position));
float print_position[N_AXIS];
system_convert_array_steps_to_mpos(print_position,current_position);
// Report current machine state and sub-states
serial_write('<');
switch (sys.state) {
case STATE_IDLE: printPgmString(PSTR("Idle")); break;
case STATE_CYCLE: printPgmString(PSTR("Run")); break;
case STATE_HOLD:
if (!(sys.suspend & SUSPEND_JOG_CANCEL)) {
printPgmString(PSTR("Hold:"));
if (sys.suspend & SUSPEND_HOLD_COMPLETE) { serial_write('0'); } // Ready to resume
else { serial_write('1'); } // Actively holding
break;
} // Continues to print jog state during jog cancel.
case STATE_JOG: printPgmString(PSTR("Jog")); break;
case STATE_HOMING: printPgmString(PSTR("Home")); break;
case STATE_ALARM: printPgmString(PSTR("Alarm")); break;
case STATE_CHECK_MODE: printPgmString(PSTR("Check")); break;
case STATE_SAFETY_DOOR:
printPgmString(PSTR("Door:"));
if (sys.suspend & SUSPEND_INITIATE_RESTORE) {
serial_write('3'); // Restoring
} else {
if (sys.suspend & SUSPEND_RETRACT_COMPLETE) {
if (sys.suspend & SUSPEND_SAFETY_DOOR_AJAR) {
serial_write('1'); // Door ajar
} else {
serial_write('0');
} // Door closed and ready to resume
} else {
serial_write('2'); // Retracting
}
}
break;
case STATE_SLEEP: printPgmString(PSTR("Sleep")); break;
}
float wco[N_AXIS];
if (bit_isfalse(settings.status_report_mask,BITFLAG_RT_STATUS_POSITION_TYPE) ||
(sys.report_wco_counter == 0) ) {
for (idx=0; idx< N_AXIS; idx++) {
// Apply work coordinate offsets and tool length offset to current position.
wco[idx] = gc_state.coord_system[idx]+gc_state.coord_offset[idx];
if (idx == TOOL_LENGTH_OFFSET_AXIS) { wco[idx] += gc_state.tool_length_offset; }
if (bit_isfalse(settings.status_report_mask,BITFLAG_RT_STATUS_POSITION_TYPE)) {
print_position[idx] -= wco[idx];
}
}
}
// Report machine position
if (bit_istrue(settings.status_report_mask,BITFLAG_RT_STATUS_POSITION_TYPE)) {
printPgmString(PSTR("|MPos:"));
} else {
printPgmString(PSTR("|WPos:"));
}
report_util_axis_values(print_position);
// Returns planner and serial read buffer states.
#ifdef REPORT_FIELD_BUFFER_STATE
if (bit_istrue(settings.status_report_mask,BITFLAG_RT_STATUS_BUFFER_STATE)) {
printPgmString(PSTR("|Bf:"));
print_uint8_base10(plan_get_block_buffer_available());
serial_write(',');
print_uint8_base10(serial_get_rx_buffer_available());
}
#endif
#ifdef USE_LINE_NUMBERS
#ifdef REPORT_FIELD_LINE_NUMBERS
// Report current line number
plan_block_t * cur_block = plan_get_current_block();
if (cur_block != NULL) {
uint32_t ln = cur_block->line_number;
if (ln > 0) {
printPgmString(PSTR("|Ln:"));
printInteger(ln);
}
}
#endif
#endif
// Report realtime feed speed
#ifdef REPORT_FIELD_CURRENT_FEED_SPEED
#ifdef VARIABLE_SPINDLE
printPgmString(PSTR("|FS:"));
printFloat_RateValue(st_get_realtime_rate());
serial_write(',');
printFloat(sys.spindle_speed,N_DECIMAL_RPMVALUE);
#else
printPgmString(PSTR("|F:"));
printFloat_RateValue(st_get_realtime_rate());
#endif
#endif
#ifdef REPORT_FIELD_PIN_STATE
uint8_t lim_pin_state = limits_get_state();
uint8_t ctrl_pin_state = system_control_get_state();
uint8_t prb_pin_state = probe_get_state();
if (lim_pin_state | ctrl_pin_state | prb_pin_state) {
printPgmString(PSTR("|Pn:"));
if (prb_pin_state) { serial_write('P'); }
if (lim_pin_state) {
if (bit_istrue(lim_pin_state,bit(X_AXIS))) { serial_write('X'); }
if (bit_istrue(lim_pin_state,bit(Y_AXIS))) { serial_write('Y'); }
if (bit_istrue(lim_pin_state,bit(Z_AXIS))) { serial_write('Z'); }
}
if (ctrl_pin_state) {
#ifdef ENABLE_SAFETY_DOOR_INPUT_PIN
if (bit_istrue(ctrl_pin_state,CONTROL_PIN_INDEX_SAFETY_DOOR)) { serial_write('D'); }
#endif
if (bit_istrue(ctrl_pin_state,CONTROL_PIN_INDEX_RESET)) { serial_write('R'); }
if (bit_istrue(ctrl_pin_state,CONTROL_PIN_INDEX_FEED_HOLD)) { serial_write('H'); }
if (bit_istrue(ctrl_pin_state,CONTROL_PIN_INDEX_CYCLE_START)) { serial_write('S'); }
}
}
#endif
#ifdef REPORT_FIELD_WORK_COORD_OFFSET
if (sys.report_wco_counter > 0) { sys.report_wco_counter--; }
else {
if (sys.state & (STATE_HOMING | STATE_CYCLE | STATE_HOLD | STATE_JOG | STATE_SAFETY_DOOR)) {
sys.report_wco_counter = (REPORT_WCO_REFRESH_BUSY_COUNT-1); // Reset counter for slow refresh
} else { sys.report_wco_counter = (REPORT_WCO_REFRESH_IDLE_COUNT-1); }
if (sys.report_ovr_counter == 0) { sys.report_ovr_counter = 1; } // Set override on next report.
printPgmString(PSTR("|WCO:"));
report_util_axis_values(wco);
}
#endif
#ifdef REPORT_FIELD_OVERRIDES
if (sys.report_ovr_counter > 0) { sys.report_ovr_counter--; }
else {
if (sys.state & (STATE_HOMING | STATE_CYCLE | STATE_HOLD | STATE_JOG | STATE_SAFETY_DOOR)) {
sys.report_ovr_counter = (REPORT_OVR_REFRESH_BUSY_COUNT-1); // Reset counter for slow refresh
} else { sys.report_ovr_counter = (REPORT_OVR_REFRESH_IDLE_COUNT-1); }
printPgmString(PSTR("|Ov:"));
print_uint8_base10(sys.f_override);
serial_write(',');
print_uint8_base10(sys.r_override);
serial_write(',');
print_uint8_base10(sys.spindle_speed_ovr);
uint8_t sp_state = spindle_get_state();
uint8_t cl_state = coolant_get_state();
if (sp_state || cl_state) {
printPgmString(PSTR("|A:"));
if (sp_state) { // != SPINDLE_STATE_DISABLE
#ifdef VARIABLE_SPINDLE
#ifdef USE_SPINDLE_DIR_AS_ENABLE_PIN
serial_write('S'); // CW
#else
if (sp_state == SPINDLE_STATE_CW) { serial_write('S'); } // CW
else { serial_write('C'); } // CCW
#endif
#else
if (sp_state & SPINDLE_STATE_CW) { serial_write('S'); } // CW
else { serial_write('C'); } // CCW
#endif
}
if (cl_state & COOLANT_STATE_FLOOD) { serial_write('F'); }
#ifdef ENABLE_M7
if (cl_state & COOLANT_STATE_MIST) { serial_write('M'); }
#endif
}
}
#endif
serial_write('>');
report_util_line_feed();
#endif
}
#ifdef DEBUG
void report_realtime_debug()
{
}
#endif