/*
report.c - reporting and messaging methods
Part of Grbl
Copyright (c) 2012-2016 Sungeun K. Jeon for Gnea Research LLC
2018 - Bart Dring This file was modified for use on the ESP32
CPU. Do not use this with Grbl for atMega328P
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 accommodate their needs.
ESP32 Notes:
Major rewrite to fix issues with BlueTooth. As described here there is a
when you try to send data a single byte at a time using SerialBT.write(...).
https://github.com/espressif/arduino-esp32/issues/1537
A solution is to send messages as a string using SerialBT.print(...). Use
a short delay after each send. Therefore this file needed to be rewritten
to work that way. AVR Grbl was written to be super efficient to give it
good performance. This is far less efficient, but the ESP32 can handle it.
Do not use this version of the file with AVR Grbl.
ESP32 discussion here ... https://github.com/bdring/Grbl_Esp32/issues/3
*/
#include "grbl.h"
#define DEFAULTBUFFERSIZE 64
// this is a generic send function that everything should use, so interfaces could be added (Bluetooth, etc)
void grbl_send(uint8_t client, const char *text)
{
if (client == CLIENT_INPUT) return;
#ifdef ENABLE_BLUETOOTH
if (SerialBT.hasClient() && ( client == CLIENT_BT || client == CLIENT_ALL ) )
{
SerialBT.print(text);
//delay(10); // possible fix for dropped characters
}
#endif
#if defined (ENABLE_WIFI) && defined(ENABLE_HTTP) && defined(ENABLE_SERIAL2SOCKET_OUT)
if ( client == CLIENT_WEBUI || client == CLIENT_ALL )
Serial2Socket.write((const uint8_t*)text, strlen(text));
#endif
#if defined (ENABLE_WIFI) && defined(ENABLE_TELNET)
if ( client == CLIENT_TELNET || client == CLIENT_ALL ){
telnet_server.write((const uint8_t*)text, strlen(text));
}
#endif
if ( client == CLIENT_SERIAL || client == CLIENT_ALL )
Serial.print(text);
}
// This is a formating version of the grbl_send(CLIENT_ALL,...) function that work like printf
void grbl_sendf(uint8_t client, const char *format, ...)
{
if (client == CLIENT_INPUT) return;
char loc_buf[64];
char * temp = loc_buf;
va_list arg;
va_list copy;
va_start(arg, format);
va_copy(copy, arg);
size_t len = vsnprintf(NULL, 0, format, arg);
va_end(copy);
if(len >= sizeof(loc_buf)){
temp = new char[len+1];
if(temp == NULL) {
return;
}
}
len = vsnprintf(temp, len+1, format, arg);
grbl_send(client, temp);
va_end(arg);
if(len > 64){
delete[] temp;
}
}
//function to notify
void grbl_notify(const char *title, const char *msg){
#ifdef ENABLE_NOTIFICATIONS
notificationsservice.sendMSG(title, msg);
#endif
}
void grbl_notifyf(const char *title, const char *format, ...){
char loc_buf[64];
char * temp = loc_buf;
va_list arg;
va_list copy;
va_start(arg, format);
va_copy(copy, arg);
size_t len = vsnprintf(NULL, 0, format, arg);
va_end(copy);
if(len >= sizeof(loc_buf)){
temp = new char[len+1];
if(temp == NULL) {
return;
}
}
len = vsnprintf(temp, len+1, format, arg);
grbl_notify(title, temp);
va_end(arg);
if(len > 64){
delete[] temp;
}
}
// formats axis values into a string and returns that string in rpt
static void report_util_axis_values(float *axis_value, char *rpt) {
uint8_t idx;
char axisVal[10];
float unit_conv = 1.0; // unit conversion multiplier..default is mm
rpt[0] = '\0';
if (bit_istrue(settings.flags,BITFLAG_REPORT_INCHES))
unit_conv = 1.0 / MM_PER_INCH;
for (idx=0; idx= MOTION_MODE_PROBE_TOWARD) {
sprintf(temp, "38.%d", gc_state.modal.motion - (MOTION_MODE_PROBE_TOWARD-2));
} else {
sprintf(temp, "%d", gc_state.modal.motion);
}
strcat(modes_rpt, temp);
sprintf(temp, " G%d", gc_state.modal.coord_select+54);
strcat(modes_rpt, temp);
sprintf(temp, " G%d", gc_state.modal.plane_select+17);
strcat(modes_rpt, temp);
sprintf(temp, " G%d", 21-gc_state.modal.units);
strcat(modes_rpt, temp);
sprintf(temp, " G%d", gc_state.modal.distance+90);
strcat(modes_rpt, temp);
sprintf(temp, " G%d", 94-gc_state.modal.feed_rate);
strcat(modes_rpt, temp);
if (gc_state.modal.program_flow) {
//report_util_gcode_modes_M();
switch (gc_state.modal.program_flow) {
case PROGRAM_FLOW_PAUSED : strcat(modes_rpt, " M0"); //serial_write('0'); break;
// case PROGRAM_FLOW_OPTIONAL_STOP : serial_write('1'); break; // M1 is ignored and not supported.
case PROGRAM_FLOW_COMPLETED_M2 :
case PROGRAM_FLOW_COMPLETED_M30 :
sprintf(temp, " M%d", gc_state.modal.program_flow);
strcat(modes_rpt, temp);
break;
}
}
switch (gc_state.modal.spindle) {
case SPINDLE_ENABLE_CW : strcat(modes_rpt, " M3"); break;
case SPINDLE_ENABLE_CCW : strcat(modes_rpt, " M4"); break;
case SPINDLE_DISABLE : strcat(modes_rpt, " M5"); break;
}
//report_util_gcode_modes_M(); // optional M7 and M8 should have been dealt with by here
if (gc_state.modal.coolant) { // Note: Multiple coolant states may be active at the same time.
if (gc_state.modal.coolant & PL_COND_FLAG_COOLANT_MIST) { strcat(modes_rpt, " M7"); }
if (gc_state.modal.coolant & PL_COND_FLAG_COOLANT_FLOOD) { strcat(modes_rpt, " M8"); }
}
else {
strcat(modes_rpt, " M9");
}
sprintf(temp, " T%d", gc_state.tool);
strcat(modes_rpt, temp);
if (bit_istrue(settings.flags,BITFLAG_REPORT_INCHES)) {
sprintf(temp, " F%.1f", gc_state.feed_rate);
} else {
sprintf(temp, " F%.0f", gc_state.feed_rate);
}
strcat(modes_rpt, temp);
#ifdef VARIABLE_SPINDLE
sprintf(temp, " S%4.3f", gc_state.spindle_speed);
strcat(modes_rpt, temp);
#endif
strcat(modes_rpt, "]\r\n");
grbl_send(client, modes_rpt);
}
// Prints specified startup line
void report_startup_line(uint8_t n, char *line, uint8_t client)
{
grbl_sendf(client, "$N%d=%s\r\n", n, line); // OK to send to all
}
void report_execute_startup_message(char *line, uint8_t status_code, uint8_t client)
{
grbl_sendf(client, ">%s:", line); // OK to send to all
report_status_message(status_code, client);
}
// Prints build info line
void report_build_info(char *line, uint8_t client)
{
char build_info[50];
strcpy(build_info, "[VER:" GRBL_VERSION "." GRBL_VERSION_BUILD ":");
strcat(build_info, line);
strcat(build_info, "]\r\n[OPT:");
#ifdef VARIABLE_SPINDLE
strcat(build_info,"V");
#endif
#ifdef USE_LINE_NUMBERS
strcat(build_info,"N");
#endif
#ifdef COOLANT_MIST_PIN
strcat(build_info,"M"); // TODO Need to deal with M8...it could be disabled
#endif
#ifdef COREXY
strcat(build_info,"C");
#endif
#ifdef PARKING_ENABLE
strcat(build_info,"P");
#endif
#if (defined(HOMING_FORCE_SET_ORIGIN) || defined(HOMING_FORCE_POSITIVE_SPACE))
strcat(build_info,"Z"); // homing MPOS bahavior is not the default behavior
#endif
#ifdef HOMING_SINGLE_AXIS_COMMANDS
strcat(build_info,"H");
#endif
#ifdef LIMITS_TWO_SWITCHES_ON_AXES
strcat(build_info,"L");
#endif
#ifdef ALLOW_FEED_OVERRIDE_DURING_PROBE_CYCLES
strcat(build_info,"A");
#endif
#ifdef ENABLE_BLUETOOTH
strcat(build_info,"B");
#endif
#ifdef ENABLE_SD_CARD
strcat(build_info,"S");
#endif
#if defined (ENABLE_WIFI)
strcat(build_info,"W");
#endif
#ifndef ENABLE_RESTORE_EEPROM_WIPE_ALL // NOTE: Shown when disabled.
strcat(build_info,"*");
#endif
#ifndef ENABLE_RESTORE_EEPROM_DEFAULT_SETTINGS // NOTE: Shown when disabled.
strcat(build_info,"$");
#endif
#ifndef ENABLE_RESTORE_EEPROM_CLEAR_PARAMETERS // NOTE: Shown when disabled.
strcat(build_info,"#");
#endif
#ifndef ENABLE_BUILD_INFO_WRITE_COMMAND // NOTE: Shown when disabled.
strcat(build_info,"I");
#endif
#ifndef FORCE_BUFFER_SYNC_DURING_EEPROM_WRITE // NOTE: Shown when disabled.
strcat(build_info,"E");
#endif
#ifndef FORCE_BUFFER_SYNC_DURING_WCO_CHANGE // NOTE: Shown when disabled.
strcat(build_info,"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.
strcat(build_info,"]\r\n");
grbl_send(client, build_info); // ok to send to all
#if defined (ENABLE_WIFI)
grbl_send(client, (char *)wifi_config.info());
#endif
#if defined (ENABLE_BLUETOOTH)
grbl_send(client, (char *)bt_config.info());
#endif
}
// 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, uint8_t client)
{
grbl_sendf(client, "[echo: %s]\r\n", line);
}
// 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(uint8_t client)
{
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];
char status[200];
char temp[80];
system_convert_array_steps_to_mpos(print_position,current_position);
// Report current machine state and sub-states
strcpy(status, "<");
switch (sys.state) {
case STATE_IDLE: strcat(status, "Idle"); break;
case STATE_CYCLE: strcat(status, "Run"); break;
case STATE_HOLD:
if (!(sys.suspend & SUSPEND_JOG_CANCEL)) {
strcat(status, "Hold:");
if (sys.suspend & SUSPEND_HOLD_COMPLETE) { strcat(status, "0"); } // Ready to resume
else { strcat(status, "1"); } // Actively holding
break;
} // Continues to print jog state during jog cancel.
case STATE_JOG: strcat(status, "Jog"); break;
case STATE_HOMING: strcat(status, "Home"); break;
case STATE_ALARM: strcat(status, "Alarm"); break;
case STATE_CHECK_MODE: strcat(status, "Check"); break;
case STATE_SAFETY_DOOR:
strcat(status, "Door:");
if (sys.suspend & SUSPEND_INITIATE_RESTORE) {
strcat(status, "3"); // Restoring
} else {
if (sys.suspend & SUSPEND_RETRACT_COMPLETE) {
if (sys.suspend & SUSPEND_SAFETY_DOOR_AJAR) {
strcat(status, "1"); // Door ajar
} else {
strcat(status, "0");
} // Door closed and ready to resume
} else {
strcat(status, "2"); // Retracting
}
}
break;
case STATE_SLEEP: strcat(status, "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)) {
strcat(status, "|MPos:");
} else {
#ifdef FWD_KINEMATICS_REPORTING
forward_kinematics(print_position);
#endif
strcat(status, "|WPos:");
}
report_util_axis_values(print_position, temp);
strcat(status, temp);
// Returns planner and serial read buffer states.
#ifdef REPORT_FIELD_BUFFER_STATE
if (bit_istrue(settings.status_report_mask,BITFLAG_RT_STATUS_BUFFER_STATE)) {
int bufsize = DEFAULTBUFFERSIZE;
#if defined (ENABLE_WIFI) && defined(ENABLE_TELNET)
if (client == CLIENT_TELNET){
bufsize = telnet_server.get_rx_buffer_available();
}
#endif //ENABLE_WIFI && ENABLE_TELNET
#if defined(ENABLE_BLUETOOTH)
if (client == CLIENT_BT){
//TODO FIXME
bufsize = 512 - SerialBT.available();
}
#endif //ENABLE_BLUETOOTH
if (client == CLIENT_SERIAL){
bufsize = serial_get_rx_buffer_available(CLIENT_SERIAL);
}
sprintf(temp, "|Bf:%d,%d", plan_get_block_buffer_available(), bufsize);
strcat(status, temp);
}
#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) {
sprintf(temp, "|Ln:%d", ln);
strcat(status, temp);
}
}
#endif
#endif
// Report realtime feed speed
#ifdef REPORT_FIELD_CURRENT_FEED_SPEED
#ifdef VARIABLE_SPINDLE
if (bit_istrue(settings.flags,BITFLAG_REPORT_INCHES)) {
sprintf(temp, "|FS:%.1f,%.0f", st_get_realtime_rate(), sys.spindle_speed / MM_PER_INCH);
} else {
sprintf(temp, "|FS:%.0f,%.0f", st_get_realtime_rate(), sys.spindle_speed);
}
strcat(status, temp);
#else
if (bit_istrue(settings.flags,BITFLAG_REPORT_INCHES)) {
sprintf(temp, "|F:%.1f", st_get_realtime_rate() / MM_PER_INCH);
} else {
sprintf(temp, "|F:%.0f", st_get_realtime_rate());
}
strcat(status, temp);
#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) {
strcat(status, "|Pn:");
if (prb_pin_state) { strcat(status, "P"); }
if (lim_pin_state) {
if (bit_istrue(lim_pin_state,bit(X_AXIS))) { strcat(status, "X"); }
if (bit_istrue(lim_pin_state,bit(Y_AXIS))) { strcat(status, "Y"); }
if (bit_istrue(lim_pin_state,bit(Z_AXIS))) { strcat(status, "Z"); }
#if (N_AXIS > A_AXIS)
if (bit_istrue(lim_pin_state,bit(A_AXIS))) { strcat(status, "A"); }
#endif
#if (N_AXIS > B_AXIS)
if (bit_istrue(lim_pin_state,bit(B_AXIS))) { strcat(status, "B"); }
#endif
#if (N_AXIS > C_AXIS)
if (bit_istrue(lim_pin_state,bit(C_AXIS))) { strcat(status, "C"); }
#endif
}
if (ctrl_pin_state) {
#ifdef ENABLE_SAFETY_DOOR_INPUT_PIN
if (bit_istrue(ctrl_pin_state,CONTROL_PIN_INDEX_SAFETY_DOOR)) { strcat(status, "D"); }
#endif
if (bit_istrue(ctrl_pin_state,CONTROL_PIN_INDEX_RESET)) { strcat(status, "R"); }
if (bit_istrue(ctrl_pin_state,CONTROL_PIN_INDEX_FEED_HOLD)) { strcat(status, "H"); }
if (bit_istrue(ctrl_pin_state,CONTROL_PIN_INDEX_CYCLE_START)) { strcat(status, "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.
strcat(status, "|WCO:");
report_util_axis_values(wco, temp);
strcat(status, temp);
}
#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); }
sprintf(temp, "|Ov:%d,%d,%d", sys.f_override, sys.r_override, sys.spindle_speed_ovr);
strcat(status, temp);
uint8_t sp_state = spindle_get_state();
uint8_t cl_state = coolant_get_state();
if (sp_state || cl_state) {
strcat(status, "|A:");
if (sp_state) { // != SPINDLE_STATE_DISABLE
if (sp_state == SPINDLE_STATE_CW) { strcat(status, "S"); } // CW
else { strcat(status, "C"); } // CCW
}
if (cl_state & COOLANT_STATE_FLOOD) { strcat(status, "F"); }
#ifdef COOLANT_MIST_PIN // TODO Deal with M8 - Flood
if (cl_state & COOLANT_STATE_MIST) { strcat(status, "M"); }
#endif
}
}
#endif
#ifdef ENABLE_SD_CARD
if (get_sd_state(false) == SDCARD_BUSY_PRINTING) {
sprintf(temp, "|SD:%4.2f,", sd_report_perc_complete());
strcat(status, temp);
sd_get_current_filename(temp);
strcat(status, temp);
}
#endif
strcat(status, ">\r\n");
grbl_send(client, status);
}
void report_realtime_steps()
{
uint8_t idx;
for (idx=0; idx< N_AXIS; idx++) {
grbl_sendf(CLIENT_ALL, "%ld\n", sys_position[idx]); // OK to send to all ... debug stuff
}
}
void report_gcode_comment(char *comment) {
char msg[80];
const uint8_t offset = 4; // ignore "MSG_" part of comment
uint8_t index = offset;
if (strstr(comment, "MSG")) {
while(index < strlen(comment)) {
msg[index-offset] = comment[index];
index++;
}
msg[index-offset] = 0; // null terminate
grbl_sendf(CLIENT_ALL, "[MSG:GCode Comment %s]\r\n",msg);
}
}