mirror of
https://github.com/bdring/Grbl_Esp32.git
synced 2025-09-03 11:22:38 +02:00
@@ -19,6 +19,7 @@
|
||||
*/
|
||||
|
||||
#include "grbl.h"
|
||||
#include "WiFi.h"
|
||||
|
||||
// Declare system global variable structure
|
||||
system_t sys;
|
||||
@@ -36,13 +37,18 @@ volatile uint8_t sys_rt_exec_accessory_override; // Global realtime executor bit
|
||||
|
||||
|
||||
void setup() {
|
||||
WiFi.persistent(false);
|
||||
WiFi.disconnect(true);
|
||||
WiFi.enableSTA (false);
|
||||
WiFi.enableAP (false);
|
||||
WiFi.mode (WIFI_OFF);
|
||||
|
||||
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
|
||||
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
|
||||
|
||||
settings_init(); // Load Grbl settings from EEPROM
|
||||
|
@@ -43,7 +43,7 @@ void machine_init()
|
||||
{
|
||||
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
|
||||
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;
|
||||
break;
|
||||
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
|
||||
break;
|
||||
}
|
||||
|
||||
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");
|
||||
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
|
||||
|
||||
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;
|
||||
}
|
||||
|
||||
@@ -259,7 +259,7 @@ void user_tool_change(uint8_t 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) {
|
||||
#ifdef MACRO_BUTTON_0_PIN
|
||||
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");
|
||||
break;
|
||||
#endif
|
||||
|
||||
#ifdef MACRO_BUTTON_1_PIN
|
||||
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();
|
||||
sprintf(gcode_line, "G90G0X%3.2f\r", ATARI_PAPER_WIDTH); // alway return to right side to reduce home travel stalls
|
||||
inputBuffer.push(gcode_line);
|
||||
@@ -299,7 +299,7 @@ void user_defined_macro(uint8_t index)
|
||||
#ifdef MACRO_BUTTON_2_PIN
|
||||
case CONTROL_PIN_INDEX_MACRO_2:
|
||||
// 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("G4P0.1\r"); // sync...forces wait for planner to clear
|
||||
sys_position[Y_AXIS] = 0.0; // reset the Y position
|
||||
@@ -309,7 +309,7 @@ void user_defined_macro(uint8_t index)
|
||||
#endif
|
||||
|
||||
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;
|
||||
}
|
||||
}
|
||||
|
@@ -49,6 +49,7 @@ Some features should not be changed. See notes below.
|
||||
#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 GRBL_MSG_LEVEL MSG_LEVEL_INFO // what level of [MSG:....] do you want to see 0=all off
|
||||
|
||||
// Serial baud rate
|
||||
#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.
|
||||
// You typically should not define a pin for the Z axis in cpu_map.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 your servo pin here or in cpu_map.h
|
||||
//#define SERVO_PEN_PIN GPIO_NUM_27
|
||||
|
@@ -186,7 +186,8 @@ uint8_t gc_execute_line(char *line, uint8_t client)
|
||||
case 38:
|
||||
#ifndef PROBE_PIN //only allow G38 "Probe" commands if a probe pin is defined.
|
||||
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]
|
||||
}
|
||||
#endif
|
||||
@@ -321,7 +322,7 @@ uint8_t gc_execute_line(char *line, uint8_t client)
|
||||
case 4:
|
||||
case 5:
|
||||
#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
|
||||
word_bit = MODAL_GROUP_M7;
|
||||
switch(int_value) {
|
||||
@@ -476,7 +477,7 @@ uint8_t gc_execute_line(char *line, uint8_t client)
|
||||
if(value > MAX_TOOL_NUMBER) {
|
||||
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;
|
||||
break;
|
||||
case 'X':
|
||||
|
@@ -20,7 +20,7 @@
|
||||
|
||||
// Grbl versioning system
|
||||
#define GRBL_VERSION "1.1f"
|
||||
#define GRBL_VERSION_BUILD "20200202"
|
||||
#define GRBL_VERSION_BUILD "20200208"
|
||||
|
||||
//#include <sdkconfig.h>
|
||||
#include <Arduino.h>
|
||||
@@ -78,7 +78,6 @@
|
||||
#endif
|
||||
#endif
|
||||
|
||||
#include "servo_pen.h"
|
||||
#include "solenoid_pen.h"
|
||||
|
||||
#ifdef USE_SERVO_AXES
|
||||
|
@@ -400,8 +400,6 @@ uint8_t limits_get_state()
|
||||
pin += (digitalRead(C_LIMIT_PIN) << C_AXIS);
|
||||
#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
|
||||
pin ^= INVERT_LIMIT_PIN_MASK;
|
||||
#endif
|
||||
@@ -410,8 +408,6 @@ uint8_t limits_get_state()
|
||||
pin ^= LIMIT_MASK;
|
||||
}
|
||||
|
||||
//grbl_sendf(CLIENT_SERIAL, "[MSG: Limit Inverted %d]\r\n", pin);
|
||||
|
||||
if (pin) {
|
||||
uint8_t idx;
|
||||
for (idx=0; idx<N_AXIS; idx++) {
|
||||
@@ -421,8 +417,6 @@ uint8_t limits_get_state()
|
||||
}
|
||||
}
|
||||
|
||||
//grbl_sendf(CLIENT_SERIAL, "[MSG: Limit State %d]\r\n", limit_state);
|
||||
|
||||
return(limit_state);
|
||||
}
|
||||
|
||||
|
@@ -136,7 +136,7 @@ void Trinamic_Init()
|
||||
{
|
||||
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();
|
||||
|
||||
@@ -244,16 +244,20 @@ void trinamic_change_settings()
|
||||
|
||||
void trinamic_test_response(uint8_t result, const char *axis)
|
||||
{
|
||||
grbl_sendf(CLIENT_SERIAL, "[MSG:%s Trinamic driver test ", axis);
|
||||
if (result) {
|
||||
grbl_sendf(CLIENT_SERIAL, "failed.");
|
||||
grbl_msg_sendf(CLIENT_SERIAL, MSG_LEVEL_INFO, "%s Trinamic driver test failed", axis);
|
||||
switch(result) {
|
||||
case 1: grbl_sendf(CLIENT_SERIAL, " Check connection]\r\n"); break;
|
||||
case 2: grbl_sendf(CLIENT_SERIAL, " Check motor power]\r\n"); break;
|
||||
case 1:
|
||||
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 {
|
||||
grbl_sendf(CLIENT_SERIAL, "passed]\r\n");
|
||||
grbl_msg_sendf(CLIENT_SERIAL, MSG_LEVEL_INFO, "%s Trinamic driver test passed", axis);
|
||||
}
|
||||
}
|
||||
|
||||
|
@@ -47,15 +47,15 @@
|
||||
void unipolar_init(){
|
||||
#ifdef X_UNIPOLAR
|
||||
X_Unipolar.init();
|
||||
grbl_send(CLIENT_SERIAL, "[MSG:X Unipolar]\r\n");
|
||||
grbl_msg_sendf(CLIENT_SERIAL, MSG_LEVEL_INFO, "X unipolar");
|
||||
#endif
|
||||
#ifdef Y_UNIPOLAR
|
||||
Y_Unipolar.init();
|
||||
grbl_send(CLIENT_SERIAL, "[MSG:Y Unipolar]\r\n");
|
||||
grbl_msg_sendf(CLIENT_SERIAL, MSG_LEVEL_INFO, "Y unipolar");
|
||||
#endif
|
||||
#ifdef Z_UNIPOLAR
|
||||
Z_Unipolar.init();
|
||||
grbl_send(CLIENT_SERIAL, "[MSG:Z Unipolar]\r\n");
|
||||
grbl_msg_sendf(CLIENT_SERIAL, MSG_LEVEL_INFO, "Z unipolar");
|
||||
#endif
|
||||
}
|
||||
|
||||
@@ -110,8 +110,6 @@
|
||||
if (enabled == _enabled)
|
||||
return; // no change
|
||||
|
||||
//grbl_sendf(CLIENT_SERIAL, "[MSG:Enabled...%d]\r\n", enabled);
|
||||
|
||||
_enabled = enabled;
|
||||
|
||||
if (!enabled) {
|
||||
|
@@ -54,11 +54,26 @@ int InputBuffer::available(){
|
||||
return _RXbufferSize;
|
||||
}
|
||||
|
||||
int InputBuffer::availableforwrite(){
|
||||
return (RXBUFFERSIZE - _RXbufferSize);
|
||||
}
|
||||
|
||||
size_t InputBuffer::write(uint8_t c)
|
||||
{
|
||||
//No need currently
|
||||
//keep for compatibility
|
||||
if ((1 + _RXbufferSize) <= RXBUFFERSIZE){
|
||||
int current = _RXbufferpos + _RXbufferSize;
|
||||
if (current > RXBUFFERSIZE)
|
||||
current = current - RXBUFFERSIZE;
|
||||
|
||||
if (current > (RXBUFFERSIZE-1))
|
||||
current = 0;
|
||||
_RXbuffer[current] = c;
|
||||
current ++;
|
||||
|
||||
_RXbufferSize+=1;
|
||||
return 1;
|
||||
}
|
||||
return 0;
|
||||
}
|
||||
|
||||
size_t InputBuffer::write(const uint8_t *buffer, size_t size)
|
||||
|
@@ -54,6 +54,7 @@ class InputBuffer: public Print{
|
||||
void begin();
|
||||
void end();
|
||||
int available();
|
||||
int availableforwrite();
|
||||
int peek(void);
|
||||
int read(void);
|
||||
bool push (const char * data);
|
||||
|
@@ -264,7 +264,6 @@ float abs_angle(float ang) {
|
||||
// Polar coaster has macro buttons, this handles those button pushes.
|
||||
void user_defined_macro(uint8_t index)
|
||||
{
|
||||
//grbl_sendf(CLIENT_SERIAL, "[MSG: Macro #%d]\r\n", index);
|
||||
switch (index) {
|
||||
#ifdef MACRO_BUTTON_0_PIN
|
||||
case CONTROL_PIN_INDEX_MACRO_0:
|
||||
|
@@ -85,7 +85,7 @@ void protocol_main_loop()
|
||||
|
||||
for (;;) {
|
||||
|
||||
// serialCheck(); // un comment this if you do this here rather than in a separate task
|
||||
|
||||
|
||||
#ifdef ENABLE_SD_CARD
|
||||
if (SD_ready_next) {
|
||||
@@ -108,7 +108,7 @@ void protocol_main_loop()
|
||||
// initial filtering by removing spaces and comments and capitalizing all letters.
|
||||
|
||||
uint8_t client = CLIENT_SERIAL;
|
||||
for (client = 0; client <= CLIENT_COUNT; client++)
|
||||
for (client = 0; client < CLIENT_COUNT; client++)
|
||||
{
|
||||
while((c = serial_read(client)) != SERIAL_NO_DATA) {
|
||||
if ((c == '\n') || (c == '\r')) { // End of line reached
|
||||
@@ -139,12 +139,12 @@ void protocol_main_loop()
|
||||
if (!COMMANDS::execute_internal_command (cmd, cmd_params, LEVEL_GUEST, &espresponse)) {
|
||||
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)) {
|
||||
// Everything else is gcode. Block if in alarm or jog mode.
|
||||
report_status_message(STATUS_SYSTEM_GC_LOCK, client);
|
||||
} else {
|
||||
// Parse and execute g-code block.
|
||||
// Parse and execute g-code block
|
||||
report_status_message(gc_execute_line(line, client), client);
|
||||
}
|
||||
|
||||
|
@@ -103,6 +103,32 @@ void grbl_sendf(uint8_t client, const char *format, ...)
|
||||
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
|
||||
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) {
|
||||
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:
|
||||
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:
|
||||
grbl_send(CLIENT_ALL, "[MSG:Caution: Unlocked]\r\n"); break;
|
||||
grbl_msg_sendf(CLIENT_SERIAL, MSG_LEVEL_INFO, "Caution: Unlocked"); break;
|
||||
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:
|
||||
grbl_send(CLIENT_ALL, "[MSG:Disabled]\r\n"); break;
|
||||
grbl_msg_sendf(CLIENT_SERIAL, MSG_LEVEL_INFO, "Disabled"); break;
|
||||
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:
|
||||
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:
|
||||
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:
|
||||
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:
|
||||
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:
|
||||
grbl_send(CLIENT_ALL, "[MSG:Sleeping]\r\n"); break;
|
||||
grbl_msg_sendf(CLIENT_SERIAL, MSG_LEVEL_INFO, "Sleeping"); break;
|
||||
#ifdef ENABLE_SD_CARD
|
||||
case MESSAGE_SD_FILE_QUIT:
|
||||
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
|
||||
}
|
||||
}
|
||||
@@ -288,8 +316,6 @@ void report_grbl_settings(uint8_t client, uint8_t show_extended) {
|
||||
show_extended = true;
|
||||
#endif
|
||||
|
||||
grbl_sendf(CLIENT_SERIAL, "[MSG:Extended %d]\r\n", show_extended);
|
||||
|
||||
rpt[0] = '\0';
|
||||
|
||||
sprintf(setting, "$0=%d\r\n", settings.pulse_microseconds); strcat(rpt, setting);
|
||||
@@ -872,6 +898,6 @@ void report_gcode_comment(char *comment) {
|
||||
}
|
||||
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);
|
||||
}
|
||||
}
|
@@ -99,17 +99,25 @@
|
||||
#define MESSAGE_SLEEP_MODE 11
|
||||
#define MESSAGE_SD_FILE_QUIT 60 // mc_reset was called during an SD job
|
||||
|
||||
#define CLIENT_SERIAL 1
|
||||
#define CLIENT_BT 2
|
||||
#define CLIENT_WEBUI 3
|
||||
#define CLIENT_TELNET 4
|
||||
#define CLIENT_INPUT 5
|
||||
#define CLIENT_SERIAL 0
|
||||
#define CLIENT_BT 1
|
||||
#define CLIENT_WEBUI 2
|
||||
#define CLIENT_TELNET 3
|
||||
#define CLIENT_INPUT 4
|
||||
#define CLIENT_ALL 0xFF
|
||||
#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.
|
||||
void grbl_send(uint8_t client, const char *text);
|
||||
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
|
||||
void grbl_notify(const char *title, const char *msg);
|
||||
|
@@ -16,35 +16,69 @@
|
||||
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/>.
|
||||
|
||||
What is going on here?
|
||||
|
||||
Original Grbl only supports communication via serial port. That is why this
|
||||
file is call serial.cpp. Grbl_ESP32 supports many "clients".
|
||||
|
||||
Clients are sources of commands like the serial port or a bluetooth connection.
|
||||
Multiple clients can be active at a time. If a client asks for status, only the client will
|
||||
receive the reply to the command.
|
||||
|
||||
The serial port acts as the debugging port because it is always on and does not
|
||||
need to be reconnected after reboot. Messages about the configuration and other events
|
||||
are sent to the serial port automatically, without a request command. These are in the
|
||||
[MSG: xxxxxx] format. Gcode senders are should be OK with this because Grbl has always
|
||||
send some messages like this.
|
||||
|
||||
Important: It is up user that the clients play well together. Ideally, if one client
|
||||
is sending the gcode, the others should just be doing status, feedhold, etc.
|
||||
|
||||
Clients send gcode, grbl commands ($$, [ESP...], etc) and realtime commands (?,!.~, etc)
|
||||
Gcode and Grbl commands are a string of printable characters followed by a '\r' or '\n'
|
||||
Realtime commands are single characters with no '\r' or '\n'
|
||||
|
||||
After sending a gcode or grbl command, you must wait for an OK to send another.
|
||||
This is because only a certain number of commands can be buffered at a time.
|
||||
Grbl will tell you when it is ready for another one with the OK.
|
||||
|
||||
Realtime commands can be sent at any time and will acted upon very quickly.
|
||||
Realtime commands can be anywhere in the stream.
|
||||
|
||||
To allow the realtime commands to be randomly mixed in the stream of data, we
|
||||
read all clients as fast as possible. The realtime commands are acted upon and the other charcters are
|
||||
placed into a client_buffer[client].
|
||||
|
||||
The main protocol loop reads from client_buffer[]
|
||||
|
||||
|
||||
*/
|
||||
|
||||
#include "grbl.h"
|
||||
#include "commands.h"
|
||||
|
||||
#define RX_RING_BUFFER (RX_BUFFER_SIZE+1)
|
||||
#define TX_RING_BUFFER (TX_BUFFER_SIZE+1)
|
||||
|
||||
portMUX_TYPE myMutex = portMUX_INITIALIZER_UNLOCKED;
|
||||
|
||||
uint8_t serial_rx_buffer[CLIENT_COUNT][RX_RING_BUFFER];
|
||||
uint8_t serial_rx_buffer_head[CLIENT_COUNT] = {0};
|
||||
volatile uint8_t serial_rx_buffer_tail[CLIENT_COUNT] = {0};
|
||||
static TaskHandle_t serialCheckTaskHandle = 0;
|
||||
|
||||
// Returns the number of bytes available in the RX serial buffer.
|
||||
InputBuffer client_buffer[CLIENT_COUNT]; // create a buffer for each client
|
||||
|
||||
// Returns the number of bytes available in a client buffer.
|
||||
uint8_t serial_get_rx_buffer_available(uint8_t client)
|
||||
{
|
||||
uint8_t client_idx = client - 1;
|
||||
|
||||
uint8_t rtail = serial_rx_buffer_tail[client_idx]; // Copy to limit multiple calls to volatile
|
||||
if (serial_rx_buffer_head[client_idx] >= rtail) { return(RX_BUFFER_SIZE - (serial_rx_buffer_head[client_idx]-rtail)); }
|
||||
return((rtail-serial_rx_buffer_head[client_idx]-1));
|
||||
return client_buffer[client].availableforwrite();
|
||||
}
|
||||
|
||||
void serial_init()
|
||||
{
|
||||
Serial.begin(BAUD_RATE);
|
||||
|
||||
// reset all buffers
|
||||
serial_reset_read_buffer(CLIENT_ALL);
|
||||
|
||||
grbl_send(CLIENT_SERIAL,"\r\n"); // create some white space after ESP32 boot info
|
||||
|
||||
serialCheckTaskHandle = 0;
|
||||
// create a task to check for incoming data
|
||||
xTaskCreatePinnedToCore( serialCheckTask, // task
|
||||
@@ -64,25 +98,11 @@ void serial_init()
|
||||
void serialCheckTask(void *pvParameters)
|
||||
{
|
||||
uint8_t data = 0;
|
||||
uint8_t next_head;
|
||||
uint8_t client = CLIENT_ALL; // who send the data
|
||||
|
||||
uint8_t client_idx = 0; // index of data buffer
|
||||
uint8_t client = CLIENT_ALL; // who sent the data
|
||||
|
||||
while(true) // run continuously
|
||||
{
|
||||
while (Serial.available() || inputBuffer.available()
|
||||
#ifdef ENABLE_BLUETOOTH
|
||||
|| (SerialBT.hasClient() && SerialBT.available())
|
||||
#endif
|
||||
#if defined (ENABLE_WIFI) && defined(ENABLE_HTTP) && defined(ENABLE_SERIAL2SOCKET_IN)
|
||||
|| Serial2Socket.available()
|
||||
#endif
|
||||
#if defined (ENABLE_WIFI) && defined(ENABLE_TELNET)
|
||||
|| telnet_server.available()
|
||||
#endif
|
||||
)
|
||||
{
|
||||
while (any_client_has_data()) {
|
||||
if (Serial.available())
|
||||
{
|
||||
client = CLIENT_SERIAL;
|
||||
@@ -123,68 +143,20 @@ void serialCheckTask(void *pvParameters)
|
||||
#endif
|
||||
}
|
||||
|
||||
client_idx = client - 1; // for zero based array
|
||||
|
||||
|
||||
// Pick off realtime command characters directly from the serial stream. These characters are
|
||||
// not passed into the main buffer, but these set system state flag bits for realtime execution.
|
||||
switch (data) {
|
||||
case CMD_RESET:
|
||||
mc_reset(); // Call motion control reset routine.
|
||||
//report_init_message(client); // fool senders into thinking a reset happened.
|
||||
break;
|
||||
case CMD_STATUS_REPORT:
|
||||
report_realtime_status(client);
|
||||
break; // direct call instead of setting flag
|
||||
case CMD_CYCLE_START: system_set_exec_state_flag(EXEC_CYCLE_START); break; // Set as true
|
||||
case CMD_FEED_HOLD: system_set_exec_state_flag(EXEC_FEED_HOLD); break; // Set as true
|
||||
default :
|
||||
if (data > 0x7F) { // Real-time control characters are extended ACSII only.
|
||||
switch(data) {
|
||||
case CMD_SAFETY_DOOR: system_set_exec_state_flag(EXEC_SAFETY_DOOR); break; // Set as true
|
||||
case CMD_JOG_CANCEL:
|
||||
if (sys.state & STATE_JOG) { // Block all other states from invoking motion cancel.
|
||||
system_set_exec_state_flag(EXEC_MOTION_CANCEL);
|
||||
if (is_realtime_command(data)) {
|
||||
execute_realtime_command(data, client);
|
||||
}
|
||||
break;
|
||||
#ifdef DEBUG
|
||||
case CMD_DEBUG_REPORT: {uint8_t sreg = SREG; cli(); bit_true(sys_rt_exec_debug,EXEC_DEBUG_REPORT); SREG = sreg;} break;
|
||||
#endif
|
||||
case CMD_FEED_OVR_RESET: system_set_exec_motion_override_flag(EXEC_FEED_OVR_RESET); break;
|
||||
case CMD_FEED_OVR_COARSE_PLUS: system_set_exec_motion_override_flag(EXEC_FEED_OVR_COARSE_PLUS); break;
|
||||
case CMD_FEED_OVR_COARSE_MINUS: system_set_exec_motion_override_flag(EXEC_FEED_OVR_COARSE_MINUS); break;
|
||||
case CMD_FEED_OVR_FINE_PLUS: system_set_exec_motion_override_flag(EXEC_FEED_OVR_FINE_PLUS); break;
|
||||
case CMD_FEED_OVR_FINE_MINUS: system_set_exec_motion_override_flag(EXEC_FEED_OVR_FINE_MINUS); break;
|
||||
case CMD_RAPID_OVR_RESET: system_set_exec_motion_override_flag(EXEC_RAPID_OVR_RESET); break;
|
||||
case CMD_RAPID_OVR_MEDIUM: system_set_exec_motion_override_flag(EXEC_RAPID_OVR_MEDIUM); break;
|
||||
case CMD_RAPID_OVR_LOW: system_set_exec_motion_override_flag(EXEC_RAPID_OVR_LOW); break;
|
||||
case CMD_SPINDLE_OVR_RESET: system_set_exec_accessory_override_flag(EXEC_SPINDLE_OVR_RESET); break;
|
||||
case CMD_SPINDLE_OVR_COARSE_PLUS: system_set_exec_accessory_override_flag(EXEC_SPINDLE_OVR_COARSE_PLUS); break;
|
||||
case CMD_SPINDLE_OVR_COARSE_MINUS: system_set_exec_accessory_override_flag(EXEC_SPINDLE_OVR_COARSE_MINUS); break;
|
||||
case CMD_SPINDLE_OVR_FINE_PLUS: system_set_exec_accessory_override_flag(EXEC_SPINDLE_OVR_FINE_PLUS); break;
|
||||
case CMD_SPINDLE_OVR_FINE_MINUS: system_set_exec_accessory_override_flag(EXEC_SPINDLE_OVR_FINE_MINUS); break;
|
||||
case CMD_SPINDLE_OVR_STOP: system_set_exec_accessory_override_flag(EXEC_SPINDLE_OVR_STOP); break;
|
||||
#ifdef COOLANT_FLOOD_PIN
|
||||
case CMD_COOLANT_FLOOD_OVR_TOGGLE: system_set_exec_accessory_override_flag(EXEC_COOLANT_FLOOD_OVR_TOGGLE); break;
|
||||
#endif
|
||||
#ifdef COOLANT_MIST_PIN
|
||||
case CMD_COOLANT_MIST_OVR_TOGGLE: system_set_exec_accessory_override_flag(EXEC_COOLANT_MIST_OVR_TOGGLE); break;
|
||||
#endif
|
||||
}
|
||||
// Throw away any unfound extended-ASCII character by not passing it to the serial buffer.
|
||||
} else { // Write character to buffer
|
||||
|
||||
else {
|
||||
vTaskEnterCritical(&myMutex);
|
||||
next_head = serial_rx_buffer_head[client_idx] + 1;
|
||||
if (next_head == RX_RING_BUFFER) { next_head = 0; }
|
||||
|
||||
// Write data to buffer unless it is full.
|
||||
if (next_head != serial_rx_buffer_tail[client_idx]) {
|
||||
serial_rx_buffer[client_idx][serial_rx_buffer_head[client_idx]] = data;
|
||||
serial_rx_buffer_head[client_idx] = next_head;
|
||||
}
|
||||
client_buffer[client].write(data);
|
||||
vTaskExitCritical(&myMutex);
|
||||
}
|
||||
} // switch data
|
||||
|
||||
|
||||
} // if something available
|
||||
COMMANDS::handle();
|
||||
#ifdef ENABLE_WIFI
|
||||
@@ -200,71 +172,82 @@ void serialCheckTask(void *pvParameters)
|
||||
} // while(true)
|
||||
}
|
||||
|
||||
// ==================== call this in main protocol loop if you want it in the main task =========
|
||||
// be sure to stop task.
|
||||
// Realtime stuff is acted upon, then characters are added to the appropriate buffer
|
||||
void serialCheck()
|
||||
void serial_reset_read_buffer(uint8_t client)
|
||||
{
|
||||
uint8_t data = 0;
|
||||
uint8_t next_head;
|
||||
uint8_t client = CLIENT_SERIAL; // who send the data
|
||||
for (uint8_t client_num = 0; client_num < CLIENT_COUNT; client_num++)
|
||||
{
|
||||
if (client == client_num || client == CLIENT_ALL)
|
||||
{
|
||||
client_buffer[client].begin();
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
uint8_t client_idx = 0; // index of data buffer
|
||||
// Writes one byte to the TX serial buffer. Called by main program.
|
||||
void serial_write(uint8_t data) {
|
||||
Serial.write((char)data);
|
||||
}
|
||||
|
||||
// Fetches the first byte in the serial read buffer. Called by protocol loop.
|
||||
uint8_t serial_read(uint8_t client)
|
||||
{
|
||||
uint8_t data;
|
||||
|
||||
while (Serial.available() || inputBuffer.available()
|
||||
vTaskEnterCritical(&myMutex);
|
||||
if (client_buffer[client].available()) {
|
||||
data = client_buffer[client].read();
|
||||
vTaskExitCritical(&myMutex);
|
||||
//Serial.write((char)data);
|
||||
return data;
|
||||
}
|
||||
else {
|
||||
vTaskExitCritical(&myMutex);
|
||||
return SERIAL_NO_DATA;
|
||||
}
|
||||
}
|
||||
|
||||
bool any_client_has_data() {
|
||||
return (Serial.available() || inputBuffer.available()
|
||||
#ifdef ENABLE_BLUETOOTH
|
||||
|| (SerialBT.hasClient() && SerialBT.available())
|
||||
#endif
|
||||
#if defined (ENABLE_WIFI) && defined(ENABLE_HTTP) && defined(ENABLE_SERIAL2SOCKET_IN)
|
||||
|| Serial2Socket.available()
|
||||
#endif
|
||||
)
|
||||
{
|
||||
if (Serial.available())
|
||||
{
|
||||
client = CLIENT_SERIAL;
|
||||
data = Serial.read();
|
||||
}
|
||||
else if (inputBuffer.available())
|
||||
{
|
||||
client = CLIENT_INPUT;
|
||||
data = inputBuffer.read();
|
||||
}
|
||||
#if defined (ENABLE_BLUETOOTH) || (defined (ENABLE_WIFI) && defined(ENABLE_HTTP) && defined(ENABLE_SERIAL2SOCKET_IN))
|
||||
else
|
||||
{ //currently is wifi or BT but better to prepare both can be live
|
||||
#ifdef ENABLE_BLUETOOTH
|
||||
if(SerialBT.hasClient() && SerialBT.available()){
|
||||
client = CLIENT_BT;
|
||||
data = SerialBT.read();
|
||||
} else {
|
||||
#if defined (ENABLE_WIFI) && defined(ENABLE_TELNET)
|
||||
|| telnet_server.available()
|
||||
#endif
|
||||
#if defined (ENABLE_WIFI) && defined(ENABLE_HTTP) && defined(ENABLE_SERIAL2SOCKET_IN)
|
||||
client = CLIENT_WEBUI;
|
||||
data = Serial2Socket.read();
|
||||
#endif
|
||||
#ifdef ENABLE_BLUETOOTH
|
||||
}
|
||||
#endif
|
||||
}
|
||||
#endif
|
||||
);
|
||||
}
|
||||
|
||||
client_idx = client - 1; // for zero based array
|
||||
// checks to see if a character is a realtime character
|
||||
bool is_realtime_command(uint8_t data) {
|
||||
return (data == CMD_RESET || data == CMD_STATUS_REPORT || data == CMD_CYCLE_START || data == CMD_FEED_HOLD || data > 0x7F);
|
||||
}
|
||||
|
||||
// Act upon a realtime character
|
||||
void execute_realtime_command(uint8_t command, uint8_t client) {
|
||||
switch (command) {
|
||||
case CMD_RESET:
|
||||
mc_reset(); // Call motion control reset routine.
|
||||
break;
|
||||
|
||||
// Pick off realtime command characters directly from the serial stream. These characters are
|
||||
// not passed into the main buffer, but these set system state flag bits for realtime execution.
|
||||
switch (data) {
|
||||
case CMD_RESET: mc_reset(); break; // Call motion control reset routine.
|
||||
case CMD_STATUS_REPORT:
|
||||
report_realtime_status(client);
|
||||
break; // direct call instead of setting flag
|
||||
case CMD_CYCLE_START: system_set_exec_state_flag(EXEC_CYCLE_START); break; // Set as true
|
||||
case CMD_FEED_HOLD: system_set_exec_state_flag(EXEC_FEED_HOLD); break; // Set as true
|
||||
default :
|
||||
if (data > 0x7F) { // Real-time control characters are extended ACSII only.
|
||||
switch(data) {
|
||||
case CMD_SAFETY_DOOR: system_set_exec_state_flag(EXEC_SAFETY_DOOR); break; // Set as true
|
||||
report_realtime_status(client); // direct call instead of setting flag
|
||||
break;
|
||||
|
||||
case CMD_CYCLE_START:
|
||||
system_set_exec_state_flag(EXEC_CYCLE_START); // Set as true
|
||||
break;
|
||||
|
||||
case CMD_FEED_HOLD:
|
||||
system_set_exec_state_flag(EXEC_FEED_HOLD); // Set as true
|
||||
break;
|
||||
|
||||
case CMD_SAFETY_DOOR:
|
||||
system_set_exec_state_flag(EXEC_SAFETY_DOOR);
|
||||
break; // Set as true
|
||||
|
||||
case CMD_JOG_CANCEL:
|
||||
if (sys.state & STATE_JOG) { // Block all other states from invoking motion cancel.
|
||||
system_set_exec_state_flag(EXEC_MOTION_CANCEL);
|
||||
@@ -293,56 +276,8 @@ void serialCheck()
|
||||
#ifdef COOLANT_MIST_PIN
|
||||
case CMD_COOLANT_MIST_OVR_TOGGLE: system_set_exec_accessory_override_flag(EXEC_COOLANT_MIST_OVR_TOGGLE); break;
|
||||
#endif
|
||||
}
|
||||
// Throw away any unfound extended-ASCII character by not passing it to the serial buffer.
|
||||
} else { // Write character to buffer
|
||||
|
||||
|
||||
next_head = serial_rx_buffer_head[client_idx] + 1;
|
||||
if (next_head == RX_RING_BUFFER) { next_head = 0; }
|
||||
|
||||
// Write data to buffer unless it is full.
|
||||
if (next_head != serial_rx_buffer_tail[client_idx]) {
|
||||
serial_rx_buffer[client_idx][serial_rx_buffer_head[client_idx]] = data;
|
||||
serial_rx_buffer_head[client_idx] = next_head;
|
||||
}
|
||||
}
|
||||
} // switch data
|
||||
} // if something available
|
||||
}
|
||||
|
||||
void serial_reset_read_buffer(uint8_t client)
|
||||
{
|
||||
for (uint8_t client_num = 0; client_num <= CLIENT_COUNT; client_num++)
|
||||
{
|
||||
if (client == client_num || client == CLIENT_ALL)
|
||||
{
|
||||
serial_rx_buffer_tail[client_num-1] = serial_rx_buffer_head[client_num-1];
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
// Writes one byte to the TX serial buffer. Called by main program.
|
||||
void serial_write(uint8_t data) {
|
||||
Serial.write((char)data);
|
||||
}
|
||||
// Fetches the first byte in the serial read buffer. Called by main program.
|
||||
uint8_t serial_read(uint8_t client)
|
||||
{
|
||||
uint8_t client_idx = client - 1;
|
||||
|
||||
uint8_t tail = serial_rx_buffer_tail[client_idx]; // Temporary serial_rx_buffer_tail (to optimize for volatile)
|
||||
if (serial_rx_buffer_head[client_idx] == tail) {
|
||||
return SERIAL_NO_DATA;
|
||||
} else {
|
||||
vTaskEnterCritical(&myMutex); // make sure buffer is not modified while reading by newly read chars from the serial when we are here
|
||||
uint8_t data = serial_rx_buffer[client_idx][tail];
|
||||
|
||||
tail++;
|
||||
if (tail == RX_RING_BUFFER) { tail = 0; }
|
||||
serial_rx_buffer_tail[client_idx] = tail;
|
||||
vTaskExitCritical(&myMutex);
|
||||
return data;
|
||||
}
|
||||
|
||||
}
|
||||
|
||||
|
@@ -39,8 +39,6 @@
|
||||
// a task to read for incoming data from serial port
|
||||
void serialCheckTask(void *pvParameters);
|
||||
|
||||
void serialCheck();
|
||||
|
||||
void serial_write(uint8_t data);
|
||||
// Fetches the first byte in the serial read buffer. Called by main program.
|
||||
uint8_t serial_read(uint8_t client);
|
||||
@@ -54,4 +52,8 @@ void serial_reset_read_buffer(uint8_t client);
|
||||
// Returns the number of bytes available in the RX serial buffer.
|
||||
uint8_t serial_get_rx_buffer_available(uint8_t client);
|
||||
|
||||
void execute_realtime_command(uint8_t command, uint8_t client);
|
||||
bool any_client_has_data();
|
||||
bool is_realtime_command(uint8_t data);
|
||||
|
||||
#endif
|
||||
|
@@ -50,9 +50,8 @@ static TaskHandle_t servosSyncTaskHandle = 0;
|
||||
|
||||
void init_servos()
|
||||
{
|
||||
//grbl_send(CLIENT_SERIAL, "[MSG: Init Servos]\r\n");
|
||||
#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.set_range(SERVO_X_RANGE_MIN, SERVO_X_RANGE_MAX);
|
||||
X_Servo_Axis.set_homing_type(SERVO_HOMING_OFF);
|
||||
@@ -60,12 +59,12 @@ void init_servos()
|
||||
X_Servo_Axis.set_disable_with_steppers(false);
|
||||
#endif
|
||||
#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.set_range(SERVO_Y_RANGE_MIN, SERVO_Y_RANGE_MAX);
|
||||
#endif
|
||||
#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.set_range(SERVO_Z_RANGE_MIN, SERVO_Z_RANGE_MAX);
|
||||
#ifdef SERVO_Z_HOMING_TYPE
|
||||
@@ -80,7 +79,7 @@ void init_servos()
|
||||
#endif
|
||||
|
||||
#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.set_range(SERVO_A_RANGE_MIN, SERVO_A_RANGE_MAX);
|
||||
A_Servo_Axis.set_homing_type(SERVO_HOMING_OFF);
|
||||
@@ -88,12 +87,12 @@ void init_servos()
|
||||
A_Servo_Axis.set_disable_with_steppers(false);
|
||||
#endif
|
||||
#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.set_range(SERVO_B_RANGE_MIN, SERVO_B_RANGE_MAX);
|
||||
#endif
|
||||
#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.set_range(SERVO_C_RANGE_MIN, SERVO_C_RANGE_MAX);
|
||||
//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 (_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;
|
||||
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
|
||||
if ( (settings.max_travel[_axis] < -SERVO_CAL_MAX) || (settings.max_travel[_axis] > -SERVO_CAL_MIN) ) {
|
||||
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;
|
||||
write_global_settings();
|
||||
}
|
||||
@@ -312,7 +311,7 @@ void ServoAxis::set_range(float min, float max) {
|
||||
_position_max = max;
|
||||
}
|
||||
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");
|
||||
}
|
||||
}
|
||||
|
||||
|
@@ -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
|
@@ -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
|
@@ -461,6 +461,6 @@ void settings_spi_driver_init() {
|
||||
#ifdef USE_TRINAMIC
|
||||
trinamic_change_settings();
|
||||
#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
|
||||
}
|
@@ -34,18 +34,18 @@ void spindle_init()
|
||||
#ifdef SPINDLE_PWM_PIN
|
||||
|
||||
#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
|
||||
|
||||
#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
|
||||
|
||||
// determine how many PWM counts are in eqach PWM cycle
|
||||
spindle_pwm_period = ((1<<SPINDLE_PWM_BIT_PRECISION) -1);
|
||||
|
||||
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
|
||||
|
@@ -447,13 +447,13 @@ void stepper_init()
|
||||
Trinamic_Init();
|
||||
#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
|
||||
grbl_send(CLIENT_SERIAL, "[MSG:RMT Steps]\r\n");
|
||||
grbl_msg_sendf(CLIENT_SERIAL, MSG_LEVEL_INFO, "RMT Steps");
|
||||
initRMT();
|
||||
#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
|
||||
#ifdef X_STEP_PIN
|
||||
pinMode(X_STEP_PIN, OUTPUT);
|
||||
|
@@ -47,25 +47,25 @@ void system_ini() // Renamed from system_init() due to conflict with esp32 files
|
||||
#endif
|
||||
|
||||
#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);
|
||||
attachInterrupt(digitalPinToInterrupt(MACRO_BUTTON_0_PIN), isr_control_inputs, CHANGE);
|
||||
#endif
|
||||
|
||||
#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);
|
||||
attachInterrupt(digitalPinToInterrupt(MACRO_BUTTON_1_PIN), isr_control_inputs, CHANGE);
|
||||
#endif
|
||||
|
||||
#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);
|
||||
attachInterrupt(digitalPinToInterrupt(MACRO_BUTTON_2_PIN), isr_control_inputs, CHANGE);
|
||||
#endif
|
||||
|
||||
#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);
|
||||
attachInterrupt(digitalPinToInterrupt(MACRO_BUTTON_3_PIN), isr_control_inputs, CHANGE);
|
||||
#endif
|
||||
@@ -544,7 +544,7 @@ uint8_t get_limit_pin_mask(uint8_t axis_idx)
|
||||
void system_exec_control_pin(uint8_t pin) {
|
||||
|
||||
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();
|
||||
}
|
||||
else if (bit_istrue(pin,CONTROL_PIN_INDEX_CYCLE_START)) {
|
||||
|
@@ -176,7 +176,7 @@ bool Web_Server::begin(){
|
||||
#endif
|
||||
|
||||
#ifdef ENABLE_CAPTIVE_PORTAL
|
||||
if(WiFi.getMode() != WIFI_STA){
|
||||
if(WiFi.getMode() == WIFI_AP){
|
||||
// if DNSServer is started with "*" for domain name, it will reply with
|
||||
// provided IP to all DNS request
|
||||
dnsServer.start(DNS_PORT, "*", WiFi.softAPIP());
|
||||
@@ -341,7 +341,7 @@ void Web_Server:: handle_not_found()
|
||||
|
||||
if (page_not_found ) {
|
||||
#ifdef ENABLE_CAPTIVE_PORTAL
|
||||
if (WiFi.getMode()!=WIFI_STA ) {
|
||||
if(WiFi.getMode() == WIFI_AP) {
|
||||
String contentType= PAGE_CAPTIVE;
|
||||
String stmp = WiFi.softAPIP().toString();
|
||||
//Web address = ip + port
|
||||
@@ -1630,7 +1630,7 @@ void Web_Server::handle(){
|
||||
static uint32_t timeout = millis();
|
||||
COMMANDS::wait(0);
|
||||
#ifdef ENABLE_CAPTIVE_PORTAL
|
||||
if(WiFi.getMode() != WIFI_STA){
|
||||
if(WiFi.getMode() == WIFI_AP){
|
||||
dnsServer.processNextRequest();
|
||||
}
|
||||
#endif
|
||||
|
@@ -27,3 +27,4 @@ framework = arduino
|
||||
upload_speed = 512000
|
||||
board_build.partitions = min_spiffs.csv
|
||||
monitor_speed = 115200
|
||||
build_flags = -DCORE_DEBUG_LEVEL=0
|
||||
|
Reference in New Issue
Block a user