1
0
mirror of https://github.com/bdring/Grbl_Esp32.git synced 2025-09-01 18:32:37 +02:00

Change [MSG:.....] method

[MSG:....] type information can now have levels and can be turned off.
added debug level none to
This commit is contained in:
bdring
2020-02-06 20:22:00 -06:00
parent dc8bd1c0bd
commit d1164248b7
20 changed files with 114 additions and 338 deletions

View File

@@ -37,12 +37,12 @@ volatile uint8_t sys_rt_exec_accessory_override; // Global realtime executor bit
void setup() { void setup() {
serial_init(); // Setup serial baud rate and interrupts serial_init(); // Setup serial baud rate and interrupts
grbl_sendf(CLIENT_SERIAL, "[MSG:ESP32 SDK: %s]\r\n", ESP.getSdkVersion()); // print the SDK version grbl_msg_sendf(CLIENT_SERIAL, MSG_LEVEL_INFO, "Compiled with ESP32 SDK:%s", ESP.getSdkVersion()); // print the SDK version
#ifdef CPU_MAP_NAME // show the map name at startup #ifdef CPU_MAP_NAME // show the map name at startup
grbl_send(CLIENT_SERIAL,"[MSG:Using cpu_map..." CPU_MAP_NAME "]\r\n"); grbl_msg_sendf(CLIENT_SERIAL, MSG_LEVEL_INFO, "Using cpu_map:%s", CPU_MAP_NAME);
#endif #endif
settings_init(); // Load Grbl settings from EEPROM settings_init(); // Load Grbl settings from EEPROM

View File

@@ -43,7 +43,7 @@ void machine_init()
{ {
solenoid_pull_count = 0; // initialize solenoid_pull_count = 0; // initialize
grbl_send(CLIENT_SERIAL, "[MSG:Atari 1020 Solenoid]\r\n"); grbl_msg_sendf(CLIENT_SERIAL, MSG_LEVEL_INFO, "Atari 1020 Solenoid");
// setup PWM channel // setup PWM channel
ledcSetup(SOLENOID_CHANNEL_NUM, SOLENOID_PWM_FREQ, SOLENOID_PWM_RES_BITS); ledcSetup(SOLENOID_CHANNEL_NUM, SOLENOID_PWM_FREQ, SOLENOID_PWM_RES_BITS);
@@ -167,13 +167,13 @@ void atari_home_task(void *pvParameters) {
homing_phase = HOMING_PHASE_CHECK; homing_phase = HOMING_PHASE_CHECK;
break; break;
default: default:
grbl_sendf(CLIENT_SERIAL, "[MSG:Homing phase error %d]\r\n", homing_phase); grbl_msg_sendf(CLIENT_SERIAL, MSG_LEVEL_INFO, "Homing phase error %d", homing_phase);
atari_homing = false;; // kills task atari_homing = false;; // kills task
break; break;
} }
if (homing_attempt > ATARI_HOMING_ATTEMPTS) { // try all positions plus 1 if (homing_attempt > ATARI_HOMING_ATTEMPTS) { // try all positions plus 1
grbl_send(CLIENT_SERIAL, "[MSG: Atari homing failed]\r\n"); grbl_msg_sendf(CLIENT_SERIAL, MSG_LEVEL_INFO, "Atari homing failed");
inputBuffer.push("G90\r"); inputBuffer.push("G90\r");
atari_homing = false;; atari_homing = false;;
} }
@@ -236,7 +236,7 @@ void user_tool_change(uint8_t new_tool) {
protocol_buffer_synchronize(); // wait for all previous moves to complete protocol_buffer_synchronize(); // wait for all previous moves to complete
if ((new_tool < 1) || (new_tool > MAX_PEN_NUMBER)) { if ((new_tool < 1) || (new_tool > MAX_PEN_NUMBER)) {
grbl_sendf(CLIENT_ALL, "[MSG: Requested Pen#%d is out of 1-4 range]\r\n", new_tool); grbl_msg_sendf(CLIENT_SERIAL, MSG_LEVEL_INFO, "Requested Pen#%d is out of 1-4 range", new_tool);
return; return;
} }
@@ -259,7 +259,7 @@ void user_tool_change(uint8_t new_tool) {
current_tool = new_tool; current_tool = new_tool;
grbl_sendf(CLIENT_ALL, "[MSG: Change to Pen#%d]\r\n", current_tool); grbl_msg_sendf(CLIENT_SERIAL, MSG_LEVEL_INFO, "Change to Pen#%d", current_tool);
} }
@@ -282,14 +282,14 @@ void user_defined_macro(uint8_t index)
switch (index) { switch (index) {
#ifdef MACRO_BUTTON_0_PIN #ifdef MACRO_BUTTON_0_PIN
case CONTROL_PIN_INDEX_MACRO_0: case CONTROL_PIN_INDEX_MACRO_0:
grbl_send(CLIENT_SERIAL, "[MSG: Pen Switch]\r\n"); grbl_msg_sendf(CLIENT_SERIAL, MSG_LEVEL_INFO, "Pen switch");
inputBuffer.push("$H\r"); inputBuffer.push("$H\r");
break; break;
#endif #endif
#ifdef MACRO_BUTTON_1_PIN #ifdef MACRO_BUTTON_1_PIN
case CONTROL_PIN_INDEX_MACRO_1: case CONTROL_PIN_INDEX_MACRO_1:
grbl_send(CLIENT_SERIAL, "[MSG: Color Switch]\r\n"); grbl_msg_sendf(CLIENT_SERIAL, MSG_LEVEL_INFO, "Color switch");
atari_next_pen(); atari_next_pen();
sprintf(gcode_line, "G90G0X%3.2f\r", ATARI_PAPER_WIDTH); // alway return to right side to reduce home travel stalls sprintf(gcode_line, "G90G0X%3.2f\r", ATARI_PAPER_WIDTH); // alway return to right side to reduce home travel stalls
inputBuffer.push(gcode_line); inputBuffer.push(gcode_line);
@@ -299,7 +299,7 @@ void user_defined_macro(uint8_t index)
#ifdef MACRO_BUTTON_2_PIN #ifdef MACRO_BUTTON_2_PIN
case CONTROL_PIN_INDEX_MACRO_2: case CONTROL_PIN_INDEX_MACRO_2:
// feed out some paper and reset the Y 0 // feed out some paper and reset the Y 0
grbl_send(CLIENT_SERIAL, "[MSG: Paper Switch]\r\n"); grbl_msg_sendf(CLIENT_SERIAL, MSG_LEVEL_INFO, "Paper switch");
inputBuffer.push("G0Y-25\r"); inputBuffer.push("G0Y-25\r");
inputBuffer.push("G4P0.1\r"); // sync...forces wait for planner to clear inputBuffer.push("G4P0.1\r"); // sync...forces wait for planner to clear
sys_position[Y_AXIS] = 0.0; // reset the Y position sys_position[Y_AXIS] = 0.0; // reset the Y position
@@ -309,7 +309,7 @@ void user_defined_macro(uint8_t index)
#endif #endif
default: default:
grbl_sendf(CLIENT_SERIAL, "[MSG: Unknown Switch %d]\r\n", index); grbl_msg_sendf(CLIENT_SERIAL, MSG_LEVEL_INFO, "Unknown Switch %d", index);
break; break;
} }
} }

View File

@@ -44,11 +44,12 @@ Some features should not be changed. See notes below.
// The CPU map is the main definition of the machine/controller you want to use // The CPU map is the main definition of the machine/controller you want to use
// These are typically found in the cpu_map.h file. // These are typically found in the cpu_map.h file.
// See Github repo wiki for more details // See Github repo wiki for more details
#define CPU_MAP_TEST_DRIVE // these are defined in cpu_map.h #define CPU_MAP_ESP32 // these are defined in cpu_map.h
#define N_AXIS 3 // Number of axes defined (valid range: 3 to 6) #define N_AXIS 3 // Number of axes defined (valid range: 3 to 6)
#define VERBOSE_HELP // adds addition help info, but could confuse some senders #define VERBOSE_HELP // adds addition help info, but could confuse some senders
#define GRBL_MSG_LEVEL MSG_LEVEL_INFO // what level of [MSG:....] do you want to see 0=all off
// Serial baud rate // Serial baud rate
#define BAUD_RATE 115200 #define BAUD_RATE 115200
@@ -264,7 +265,6 @@ Some features should not be changed. See notes below.
// Enable using a servo for the Z axis on a pen type machine. // Enable using a servo for the Z axis on a pen type machine.
// You typically should not define a pin for the Z axis in cpu_map.h // You typically should not define a pin for the Z axis in cpu_map.h
// You should configure your settings in servo_pen.h // You should configure your settings in servo_pen.h
// #define USE_PEN_SERVO // this method will be deprecated soon
// #define USE_SERVO_AXES // the new method // #define USE_SERVO_AXES // the new method
// define your servo pin here or in cpu_map.h // define your servo pin here or in cpu_map.h
//#define SERVO_PEN_PIN GPIO_NUM_27 //#define SERVO_PEN_PIN GPIO_NUM_27

View File

@@ -186,7 +186,8 @@ uint8_t gc_execute_line(char *line, uint8_t client)
case 38: case 38:
#ifndef PROBE_PIN //only allow G38 "Probe" commands if a probe pin is defined. #ifndef PROBE_PIN //only allow G38 "Probe" commands if a probe pin is defined.
if (int_value == 38) { if (int_value == 38) {
grbl_send(CLIENT_SERIAL, "[MSG:No probe pin defined!]\r\n"); grbl_msg_sendf(CLIENT_SERIAL, MSG_LEVEL_INFO, "No probe pin defined");
FAIL(STATUS_GCODE_UNSUPPORTED_COMMAND); // [Unsupported G command] FAIL(STATUS_GCODE_UNSUPPORTED_COMMAND); // [Unsupported G command]
} }
#endif #endif
@@ -321,7 +322,7 @@ uint8_t gc_execute_line(char *line, uint8_t client)
case 4: case 4:
case 5: case 5:
#ifndef SPINDLE_PWM_PIN #ifndef SPINDLE_PWM_PIN
grbl_send(CLIENT_SERIAL, "[MSG:No spindle pin defined]\r\n"); grbl_msg_sendf(CLIENT_SERIAL, MSG_LEVEL_INFO, "No spindle pin defined");
#endif #endif
word_bit = MODAL_GROUP_M7; word_bit = MODAL_GROUP_M7;
switch(int_value) { switch(int_value) {
@@ -476,7 +477,7 @@ uint8_t gc_execute_line(char *line, uint8_t client)
if(value > MAX_TOOL_NUMBER) { if(value > MAX_TOOL_NUMBER) {
FAIL(STATUS_GCODE_MAX_VALUE_EXCEEDED); FAIL(STATUS_GCODE_MAX_VALUE_EXCEEDED);
} }
grbl_sendf(CLIENT_ALL, "[MSG:Tool No: %d]\r\n", int_value); grbl_msg_sendf(CLIENT_SERIAL, MSG_LEVEL_INFO, "Tool No: %d", int_value);
gc_state.tool = int_value; gc_state.tool = int_value;
break; break;
case 'X': case 'X':

View File

@@ -20,7 +20,7 @@
// Grbl versioning system // Grbl versioning system
#define GRBL_VERSION "1.1f" #define GRBL_VERSION "1.1f"
#define GRBL_VERSION_BUILD "20200206" #define GRBL_VERSION_BUILD "20200207"
//#include <sdkconfig.h> //#include <sdkconfig.h>
#include <Arduino.h> #include <Arduino.h>
@@ -78,7 +78,6 @@
#endif #endif
#endif #endif
#include "servo_pen.h"
#include "solenoid_pen.h" #include "solenoid_pen.h"
#ifdef USE_SERVO_AXES #ifdef USE_SERVO_AXES

View File

@@ -398,9 +398,7 @@ uint8_t limits_get_state()
#ifdef C_LIMIT_PIN #ifdef C_LIMIT_PIN
pin += (digitalRead(C_LIMIT_PIN) << C_AXIS); pin += (digitalRead(C_LIMIT_PIN) << C_AXIS);
#endif #endif
//grbl_sendf(CLIENT_SERIAL, "[MSG: Limit pins %d]\r\n", pin);
#ifdef INVERT_LIMIT_PIN_MASK // not normally used..unless you have both normal and inverted switches #ifdef INVERT_LIMIT_PIN_MASK // not normally used..unless you have both normal and inverted switches
pin ^= INVERT_LIMIT_PIN_MASK; pin ^= INVERT_LIMIT_PIN_MASK;
@@ -408,9 +406,7 @@ uint8_t limits_get_state()
if (bit_istrue(settings.flags,BITFLAG_INVERT_LIMIT_PINS)) { if (bit_istrue(settings.flags,BITFLAG_INVERT_LIMIT_PINS)) {
pin ^= LIMIT_MASK; pin ^= LIMIT_MASK;
} }
//grbl_sendf(CLIENT_SERIAL, "[MSG: Limit Inverted %d]\r\n", pin);
if (pin) { if (pin) {
uint8_t idx; uint8_t idx;
@@ -419,9 +415,7 @@ uint8_t limits_get_state()
limit_state |= (1 << idx); limit_state |= (1 << idx);
} }
} }
} }
//grbl_sendf(CLIENT_SERIAL, "[MSG: Limit State %d]\r\n", limit_state);
return(limit_state); return(limit_state);
} }

View File

@@ -136,7 +136,7 @@ void Trinamic_Init()
{ {
uint8_t testResult; uint8_t testResult;
grbl_sendf(CLIENT_SERIAL, "[MSG:TMCStepper Init using Library Ver 0x%06x]\r\n", TMCSTEPPER_VERSION); grbl_msg_sendf(CLIENT_SERIAL, MSG_LEVEL_INFO, "TMCStepper Init using Library Ver 0x%06x", TMCSTEPPER_VERSION);
SPI.begin(); SPI.begin();
@@ -243,17 +243,21 @@ void trinamic_change_settings()
} }
void trinamic_test_response(uint8_t result, const char *axis) void trinamic_test_response(uint8_t result, const char *axis)
{ {
grbl_sendf(CLIENT_SERIAL, "[MSG:%s Trinamic driver test ", axis);
if (result) { if (result) {
grbl_sendf(CLIENT_SERIAL, "failed."); grbl_sendf(CLIENT_SERIAL, "failed.");
grbl_msg_sendf(CLIENT_SERIAL, MSG_LEVEL_INFO, "%s Trinamic driver test failed", axis);
switch(result) { switch(result) {
case 1: grbl_sendf(CLIENT_SERIAL, " Check connection]\r\n"); break; case 1:
case 2: grbl_sendf(CLIENT_SERIAL, " Check motor power]\r\n"); break; grbl_msg_sendf(CLIENT_SERIAL, MSG_LEVEL_INFO, "%s Trinamic driver test check connection", axis);
break;
case 2:
grbl_msg_sendf(CLIENT_SERIAL, MSG_LEVEL_INFO, "%s Trinamic driver test check motor power", axis);
break;
} }
} }
else { else {
grbl_sendf(CLIENT_SERIAL, "passed]\r\n"); grbl_msg_sendf(CLIENT_SERIAL, MSG_LEVEL_INFO, "%s Trinamic driver test passed", axis);
} }
} }

View File

@@ -47,15 +47,15 @@
void unipolar_init(){ void unipolar_init(){
#ifdef X_UNIPOLAR #ifdef X_UNIPOLAR
X_Unipolar.init(); X_Unipolar.init();
grbl_send(CLIENT_SERIAL, "[MSG:X Unipolar]\r\n"); grbl_msg_sendf(CLIENT_SERIAL, MSG_LEVEL_INFO, "X unipolar");
#endif #endif
#ifdef Y_UNIPOLAR #ifdef Y_UNIPOLAR
Y_Unipolar.init(); Y_Unipolar.init();
grbl_send(CLIENT_SERIAL, "[MSG:Y Unipolar]\r\n"); grbl_msg_sendf(CLIENT_SERIAL, MSG_LEVEL_INFO, "Y unipolar");
#endif #endif
#ifdef Z_UNIPOLAR #ifdef Z_UNIPOLAR
Z_Unipolar.init(); Z_Unipolar.init();
grbl_send(CLIENT_SERIAL, "[MSG:Z Unipolar]\r\n"); grbl_msg_sendf(CLIENT_SERIAL, MSG_LEVEL_INFO, "Z unipolar");
#endif #endif
} }
@@ -109,9 +109,7 @@
{ {
if (enabled == _enabled) if (enabled == _enabled)
return; // no change return; // no change
//grbl_sendf(CLIENT_SERIAL, "[MSG:Enabled...%d]\r\n", enabled);
_enabled = enabled; _enabled = enabled;
if (!enabled) { if (!enabled) {

View File

@@ -263,8 +263,7 @@ float abs_angle(float ang) {
// Polar coaster has macro buttons, this handles those button pushes. // Polar coaster has macro buttons, this handles those button pushes.
void user_defined_macro(uint8_t index) void user_defined_macro(uint8_t index)
{ {
//grbl_sendf(CLIENT_SERIAL, "[MSG: Macro #%d]\r\n", index);
switch (index) { switch (index) {
#ifdef MACRO_BUTTON_0_PIN #ifdef MACRO_BUTTON_0_PIN
case CONTROL_PIN_INDEX_MACRO_0: case CONTROL_PIN_INDEX_MACRO_0:

View File

@@ -111,7 +111,6 @@ void protocol_main_loop()
for (client = 0; client < CLIENT_COUNT; client++) for (client = 0; client < CLIENT_COUNT; client++)
{ {
while((c = serial_read(client)) != SERIAL_NO_DATA) { while((c = serial_read(client)) != SERIAL_NO_DATA) {
//grbl_sendf(CLIENT_SERIAL, "[MSG:ptcl read...%d %d]\r\n", c, client);
if ((c == '\n') || (c == '\r')) { // End of line reached if ((c == '\n') || (c == '\r')) { // End of line reached
protocol_execute_realtime(); // Runtime command check point. protocol_execute_realtime(); // Runtime command check point.
@@ -125,7 +124,6 @@ void protocol_main_loop()
// Direct and execute one line of formatted input, and report status of execution. // Direct and execute one line of formatted input, and report status of execution.
if (line_flags & LINE_FLAG_OVERFLOW) { if (line_flags & LINE_FLAG_OVERFLOW) {
// Report line overflow error. // Report line overflow error.
//grbl_sendf(client, "[MSG:exec gcode %s %d]\r\n", line, char_counter);
report_status_message(STATUS_OVERFLOW, client); report_status_message(STATUS_OVERFLOW, client);
} else if (line[0] == 0) { } else if (line[0] == 0) {
// Empty or comment line. For syncing purposes. // Empty or comment line. For syncing purposes.
@@ -141,13 +139,12 @@ void protocol_main_loop()
if (!COMMANDS::execute_internal_command (cmd, cmd_params, LEVEL_GUEST, &espresponse)) { if (!COMMANDS::execute_internal_command (cmd, cmd_params, LEVEL_GUEST, &espresponse)) {
report_status_message(STATUS_GCODE_UNSUPPORTED_COMMAND, CLIENT_ALL); report_status_message(STATUS_GCODE_UNSUPPORTED_COMMAND, CLIENT_ALL);
} }
} else grbl_sendf(client, "[MSG: Unknow Command...%s]\r\n", line); } else grbl_msg_sendf(CLIENT_SERIAL, MSG_LEVEL_INFO, "Unknow Command...%s", line);
} else if (sys.state & (STATE_ALARM | STATE_JOG)) { } else if (sys.state & (STATE_ALARM | STATE_JOG)) {
// Everything else is gcode. Block if in alarm or jog mode. // Everything else is gcode. Block if in alarm or jog mode.
report_status_message(STATUS_SYSTEM_GC_LOCK, client); report_status_message(STATUS_SYSTEM_GC_LOCK, client);
} else { } else {
// Parse and execute g-code block. // Parse and execute g-code block
//grbl_sendf(client, "[MSG:exec gcode %s]\r\n", line);
report_status_message(gc_execute_line(line, client), client); report_status_message(gc_execute_line(line, client), client);
} }

View File

@@ -103,6 +103,32 @@ void grbl_sendf(uint8_t client, const char *format, ...)
delete[] temp; delete[] temp;
} }
} }
// Use to send [MSG:xxxx] Type messages. The level allows messages to be easily suppressed
void grbl_msg_sendf(uint8_t client, uint8_t level, const char *format, ...) {
if (client == CLIENT_INPUT) return;
if (level > GRBL_MSG_LEVEL) 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_sendf(client, "[MSG:%s]\r\n", temp);
va_end(arg);
if(len > 64){
delete[] temp;
}
}
//function to notify //function to notify
void grbl_notify(const char *title, const char *msg){ void grbl_notify(const char *title, const char *msg){
@@ -234,31 +260,33 @@ void report_feedback_message(uint8_t message_code) // OK to send to all clients
{ {
switch(message_code) { switch(message_code) {
case MESSAGE_CRITICAL_EVENT: case MESSAGE_CRITICAL_EVENT:
grbl_send(CLIENT_ALL,"[MSG:Reset to continue]\r\n"); break; grbl_msg_sendf(CLIENT_SERIAL, MSG_LEVEL_INFO, "Reset to continue"); break;
case MESSAGE_ALARM_LOCK: case MESSAGE_ALARM_LOCK:
grbl_send(CLIENT_ALL, "[MSG:'$H'|'$X' to unlock]\r\n"); break; grbl_msg_sendf(CLIENT_SERIAL, MSG_LEVEL_INFO, "'$H'|'$X' to unlock"); break;
case MESSAGE_ALARM_UNLOCK: case MESSAGE_ALARM_UNLOCK:
grbl_send(CLIENT_ALL, "[MSG:Caution: Unlocked]\r\n"); break; grbl_msg_sendf(CLIENT_SERIAL, MSG_LEVEL_INFO, "Caution: Unlocked"); break;
case MESSAGE_ENABLED: case MESSAGE_ENABLED:
grbl_send(CLIENT_ALL, "[MSG:Enabled]\r\n"); break; grbl_msg_sendf(CLIENT_SERIAL, MSG_LEVEL_INFO, "Enabled"); break;
case MESSAGE_DISABLED: case MESSAGE_DISABLED:
grbl_send(CLIENT_ALL, "[MSG:Disabled]\r\n"); break; grbl_msg_sendf(CLIENT_SERIAL, MSG_LEVEL_INFO, "Disabled"); break;
case MESSAGE_SAFETY_DOOR_AJAR: case MESSAGE_SAFETY_DOOR_AJAR:
grbl_send(CLIENT_ALL, "[MSG:Check Door]\r\n"); break; grbl_msg_sendf(CLIENT_SERIAL, MSG_LEVEL_INFO, "Check door"); break;
case MESSAGE_CHECK_LIMITS: case MESSAGE_CHECK_LIMITS:
grbl_send(CLIENT_ALL, "[MSG:Check Limits]\r\n"); break; grbl_msg_sendf(CLIENT_SERIAL, MSG_LEVEL_INFO, "Check limits"); break;
case MESSAGE_PROGRAM_END: case MESSAGE_PROGRAM_END:
grbl_send(CLIENT_ALL, "[MSG:Pgm End]\r\n"); break; grbl_msg_sendf(CLIENT_SERIAL, MSG_LEVEL_INFO, "Program End"); break;
case MESSAGE_RESTORE_DEFAULTS: case MESSAGE_RESTORE_DEFAULTS:
grbl_send(CLIENT_ALL, "[MSG:Restoring defaults]\r\n"); break; grbl_msg_sendf(CLIENT_SERIAL, MSG_LEVEL_INFO, "Restoring defaults"); break;
case MESSAGE_SPINDLE_RESTORE: case MESSAGE_SPINDLE_RESTORE:
grbl_send(CLIENT_ALL, "[MSG:Restoring spindle]\r\n"); break; grbl_msg_sendf(CLIENT_SERIAL, MSG_LEVEL_INFO, "Restoring spindle");; break;
case MESSAGE_SLEEP_MODE: case MESSAGE_SLEEP_MODE:
grbl_send(CLIENT_ALL, "[MSG:Sleeping]\r\n"); break; grbl_msg_sendf(CLIENT_SERIAL, MSG_LEVEL_INFO, "Sleeping"); break;
#ifdef ENABLE_SD_CARD #ifdef ENABLE_SD_CARD
case MESSAGE_SD_FILE_QUIT: case MESSAGE_SD_FILE_QUIT:
grbl_notifyf("SD print canceled", "Reset during SD file at line: %d", sd_get_current_line_number()); grbl_notifyf("SD print canceled", "Reset during SD file at line: %d", sd_get_current_line_number());
grbl_sendf(CLIENT_ALL, "[MSG:Reset during SD file at line: %d]\r\n", sd_get_current_line_number()); break; grbl_msg_sendf(CLIENT_SERIAL, MSG_LEVEL_INFO, "Reset during SD file at line: %d", sd_get_current_line_number);
break;
#endif #endif
} }
} }
@@ -868,8 +896,8 @@ void report_gcode_comment(char *comment) {
msg[index-offset] = comment[index]; msg[index-offset] = comment[index];
index++; index++;
} }
msg[index-offset] = 0; // null terminate msg[index-offset] = 0; // null terminate
grbl_sendf(CLIENT_ALL, "[MSG:GCode Comment %s]\r\n",msg); grbl_msg_sendf(CLIENT_SERIAL, MSG_LEVEL_INFO, "GCode Comment...%s", msg);
} }
} }

View File

@@ -107,9 +107,17 @@
#define CLIENT_ALL 0xFF #define CLIENT_ALL 0xFF
#define CLIENT_COUNT 5 // total number of client types regardless if they are used #define CLIENT_COUNT 5 // total number of client types regardless if they are used
#define MSG_LEVEL_NONE 0 // set GRBL_MSG_LEVEL in config.h to the level you want to see
#define MSG_LEVEL_ERROR 1
#define MSG_LEVEL_WARNING 2
#define MSG_LEVEL_INFO 3
#define MSG_LEVEL_DEBUG 4
#define MSG_LEVEL_VERBOSE 5
// functions to send data to the user. // functions to send data to the user.
void grbl_send(uint8_t client, const char *text); void grbl_send(uint8_t client, const char *text);
void grbl_sendf(uint8_t client, const char *format, ...); void grbl_sendf(uint8_t client, const char *format, ...);
void grbl_msg_sendf(uint8_t client, uint8_t level, const char *format, ...);
//function to notify //function to notify
void grbl_notify(const char *title, const char *msg); void grbl_notify(const char *title, const char *msg);

View File

@@ -49,10 +49,9 @@ static TaskHandle_t servosSyncTaskHandle = 0;
#endif #endif
void init_servos() void init_servos()
{ {
//grbl_send(CLIENT_SERIAL, "[MSG: Init Servos]\r\n");
#ifdef SERVO_X_PIN #ifdef SERVO_X_PIN
grbl_sendf(CLIENT_SERIAL, "[MSG:X Servo range %4.3f to %4.3f]\r\n", SERVO_X_RANGE_MIN, SERVO_X_RANGE_MAX); grbl_msg_sendf(CLIENT_SERIAL, MSG_LEVEL_INFO, "X Servo range %4.3f to %4.3f", SERVO_X_RANGE_MIN, SERVO_X_RANGE_MAX);
X_Servo_Axis.init(); X_Servo_Axis.init();
X_Servo_Axis.set_range(SERVO_X_RANGE_MIN, SERVO_X_RANGE_MAX); X_Servo_Axis.set_range(SERVO_X_RANGE_MIN, SERVO_X_RANGE_MAX);
X_Servo_Axis.set_homing_type(SERVO_HOMING_OFF); X_Servo_Axis.set_homing_type(SERVO_HOMING_OFF);
@@ -60,12 +59,12 @@ void init_servos()
X_Servo_Axis.set_disable_with_steppers(false); X_Servo_Axis.set_disable_with_steppers(false);
#endif #endif
#ifdef SERVO_Y_PIN #ifdef SERVO_Y_PIN
grbl_sendf(CLIENT_SERIAL, "[MSG:Y Servo range %4.3f to %4.3f]\r\n", SERVO_Y_RANGE_MIN, SERVO_Y_RANGE_MAX); grbl_msg_sendf(CLIENT_SERIAL, MSG_LEVEL_INFO, "Y Servo range %4.3f to %4.3f", SERVO_Y_RANGE_MIN, SERVO_Y_RANGE_MAX);
Y_Servo_Axis.init(); Y_Servo_Axis.init();
Y_Servo_Axis.set_range(SERVO_Y_RANGE_MIN, SERVO_Y_RANGE_MAX); Y_Servo_Axis.set_range(SERVO_Y_RANGE_MIN, SERVO_Y_RANGE_MAX);
#endif #endif
#ifdef SERVO_Z_PIN #ifdef SERVO_Z_PIN
grbl_sendf(CLIENT_SERIAL, "[MSG:Z Servo range %4.3f to %4.3f]\r\n", SERVO_Z_RANGE_MIN, SERVO_Z_RANGE_MAX); grbl_msg_sendf(CLIENT_SERIAL, MSG_LEVEL_INFO, "Z Servo range %4.3f to %4.3f", SERVO_Z_RANGE_MIN, SERVO_Z_RANGE_MAX);
Z_Servo_Axis.init(); Z_Servo_Axis.init();
Z_Servo_Axis.set_range(SERVO_Z_RANGE_MIN, SERVO_Z_RANGE_MAX); Z_Servo_Axis.set_range(SERVO_Z_RANGE_MIN, SERVO_Z_RANGE_MAX);
#ifdef SERVO_Z_HOMING_TYPE #ifdef SERVO_Z_HOMING_TYPE
@@ -80,7 +79,7 @@ void init_servos()
#endif #endif
#ifdef SERVO_A_PIN #ifdef SERVO_A_PIN
grbl_sendf(CLIENT_SERIAL, "[MSG:A Servo range %4.3f to %4.3f]\r\n", SERVO_A_RANGE_MIN, SERVO_A_RANGE_MAX); grbl_msg_sendf(CLIENT_SERIAL, MSG_LEVEL_INFO, "A Servo range %4.3f to %4.3f", SERVO_A_RANGE_MIN, SERVO_A_RANGE_MAX);
A_Servo_Axis.init(); A_Servo_Axis.init();
A_Servo_Axis.set_range(SERVO_A_RANGE_MIN, SERVO_A_RANGE_MAX); A_Servo_Axis.set_range(SERVO_A_RANGE_MIN, SERVO_A_RANGE_MAX);
A_Servo_Axis.set_homing_type(SERVO_HOMING_OFF); A_Servo_Axis.set_homing_type(SERVO_HOMING_OFF);
@@ -88,12 +87,12 @@ void init_servos()
A_Servo_Axis.set_disable_with_steppers(false); A_Servo_Axis.set_disable_with_steppers(false);
#endif #endif
#ifdef SERVO_B_PIN #ifdef SERVO_B_PIN
grbl_sendf(CLIENT_SERIAL, "[MSG:B Servo range %4.3f to %4.3f]\r\n", SERVO_B_RANGE_MIN, SERVO_B_RANGE_MAX); grbl_msg_sendf(CLIENT_SERIAL, MSG_LEVEL_INFO, "B Servo range %4.3f to %4.3f", SERVO_B_RANGE_MIN, SERVO_B_RANGE_MAX);
B_Servo_Axis.init(); B_Servo_Axis.init();
B_Servo_Axis.set_range(SERVO_B_RANGE_MIN, SERVO_B_RANGE_MAX); B_Servo_Axis.set_range(SERVO_B_RANGE_MIN, SERVO_B_RANGE_MAX);
#endif #endif
#ifdef SERVO_C_PIN #ifdef SERVO_C_PIN
grbl_sendf(CLIENT_SERIAL, "[MSG:C Servo range %4.3f to %4.3f]\r\n", SERVO_C_RANGE_MIN, SERVO_C_RANGE_MAX); grbl_msg_sendf(CLIENT_SERIAL, MSG_LEVEL_INFO, "C Servo range %4.3f to %4.3f", SERVO_C_RANGE_MIN, SERVO_C_RANGE_MAX);
C_Servo_Axis.init(); C_Servo_Axis.init();
C_Servo_Axis.set_range(SERVO_C_RANGE_MIN, SERVO_C_RANGE_MAX); C_Servo_Axis.set_range(SERVO_C_RANGE_MIN, SERVO_C_RANGE_MAX);
//C_Servo_Axis.set_homing_type(SERVO_HOMING_TARGET); //C_Servo_Axis.set_homing_type(SERVO_HOMING_TARGET);
@@ -276,7 +275,7 @@ bool ServoAxis::_cal_is_valid()
if ( (settings.steps_per_mm[_axis] < SERVO_CAL_MIN) || (settings.steps_per_mm[_axis] > SERVO_CAL_MAX) ) { if ( (settings.steps_per_mm[_axis] < SERVO_CAL_MIN) || (settings.steps_per_mm[_axis] > SERVO_CAL_MAX) ) {
if (_showError) { if (_showError) {
grbl_sendf(CLIENT_SERIAL, "[MSG:Servo calibration ($10%d) value error. Reset to 100]\r\n", _axis); grbl_msg_sendf(CLIENT_SERIAL, MSG_LEVEL_INFO, "Servo calibration ($10%d) value error. Reset to 100", _axis);
settings.steps_per_mm[_axis] = 100; settings.steps_per_mm[_axis] = 100;
write_global_settings(); write_global_settings();
} }
@@ -286,7 +285,7 @@ bool ServoAxis::_cal_is_valid()
// Note: Max travel is set positive via $$, but stored as a negative number // Note: Max travel is set positive via $$, but stored as a negative number
if ( (settings.max_travel[_axis] < -SERVO_CAL_MAX) || (settings.max_travel[_axis] > -SERVO_CAL_MIN) ) { if ( (settings.max_travel[_axis] < -SERVO_CAL_MAX) || (settings.max_travel[_axis] > -SERVO_CAL_MIN) ) {
if (_showError) { if (_showError) {
grbl_sendf(CLIENT_SERIAL, "[MSG:Servo calibration ($13%d) value error. Reset to 100]\r\n", _axis); grbl_msg_sendf(CLIENT_SERIAL, MSG_LEVEL_INFO, "Servo calibration ($13%d) value error. Reset to 100", _axis);
settings.max_travel[_axis] = -100; settings.max_travel[_axis] = -100;
write_global_settings(); write_global_settings();
} }
@@ -311,8 +310,8 @@ void ServoAxis::set_range(float min, float max) {
_position_min = min; _position_min = min;
_position_max = max; _position_max = max;
} }
else { else {
grbl_send(CLIENT_SERIAL, "[MSG:Error setting range. Min not smaller than max]\r\n"); grbl_msg_sendf(CLIENT_SERIAL, MSG_LEVEL_INFO, "Error setting range. Min not smaller than max");
} }
} }

View File

@@ -1,176 +0,0 @@
/*
servo_pen.cpp
Part of Grbl_ESP32
copyright (c) 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 <http://www.gnu.org/licenses/>.
*/
#include "grbl.h"
#ifdef USE_PEN_SERVO
static TaskHandle_t servoSyncTaskHandle = 0;
// used to delay turn on
bool servo_pen_enable = false;
void servo_init()
{
grbl_send(CLIENT_SERIAL, "[MSG:Servo Pen Mode]\r\n"); // startup message
//validate_servo_settings(true); // display any calibration errors
// Debug stuff
//grbl_sendf(CLIENT_SERIAL, "[MSG:Servo max,min pulse times %.4f sec,%.4f sec]\r\n", SERVO_MAX_PULSE_SEC, SERVO_MIN_PULSE_SEC);
//grbl_sendf(CLIENT_SERIAL, "[MSG:Servo max,min pulse counts %d,%d]\r\n", SERVO_MAX_PULSE, SERVO_MIN_PULSE);
validate_servo_settings(true); // will print errors
// debug stuff
servo_pen_enable = false; // start delay has not completed yet.
// setup PWM channel
ledcSetup(SERVO_PEN_CHANNEL_NUM, SERVO_PULSE_FREQ, SERVO_PULSE_RES_BITS);
ledcAttachPin(SERVO_PEN_PIN, SERVO_PEN_CHANNEL_NUM);
servo_disable(); // start it it off
// setup a task that will calculate the determine and set the servo position
xTaskCreatePinnedToCore( servoSyncTask, // task
"servoSyncTask", // name for task
4096, // size of task stack
NULL, // parameters
1, // priority
&servoSyncTaskHandle,
0 // core
);
}
// turn off the PWM (0 duty) to prevent servo jitter when not in use.
void servo_disable()
{
ledcWrite(SERVO_PEN_CHANNEL_NUM, 0);
}
// Grbl settings are used to calibrate the servo positions
// They work on a percentage, so a value of 100 (100%) applies no calibration
// Values outside a reasonable range can cause errors, so this function checks
// that they are within a reasonable range
bool validate_servo_settings(bool verbose) // make sure the settings are reasonable..otherwise reset the settings to default
{
bool settingsOK = true;
if ( (settings.steps_per_mm[Z_AXIS] < SERVO_CAL_MIN) || (settings.steps_per_mm[Z_AXIS] > SERVO_CAL_MAX) ) {
if (verbose) {
grbl_sendf(CLIENT_SERIAL, "[MSG:Servo cal ($102) Error: %4.4f s/b between %.2f and %.2f]\r\n", settings.steps_per_mm[Z_AXIS], SERVO_CAL_MIN, SERVO_CAL_MAX);
}
settingsOK = false;
}
// Note: Max travel is set positive via $$, but stored as a negative number
if ( (settings.max_travel[Z_AXIS] < -SERVO_CAL_MAX) || (settings.max_travel[Z_AXIS] > -SERVO_CAL_MIN) ) {
if (verbose) {
grbl_sendf(CLIENT_SERIAL, "[MSG:Servo cal ($132) Error: %4.4f s/b between %.2f and %.2f]\r\n", -settings.max_travel[Z_AXIS], SERVO_CAL_MIN, SERVO_CAL_MAX);
}
settingsOK = false;
}
return settingsOK;
}
// this is the task
void servoSyncTask(void *pvParameters)
{
//int32_t current_position[N_AXIS]; // copy of current location
//float m_pos[N_AXIS]; // machine position in mm
TickType_t xLastWakeTime;
const TickType_t xServoFrequency = SERVO_TIMER_INT_FREQ; // in ticks (typically ms)
uint16_t servo_delay_counter = 0;
float mpos_z, wpos_z;
float z_offset;
xLastWakeTime = xTaskGetTickCount(); // Initialise the xLastWakeTime variable with the current time.
while(true) { // don't ever return from this or the task dies
if (sys.state != STATE_ALARM) { // don't move until alarm is cleared...typically homing
if (!servo_pen_enable ) {
servo_delay_counter++;
servo_pen_enable = (servo_delay_counter > SERVO_TURNON_DELAY);
} else {
mpos_z = system_convert_axis_steps_to_mpos(sys_position, Z_AXIS); // get the machine Z in mm
z_offset = gc_state.coord_system[Z_AXIS]+gc_state.coord_offset[Z_AXIS]; // get the current z work offset
wpos_z = mpos_z - z_offset; // determine the current work Z
calc_pen_servo(wpos_z); // calculate kinematics and move the servos
}
}
vTaskDelayUntil(&xLastWakeTime, xServoFrequency);
}
}
// calculate and set the PWM value for the servo
void calc_pen_servo(float penZ)
{
uint32_t servo_pen_pulse_len;
float servo_pen_pulse_min, servo_pen_pulse_max;
if (!servo_pen_enable) { // only proceed if startup delay as expired
return;
}
if (validate_servo_settings(false)) { // if calibration settings are OK then apply them
if (bit_istrue(settings.dir_invert_mask,bit(Z_AXIS))) { // this allows the user to change the direction via settings
// Apply a calibration to the minimum position
servo_pen_pulse_max = SERVO_MIN_PULSE * (settings.steps_per_mm[Z_AXIS] / 100.0);
// Apply a calibration to the maximum position
servo_pen_pulse_min = SERVO_MAX_PULSE * (settings.max_travel[Z_AXIS] / -100.0);
}
else {
// Apply a calibration to the minimum position
servo_pen_pulse_min = SERVO_MIN_PULSE * (settings.steps_per_mm[Z_AXIS] / 100.0);
// Apply a calibration to the maximum position
servo_pen_pulse_max = SERVO_MAX_PULSE * (settings.max_travel[Z_AXIS] / -100.0);
}
} else { // use the defaults
if (bit_istrue(settings.dir_invert_mask,bit(Z_AXIS))) { // this allows the user to change the direction via settings
servo_pen_pulse_min = SERVO_MAX_PULSE;
servo_pen_pulse_max = SERVO_MIN_PULSE;
}
else {
servo_pen_pulse_min = SERVO_MIN_PULSE;
servo_pen_pulse_max = SERVO_MAX_PULSE;
}
}
// determine the pulse length
servo_pen_pulse_len = (uint32_t)mapConstrain(penZ, SERVO_PEN_RANGE_MIN_MM, SERVO_PEN_RANGE_MAX_MM, servo_pen_pulse_min, servo_pen_pulse_max );
// skip setting value if it is unchanged
if (ledcRead(SERVO_PEN_CHANNEL_NUM) == servo_pen_pulse_len)
return;
// update the PWM value
// ledcWrite appears to have issues with interrupts, so make this a critical section
portMUX_TYPE myMutex = portMUX_INITIALIZER_UNLOCKED;
portENTER_CRITICAL(&myMutex);
ledcWrite(SERVO_PEN_CHANNEL_NUM, servo_pen_pulse_len);
portEXIT_CRITICAL(&myMutex);
}
#endif

View File

@@ -1,76 +0,0 @@
/*
servo.h
Part of Grbl_ESP32
copyright (c) 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 <http://www.gnu.org/licenses/>.
To use this, uncomment #define USE_PEN_SERVO in config.h
That should be the only change you need at the top level
Everything occurs as a low priority task that syncs the servo with the
current machine position.
*/
// ==== Begin: Things you are likely to change ====================
//#define SERVO_PEN_PIN GPIO_NUM_27 // FYI...you can disable the Z stepper pins (step & dir)
// the pulse lengths for the min and max travel .. (Note: Servo brands vary)
// If the servo goes backward from what you want, flip the values
// Note: this is not necessarily the servos limits (just the travel you want)
#define SERVO_MIN_PULSE_SEC 0.001 // min pulse in seconds
#define SERVO_MAX_PULSE_SEC 0.002 // max pulse in seconds
// Pulse repeat rate (PWM Frequency)
#define SERVO_PULSE_FREQ 50 // 50Hz ...This is a standard analog servo value. Digital ones can repeat faster
// the range of the servo is constrained
// values above or below these will be limited to the min or max
#define SERVO_PEN_RANGE_MIN_MM 0.0 // the minimum z position in mm
#define SERVO_PEN_RANGE_MAX_MM 5.0 // the minimum z position in mm
// ==== End: Things you are likely to change =======================
// Begin: Advanced settings
#define SERVO_TIMER_NUM 1
#define SERVO_TIMER_INT_FREQ 20 // Hz This is the task frequency
#define SERVO_PEN_CHANNEL_NUM 5
#define SERVO_PULSE_RES_BITS 16 // bits of resolution of PWM (16 is max)
#define SERVO_PULSE_RES_COUNT 65535 // see above TODO...do the math here 2^SERVO_PULSE_RES_BITS
// A way to reduce the turn on current
#define SERVO_TURNON_DELAY SERVO_TIMER_INT_FREQ*3 // Wait this many task counts to turn on servo
#define SERVO_TIME_PER_BIT ((1.0 / (float)SERVO_PULSE_FREQ) / ((float)SERVO_PULSE_RES_COUNT) ) // seconds
#define SERVO_MIN_PULSE (uint16_t)(SERVO_MIN_PULSE_SEC / SERVO_TIME_PER_BIT) // in timer counts
#define SERVO_MAX_PULSE (uint16_t)(SERVO_MAX_PULSE_SEC / SERVO_TIME_PER_BIT) // in timer counts
#define SERVO_CAL_MIN 20.0 // Percent: the minimum allowable calibration value
#define SERVO_CAL_MAX 180.0 // Percent: the maximum allowable calibration value
#ifndef servo_h
#define servo_h
void servo_init();
void servo_disable();
bool validate_servo_settings(bool verbose);
void servoSyncTask(void *pvParameters);
void calc_pen_servo(float penZ);
#endif

View File

@@ -461,6 +461,6 @@ void settings_spi_driver_init() {
#ifdef USE_TRINAMIC #ifdef USE_TRINAMIC
trinamic_change_settings(); trinamic_change_settings();
#else #else
grbl_send(CLIENT_ALL, "[MSG: No SPI drivers setup]\r\n"); grbl_msg_sendf(CLIENT_SERIAL, MSG_LEVEL_INFO, "No SPI drivers setup");
#endif #endif
} }

View File

@@ -34,18 +34,18 @@ void spindle_init()
#ifdef SPINDLE_PWM_PIN #ifdef SPINDLE_PWM_PIN
#ifdef INVERT_SPINDLE_PWM #ifdef INVERT_SPINDLE_PWM
grbl_send(CLIENT_SERIAL, "[MSG: INVERT_SPINDLE_PWM]\r\n"); grbl_msg_sendf(CLIENT_SERIAL, MSG_LEVEL_INFO, "INVERT_SPINDLE_PWM");
#endif #endif
#ifdef INVERT_SPINDLE_ENABLE_PIN #ifdef INVERT_SPINDLE_ENABLE_PIN
grbl_send(CLIENT_SERIAL, "[MSG: INVERT_SPINDLE_ENABLE_PIN]\r\n"); grbl_msg_sendf(CLIENT_SERIAL, MSG_LEVEL_INFO, "INVERT_SPINDLE_ENABLE_PIN");
#endif #endif
// determine how many PWM counts are in eqach PWM cycle // determine how many PWM counts are in eqach PWM cycle
spindle_pwm_period = ((1<<SPINDLE_PWM_BIT_PRECISION) -1); spindle_pwm_period = ((1<<SPINDLE_PWM_BIT_PRECISION) -1);
if (settings.spindle_pwm_min_value > settings.spindle_pwm_min_value) { if (settings.spindle_pwm_min_value > settings.spindle_pwm_min_value) {
grbl_sendf(CLIENT_SERIAL, "[MSG: Warning spindle min pwm is greater than max. Check $35 and $36]\r\n", pwm_gradient); grbl_msg_sendf(CLIENT_SERIAL, MSG_LEVEL_INFO, "Warning spindle min pwm is greater than max. Check $35 and $36");
} }
// pre-caculate some PWM count values // pre-caculate some PWM count values

View File

@@ -445,15 +445,15 @@ void stepper_init()
#ifdef USE_TRINAMIC #ifdef USE_TRINAMIC
Trinamic_Init(); Trinamic_Init();
#endif #endif
grbl_sendf(CLIENT_SERIAL, "[MSG:Axis count %d]\r\n", N_AXIS); grbl_msg_sendf(CLIENT_SERIAL, MSG_LEVEL_INFO, "Axis count %d", N_AXIS);
#ifdef USE_RMT_STEPS #ifdef USE_RMT_STEPS
grbl_send(CLIENT_SERIAL, "[MSG:RMT Steps]\r\n"); grbl_msg_sendf(CLIENT_SERIAL, MSG_LEVEL_INFO, "RMT Steps");
initRMT(); initRMT();
#else #else
grbl_send(CLIENT_SERIAL, "[MSG:Timed Steps]\r\n"); grbl_msg_sendf(CLIENT_SERIAL, MSG_LEVEL_INFO, "Timed Steps");
// make the step pins outputs // make the step pins outputs
#ifdef X_STEP_PIN #ifdef X_STEP_PIN
pinMode(X_STEP_PIN, OUTPUT); pinMode(X_STEP_PIN, OUTPUT);

View File

@@ -47,25 +47,25 @@ void system_ini() // Renamed from system_init() due to conflict with esp32 files
#endif #endif
#ifdef MACRO_BUTTON_0_PIN #ifdef MACRO_BUTTON_0_PIN
grbl_send(CLIENT_SERIAL, "[MSG:Macro Pin 0]\r\n"); grbl_msg_sendf(CLIENT_SERIAL, MSG_LEVEL_INFO, "Macro Pin 0");
pinMode(MACRO_BUTTON_0_PIN, INPUT_PULLUP); pinMode(MACRO_BUTTON_0_PIN, INPUT_PULLUP);
attachInterrupt(digitalPinToInterrupt(MACRO_BUTTON_0_PIN), isr_control_inputs, CHANGE); attachInterrupt(digitalPinToInterrupt(MACRO_BUTTON_0_PIN), isr_control_inputs, CHANGE);
#endif #endif
#ifdef MACRO_BUTTON_1_PIN #ifdef MACRO_BUTTON_1_PIN
grbl_send(CLIENT_SERIAL, "[MSG:Macro Pin 1]\r\n"); grbl_msg_sendf(CLIENT_SERIAL, MSG_LEVEL_INFO, "Macro Pin 1");
pinMode(MACRO_BUTTON_1_PIN, INPUT_PULLUP); pinMode(MACRO_BUTTON_1_PIN, INPUT_PULLUP);
attachInterrupt(digitalPinToInterrupt(MACRO_BUTTON_1_PIN), isr_control_inputs, CHANGE); attachInterrupt(digitalPinToInterrupt(MACRO_BUTTON_1_PIN), isr_control_inputs, CHANGE);
#endif #endif
#ifdef MACRO_BUTTON_2_PIN #ifdef MACRO_BUTTON_2_PIN
grbl_send(CLIENT_SERIAL, "[MSG:Macro Pin 2]\r\n"); grbl_msg_sendf(CLIENT_SERIAL, MSG_LEVEL_INFO, "Macro Pin 2");
pinMode(MACRO_BUTTON_2_PIN, INPUT_PULLUP); pinMode(MACRO_BUTTON_2_PIN, INPUT_PULLUP);
attachInterrupt(digitalPinToInterrupt(MACRO_BUTTON_2_PIN), isr_control_inputs, CHANGE); attachInterrupt(digitalPinToInterrupt(MACRO_BUTTON_2_PIN), isr_control_inputs, CHANGE);
#endif #endif
#ifdef MACRO_BUTTON_3_PIN #ifdef MACRO_BUTTON_3_PIN
grbl_send(CLIENT_SERIAL, "[MSG:Macro Pin 3]\r\n"); grbl_msg_sendf(CLIENT_SERIAL, MSG_LEVEL_INFO, "Macro Pin 3");
pinMode(MACRO_BUTTON_3_PIN, INPUT_PULLUP); pinMode(MACRO_BUTTON_3_PIN, INPUT_PULLUP);
attachInterrupt(digitalPinToInterrupt(MACRO_BUTTON_3_PIN), isr_control_inputs, CHANGE); attachInterrupt(digitalPinToInterrupt(MACRO_BUTTON_3_PIN), isr_control_inputs, CHANGE);
#endif #endif
@@ -544,7 +544,7 @@ uint8_t get_limit_pin_mask(uint8_t axis_idx)
void system_exec_control_pin(uint8_t pin) { void system_exec_control_pin(uint8_t pin) {
if (bit_istrue(pin,CONTROL_PIN_INDEX_RESET)) { if (bit_istrue(pin,CONTROL_PIN_INDEX_RESET)) {
grbl_send(CLIENT_SERIAL, "[MSG:Reset via control pin]\r\n"); // help debug reason for reset grbl_msg_sendf(CLIENT_SERIAL, MSG_LEVEL_INFO, "Reset via control pin");
mc_reset(); mc_reset();
} }
else if (bit_istrue(pin,CONTROL_PIN_INDEX_CYCLE_START)) { else if (bit_istrue(pin,CONTROL_PIN_INDEX_CYCLE_START)) {

View File

@@ -27,3 +27,4 @@ framework = arduino
upload_speed = 512000 upload_speed = 512000
board_build.partitions = min_spiffs.csv board_build.partitions = min_spiffs.csv
monitor_speed = 115200 monitor_speed = 115200
build_flags = -DCORE_DEBUG_LEVEL=0