mirror of
https://github.com/bdring/Grbl_Esp32.git
synced 2025-08-19 21:02:02 +02:00
@@ -101,7 +101,7 @@ void loop() {
|
||||
sys_rt_exec_accessory_override = 0;
|
||||
|
||||
// Reset Grbl primary systems.
|
||||
serial_reset_read_buffer(); // Clear serial read buffer
|
||||
serial_reset_read_buffer(CLIENT_ALL); // Clear serial read buffer
|
||||
|
||||
gc_init(); // Set g-code parser to default state
|
||||
|
||||
@@ -119,7 +119,7 @@ void loop() {
|
||||
|
||||
|
||||
// put your main code here, to run repeatedly:
|
||||
report_init_message();
|
||||
report_init_message(CLIENT_ALL);
|
||||
|
||||
// Start Grbl main loop. Processes program inputs and executes them.
|
||||
protocol_main_loop();
|
||||
|
@@ -107,13 +107,13 @@ Some features should not be changed. See notes below.
|
||||
// pull-off motion to disengage the limit switches. The following HOMING_CYCLE_x defines are executed
|
||||
// in order starting with suffix 0 and completes the homing routine for the specified-axes only. If
|
||||
// an axis is omitted from the defines, it will not home, nor will the system update its position.
|
||||
// Meaning that this allows for users with non-standard cartesian machines, such as a lathe (x then z,
|
||||
// Meaning that this allows for users with non-standard Cartesian machines, such as a lathe (x then z,
|
||||
// with no y), to configure the homing cycle behavior to their needs.
|
||||
// NOTE: The homing cycle is designed to allow sharing of limit pins, if the axes are not in the same
|
||||
// cycle, but this requires some pin settings changes in cpu_map.h file. For example, the default homing
|
||||
// cycle can share the Z limit pin with either X or Y limit pins, since they are on different cycles.
|
||||
// By sharing a pin, this frees up a precious IO pin for other purposes. In theory, all axes limit pins
|
||||
// may be reduced to one pin, if all axes are homed with seperate cycles, or vice versa, all three axes
|
||||
// may be reduced to one pin, if all axes are homed with separate cycles, or vice versa, all three axes
|
||||
// on separate pin, but homed in one cycle. Also, it should be noted that the function of hard limits
|
||||
// will not be affected by pin sharing.
|
||||
// NOTE: Defaults are set for a traditional 3-axis CNC machine. Z-axis first to clear, followed by X & Y.
|
||||
@@ -185,7 +185,9 @@ Some features should not be changed. See notes below.
|
||||
// Enables a second coolant control pin via the mist coolant g-code command M7 on the Arduino Uno
|
||||
// analog pin 4. Only use this option if you require a second coolant control pin.
|
||||
// NOTE: The M8 flood coolant control pin on analog pin 3 will still be functional regardless.
|
||||
//#define ENABLE_M7 // Disabled by default. Uncomment to enable.
|
||||
// ESP32 NOTE! This is here for reference only. You enable both M7 and M8 by assigning them a GPIO Pin
|
||||
// in cpu_map.h
|
||||
//#define ENABLE_M7 // Don't uncomment...see above!
|
||||
|
||||
// This option causes the feed hold input to act as a safety door switch. A safety door, when triggered,
|
||||
// immediately forces a feed hold and then safely de-energizes the machine. Resuming is blocked until
|
||||
|
@@ -26,8 +26,12 @@
|
||||
|
||||
void coolant_init()
|
||||
{
|
||||
pinMode(COOLANT_FLOOD_PIN, OUTPUT);
|
||||
#ifdef ENABLE_M7
|
||||
#ifdef COOLANT_FLOOD_PIN
|
||||
pinMode(COOLANT_FLOOD_PIN, OUTPUT);
|
||||
#endif
|
||||
|
||||
|
||||
#ifdef COOLANT_MIST_PIN
|
||||
pinMode(COOLANT_MIST_PIN, OUTPUT);
|
||||
#endif
|
||||
coolant_stop();
|
||||
@@ -39,14 +43,18 @@ uint8_t coolant_get_state()
|
||||
{
|
||||
uint8_t cl_state = COOLANT_STATE_DISABLE;
|
||||
|
||||
#ifdef INVERT_COOLANT_FLOOD_PIN
|
||||
if (! digitalRead(COOLANT_FLOOD_PIN)) {
|
||||
#else
|
||||
if (digitalRead(COOLANT_FLOOD_PIN)) {
|
||||
#endif
|
||||
cl_state |= COOLANT_STATE_FLOOD;
|
||||
}
|
||||
#ifdef ENABLE_M7
|
||||
#ifdef COOLANT_FLOOD_PIN
|
||||
#ifdef INVERT_COOLANT_FLOOD_PIN
|
||||
if (! digitalRead(COOLANT_FLOOD_PIN)) {
|
||||
#else
|
||||
if (digitalRead(COOLANT_FLOOD_PIN)) {
|
||||
#endif
|
||||
cl_state |= COOLANT_STATE_FLOOD;
|
||||
}
|
||||
#endif
|
||||
|
||||
|
||||
#ifdef COOLANT_MIST_PIN
|
||||
#ifdef INVERT_COOLANT_MIST_PIN
|
||||
if (! digitalRead(COOLANT_MIST_PIN)) {
|
||||
#else
|
||||
@@ -65,12 +73,15 @@ uint8_t coolant_get_state()
|
||||
// an interrupt-level. No report flag set, but only called by routines that don't need it.
|
||||
void coolant_stop()
|
||||
{
|
||||
#ifdef INVERT_COOLANT_FLOOD_PIN
|
||||
digitalWrite(COOLANT_FLOOD_PIN, 1);
|
||||
#else
|
||||
digitalWrite(COOLANT_FLOOD_PIN, 0);
|
||||
#endif
|
||||
#ifdef ENABLE_M7
|
||||
#ifdef COOLANT_FLOOD_PIN
|
||||
#ifdef INVERT_COOLANT_FLOOD_PIN
|
||||
digitalWrite(COOLANT_FLOOD_PIN, 1);
|
||||
#else
|
||||
digitalWrite(COOLANT_FLOOD_PIN, 0);
|
||||
#endif
|
||||
#endif
|
||||
|
||||
#ifdef COOLANT_MIST_PIN
|
||||
#ifdef INVERT_COOLANT_MIST_PIN
|
||||
digitalWrite(COOLANT_MIST_PIN, 1);
|
||||
#else
|
||||
@@ -93,7 +104,8 @@ void coolant_set_state(uint8_t mode)
|
||||
coolant_stop();
|
||||
|
||||
} else {
|
||||
|
||||
|
||||
#ifdef COOLANT_FLOOD_PIN
|
||||
if (mode & COOLANT_FLOOD_ENABLE) {
|
||||
#ifdef INVERT_COOLANT_FLOOD_PIN
|
||||
digitalWrite(COOLANT_FLOOD_PIN, 0);
|
||||
@@ -101,8 +113,9 @@ void coolant_set_state(uint8_t mode)
|
||||
digitalWrite(COOLANT_FLOOD_PIN, 1);
|
||||
#endif
|
||||
}
|
||||
#endif
|
||||
|
||||
#ifdef ENABLE_M7
|
||||
#ifdef COOLANT_MIST_PIN
|
||||
if (mode & COOLANT_MIST_ENABLE) {
|
||||
#ifdef INVERT_COOLANT_MIST_PIN
|
||||
digitalWrite(COOLANT_MIST_PIN, 0);
|
||||
|
@@ -34,35 +34,44 @@
|
||||
changed. They are just preserved right now to make it easy to stay in sync
|
||||
with AVR grbl
|
||||
|
||||
|
||||
|
||||
*/
|
||||
|
||||
// This is the CPU Map for the ESP32 CNC Controller R2
|
||||
|
||||
|
||||
// It is OK to comment out any step and direction pins. This
|
||||
// won't affect operation except that there will be no output
|
||||
// form the pins. Grbl will virtually move the axis. This could
|
||||
// be handy if you are using a servo, etc. for another axis.
|
||||
#define X_STEP_PIN GPIO_NUM_12
|
||||
#define Y_STEP_PIN GPIO_NUM_14
|
||||
#define Z_STEP_PIN GPIO_NUM_27
|
||||
#define STEP_MASK B111 // don't change
|
||||
|
||||
#define X_STEP_BIT 0
|
||||
#define Y_STEP_BIT 1
|
||||
#define Z_STEP_BIT 2
|
||||
#define X_STEP_BIT 0 // don't change
|
||||
#define Y_STEP_BIT 1 // don't change
|
||||
#define Z_STEP_BIT 2 // don't change
|
||||
|
||||
#define X_DIRECTION_BIT 0
|
||||
#define Y_DIRECTION_BIT 1
|
||||
#define Z_DIRECTION_BIT 2
|
||||
#define X_DIRECTION_BIT 0 // don't change
|
||||
#define Y_DIRECTION_BIT 1 // don't change
|
||||
#define Z_DIRECTION_BIT 2 // don't change
|
||||
|
||||
#define X_DIRECTION_PIN GPIO_NUM_26
|
||||
#define Y_DIRECTION_PIN GPIO_NUM_25
|
||||
#define Z_DIRECTION_PIN GPIO_NUM_33
|
||||
|
||||
// OK to comment out to use pin for other features
|
||||
#define STEPPERS_DISABLE_PIN GPIO_NUM_13
|
||||
|
||||
#define COOLANT_FLOOD_PIN GPIO_NUM_16
|
||||
#define COOLANT_MIST_PIN GPIO_NUM_19
|
||||
|
||||
#define SPINDLE_PWM_PIN GPIO_NUM_17
|
||||
|
||||
// *** the flood coolant feature code is activated by defining this pins
|
||||
// *** Comment it out to use the pin for other features
|
||||
#define COOLANT_FLOOD_PIN GPIO_NUM_16
|
||||
//#define COOLANT_MIST_PIN GPIO_NUM_21
|
||||
|
||||
// If SPINDLE_PWM_PIN is commented out, this frees up the pin, but Grbl will still
|
||||
// use a virtual spindle. Do not comment out the other parameters for the spindle.
|
||||
#define SPINDLE_PWM_PIN GPIO_NUM_17
|
||||
#define SPINDLE_PWM_CHANNEL 0
|
||||
#define SPINDLE_PWM_BASE_FREQ 5000 // Hz
|
||||
#define SPINDLE_PWM_BIT_PRECISION 8
|
||||
@@ -70,9 +79,14 @@
|
||||
#define SPINDLE_PWM_MAX_VALUE 255 // TODO ESP32 Calc from resolution
|
||||
#define SPINDLE_PWM_RANGE (SPINDLE_PWM_MAX_VALUE-SPINDLE_PWM_MIN_VALUE)
|
||||
|
||||
#define X_LIMIT_BIT 0
|
||||
#define Y_LIMIT_BIT 1
|
||||
#define Z_LIMIT_BIT 2
|
||||
// if these spindle function pins are defined, they will be activated in the code
|
||||
// comment them out to use the pins for other functions
|
||||
//#define SPINDLE_ENABLE_PIN GPIO_NUM_16
|
||||
//#define SPINDLE_DIR_PIN GPIO_NUM_16
|
||||
|
||||
#define X_LIMIT_BIT 0 // don't change
|
||||
#define Y_LIMIT_BIT 1 // don't change
|
||||
#define Z_LIMIT_BIT 2 // don't change
|
||||
|
||||
#define X_LIMIT_PIN GPIO_NUM_2
|
||||
#define Y_LIMIT_PIN GPIO_NUM_4
|
||||
|
@@ -48,7 +48,7 @@ void gc_init()
|
||||
|
||||
// Load default G54 coordinate system.
|
||||
if (!(settings_read_coord_data(gc_state.modal.coord_select,gc_state.coord_system))) {
|
||||
report_status_message(STATUS_SETTING_READ_FAIL);
|
||||
report_status_message(STATUS_SETTING_READ_FAIL, CLIENT_SERIAL);
|
||||
}
|
||||
}
|
||||
|
||||
@@ -66,7 +66,7 @@ void gc_sync_position()
|
||||
// characters have been removed. In this function, all units and positions are converted and
|
||||
// exported to grbl's internal functions in terms of (mm, mm/min) and absolute machine
|
||||
// coordinates, respectively.
|
||||
uint8_t gc_execute_line(char *line)
|
||||
uint8_t gc_execute_line(char *line, uint8_t client)
|
||||
{
|
||||
/* -------------------------------------------------------------------------------------
|
||||
STEP 1: Initialize parser block struct and copy current g-code state modes. The parser
|
||||
@@ -255,34 +255,38 @@ uint8_t gc_execute_line(char *line)
|
||||
default: gc_block.modal.program_flow = int_value; // Program end and reset
|
||||
}
|
||||
break;
|
||||
#ifndef USE_SPINDLE_DIR_AS_ENABLE_PIN
|
||||
case 4:
|
||||
#endif
|
||||
case 3: case 5:
|
||||
|
||||
case 3: case 4: case 5:
|
||||
word_bit = MODAL_GROUP_M7;
|
||||
switch(int_value) {
|
||||
case 3: gc_block.modal.spindle = SPINDLE_ENABLE_CW; break;
|
||||
#ifndef USE_SPINDLE_DIR_AS_ENABLE_PIN
|
||||
case 4: gc_block.modal.spindle = SPINDLE_ENABLE_CCW; break;
|
||||
#endif
|
||||
case 3:
|
||||
gc_block.modal.spindle = SPINDLE_ENABLE_CW;
|
||||
break;
|
||||
case 4:
|
||||
#ifdef SPINDLE_DIR_PIN
|
||||
gc_block.modal.spindle = SPINDLE_ENABLE_CCW;
|
||||
#else
|
||||
FAIL(STATUS_GCODE_UNSUPPORTED_COMMAND);
|
||||
#endif
|
||||
break;
|
||||
case 5: gc_block.modal.spindle = SPINDLE_DISABLE; break;
|
||||
}
|
||||
break;
|
||||
#ifdef ENABLE_M7
|
||||
case 7: case 8: case 9:
|
||||
#else
|
||||
case 8: case 9:
|
||||
#endif
|
||||
word_bit = MODAL_GROUP_M8;
|
||||
switch(int_value) {
|
||||
#ifdef ENABLE_M7
|
||||
case 7: gc_block.modal.coolant = COOLANT_MIST_ENABLE; break;
|
||||
#endif
|
||||
case 8: gc_block.modal.coolant = COOLANT_FLOOD_ENABLE; break;
|
||||
case 9: gc_block.modal.coolant = COOLANT_DISABLE; break;
|
||||
}
|
||||
break;
|
||||
default: FAIL(STATUS_GCODE_UNSUPPORTED_COMMAND); // [Unsupported M command]
|
||||
break;
|
||||
case 7: case 8: case 9:
|
||||
word_bit = MODAL_GROUP_M8;
|
||||
switch(int_value) {
|
||||
#ifdef COOLANT_MIST_PIN
|
||||
case 7: gc_block.modal.coolant = COOLANT_MIST_ENABLE; break;
|
||||
#endif
|
||||
#ifdef COOLANT_FLOOD_PIN
|
||||
case 8: gc_block.modal.coolant = COOLANT_FLOOD_ENABLE; break;
|
||||
#endif
|
||||
case 9: gc_block.modal.coolant = COOLANT_DISABLE; break;
|
||||
default: FAIL(STATUS_GCODE_UNSUPPORTED_COMMAND); // [Unsupported M command]
|
||||
}
|
||||
break;
|
||||
default:
|
||||
FAIL(STATUS_GCODE_UNSUPPORTED_COMMAND); // [Unsupported M command]
|
||||
}
|
||||
|
||||
// Check for more than one command per modal group violations in the current block
|
||||
|
@@ -238,7 +238,7 @@ typedef struct {
|
||||
void gc_init();
|
||||
|
||||
// Execute one block of rs275/ngc/g-code
|
||||
uint8_t gc_execute_line(char *line);
|
||||
uint8_t gc_execute_line(char *line, uint8_t client);
|
||||
|
||||
// Set g-code parser position. Input in steps.
|
||||
void gc_sync_position();
|
||||
|
@@ -20,7 +20,7 @@
|
||||
|
||||
// Grbl versioning system
|
||||
#define GRBL_VERSION "1.1f"
|
||||
#define GRBL_VERSION_BUILD "20180906"
|
||||
#define GRBL_VERSION_BUILD "20180910"
|
||||
|
||||
//#include <sdkconfig.h>
|
||||
#include <arduino.h>
|
||||
|
@@ -1,11 +1,15 @@
|
||||
#include "grbl.h"
|
||||
|
||||
#ifdef ENABLE_BLUETOOTH
|
||||
|
||||
BluetoothSerial SerialBT;
|
||||
|
||||
void bluetooth_init(char *name)
|
||||
{
|
||||
if (!SerialBT.begin(name))
|
||||
{
|
||||
report_status_message(STATUS_BT_FAIL_BEGIN);
|
||||
report_status_message(STATUS_BT_FAIL_BEGIN, CLIENT_SERIAL);
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
#endif
|
||||
|
@@ -29,13 +29,13 @@
|
||||
|
||||
File myFile;
|
||||
char fileTypes[FILE_TYPE_COUNT][8] = {".NC", ".TXT", ".GCODE"}; // filter out files not of these types (s/b UPPERCASE)
|
||||
bool SD_file_running = false; // a file has started but not completed
|
||||
bool SD_ready_next = false; // Grbl has processed a line and is waiting for another
|
||||
|
||||
|
||||
// attempt to mount the SD card
|
||||
bool sd_mount() {
|
||||
if(!SD.begin()){
|
||||
report_status_message(STATUS_SD_FAILED_MOUNT);
|
||||
report_status_message(STATUS_SD_FAILED_MOUNT, CLIENT_SERIAL);
|
||||
return false;
|
||||
}
|
||||
return true;
|
||||
@@ -46,11 +46,11 @@ void listDir(fs::FS &fs, const char * dirname, uint8_t levels){
|
||||
|
||||
File root = fs.open(dirname);
|
||||
if(!root){
|
||||
report_status_message(STATUS_SD_FAILED_OPEN_DIR);
|
||||
report_status_message(STATUS_SD_FAILED_OPEN_DIR, CLIENT_SERIAL);
|
||||
return;
|
||||
}
|
||||
if(!root.isDirectory()){
|
||||
report_status_message(STATUS_SD_DIR_NOT_FOUND);
|
||||
report_status_message(STATUS_SD_DIR_NOT_FOUND, CLIENT_SERIAL);
|
||||
return;
|
||||
}
|
||||
|
||||
@@ -72,7 +72,7 @@ void listDir(fs::FS &fs, const char * dirname, uint8_t levels){
|
||||
for (uint8_t i=0; i < FILE_TYPE_COUNT; i++) // make sure it is a valid file type
|
||||
{
|
||||
if (strstr(temp_filename, fileTypes[i])) {
|
||||
grbl_sendf("[FILE:%s,SIZE:%d]\r\n", file.name(), file.size());
|
||||
grbl_sendf(CLIENT_ALL, "[FILE:%s,SIZE:%d]\r\n", file.name(), file.size());
|
||||
break;
|
||||
}
|
||||
}
|
||||
@@ -83,13 +83,14 @@ void listDir(fs::FS &fs, const char * dirname, uint8_t levels){
|
||||
|
||||
boolean openFile(fs::FS &fs, const char * path){
|
||||
myFile = fs.open(path);
|
||||
|
||||
if(!myFile){
|
||||
report_status_message(STATUS_SD_FAILED_READ);
|
||||
report_status_message(STATUS_SD_FAILED_READ, CLIENT_SERIAL);
|
||||
return false;
|
||||
}
|
||||
|
||||
SD_file_running = true;
|
||||
SD_ready_next = false; // this will get set to true when Grbl issues "ok" message
|
||||
set_sd_state(SDCARD_BUSY_PRINTING);
|
||||
SD_ready_next = false; // this will get set to true when Grbl issues "ok" message
|
||||
return true;
|
||||
}
|
||||
|
||||
@@ -98,7 +99,7 @@ boolean closeFile(){
|
||||
return false;
|
||||
}
|
||||
|
||||
SD_file_running = false;
|
||||
set_sd_state(SDCARD_IDLE);
|
||||
SD_ready_next = false;
|
||||
myFile.close();
|
||||
return true;
|
||||
@@ -117,7 +118,7 @@ boolean readFileLine(char *line) {
|
||||
uint8_t line_flags = 0;
|
||||
|
||||
if (!myFile) {
|
||||
report_status_message(STATUS_SD_FAILED_READ);
|
||||
report_status_message(STATUS_SD_FAILED_READ, CLIENT_SERIAL);
|
||||
return false;
|
||||
}
|
||||
|
||||
@@ -156,7 +157,7 @@ boolean readFileLine(char *line) {
|
||||
if (index == 255) // name is too long so return false
|
||||
{
|
||||
line[index] = '\0';
|
||||
report_status_message(STATUS_OVERFLOW);
|
||||
report_status_message(STATUS_OVERFLOW, CLIENT_SERIAL);
|
||||
return false;
|
||||
}
|
||||
}
|
||||
@@ -177,18 +178,47 @@ float sd_report_perc_complete() {
|
||||
return ((float)myFile.position() / (float)myFile.size() * 100.0);
|
||||
}
|
||||
|
||||
/*
|
||||
void readFile(fs::FS &fs, const char * path){
|
||||
|
||||
File file = fs.open(path);
|
||||
if(!file){
|
||||
report_status_message(STATUS_SD_FAILED_READ);
|
||||
return;
|
||||
uint8_t sd_state = SDCARD_IDLE;
|
||||
|
||||
uint8_t get_sd_state(bool refresh){
|
||||
#if defined(SDCARD_DET_PIN) && SDCARD_SD_PIN != -1
|
||||
//no need to go further if SD detect is not correct
|
||||
if (!((digitalRead (SDCARD_DET_PIN) == SDCARD_DET_VAL) ? true : false)){
|
||||
sd_state = SDCARD_NOT_PRESENT;
|
||||
return sd_state;
|
||||
}
|
||||
|
||||
while(file.available()){
|
||||
Serial.write(file.read());
|
||||
#endif
|
||||
//if busy doing something return state
|
||||
if (!((sd_state == SDCARD_NOT_PRESENT) || (sd_state == SDCARD_IDLE))) return sd_state;
|
||||
if (!refresh) return sd_state; //to avoid refresh=true + busy to reset SD and waste time
|
||||
//SD is idle or not detected, let see if still the case
|
||||
|
||||
if (sd_state == SDCARD_IDLE) {
|
||||
SD.end();
|
||||
//using default value for speed ? should be parameter
|
||||
//refresh content if card was removed
|
||||
if (!SD.begin()) sd_state = SDCARD_NOT_PRESENT;
|
||||
else {
|
||||
if ( !(SD.cardSize() > 0 )) sd_state = SDCARD_NOT_PRESENT;
|
||||
}
|
||||
}
|
||||
file.close();
|
||||
return sd_state;
|
||||
}
|
||||
*/
|
||||
|
||||
uint8_t set_sd_state(uint8_t flag){
|
||||
sd_state = flag;
|
||||
return sd_state;
|
||||
}
|
||||
|
||||
void sd_get_current_filename(char* name) {
|
||||
|
||||
if (myFile != NULL)
|
||||
{
|
||||
strcpy(name, myFile.name());
|
||||
}
|
||||
else
|
||||
name[0] = 0;
|
||||
}
|
||||
|
||||
|
||||
|
@@ -24,10 +24,22 @@
|
||||
|
||||
#define FILE_TYPE_COUNT 3 // number of acceptable gcode file types in array
|
||||
|
||||
extern bool SD_file_running; // a file has started but not completed
|
||||
#define SDCARD_DET_PIN -1
|
||||
#define SDCARD_DET_VAL 0
|
||||
|
||||
#define SDCARD_IDLE 0
|
||||
#define SDCARD_NOT_PRESENT 1
|
||||
#define SDCARD_BUSY_PRINTING 2
|
||||
#define SDCARD_BUSY_UPLOADING 4
|
||||
#define SDCARD_BUSY_PARSING 8
|
||||
|
||||
|
||||
|
||||
extern bool SD_ready_next; // Grbl has processed a line and is waiting for another
|
||||
|
||||
bool sd_mount();
|
||||
uint8_t get_sd_state(bool refresh);
|
||||
uint8_t set_sd_state(uint8_t flag);
|
||||
void listDir(fs::FS &fs, const char * dirname, uint8_t levels);
|
||||
boolean openFile(fs::FS &fs, const char * path);
|
||||
boolean closeFile();
|
||||
@@ -35,4 +47,6 @@ boolean readFileLine(char *line);
|
||||
void readFile(fs::FS &fs, const char * path);
|
||||
float sd_report_perc_complete();
|
||||
|
||||
#endif
|
||||
void sd_get_current_filename(char* name);
|
||||
|
||||
#endif
|
||||
|
@@ -318,7 +318,7 @@ uint8_t mc_probe_cycle(float *target, plan_line_data_t *pl_data, uint8_t parser_
|
||||
|
||||
#ifdef MESSAGE_PROBE_COORDINATES
|
||||
// All done! Output the probe position as message.
|
||||
report_probe_parameters();
|
||||
report_probe_parameters(CLIENT_ALL);
|
||||
#endif
|
||||
|
||||
if (sys.probe_succeeded) { return(GC_PROBE_FOUND); } // Successful probe cycle.
|
||||
|
@@ -23,6 +23,7 @@
|
||||
*/
|
||||
|
||||
#include "grbl.h"
|
||||
#include "config.h"
|
||||
|
||||
// Define line flags. Includes comment type tracking and line overflow detection.
|
||||
#define LINE_FLAG_OVERFLOW bit(0)
|
||||
@@ -40,6 +41,8 @@ static void protocol_exec_rt_suspend();
|
||||
*/
|
||||
void protocol_main_loop()
|
||||
{
|
||||
//uint8_t client = CLIENT_SERIAL; // default client
|
||||
|
||||
// Perform some machine checks to make sure everything is good to go.
|
||||
#ifdef CHECK_LIMITS_AT_INIT
|
||||
if (bit_istrue(settings.flags, BITFLAG_HARD_LIMIT_ENABLE)) {
|
||||
@@ -74,14 +77,17 @@ void protocol_main_loop()
|
||||
uint8_t line_flags = 0;
|
||||
uint8_t char_counter = 0;
|
||||
uint8_t c;
|
||||
|
||||
for (;;) {
|
||||
|
||||
// serialCheck(); // un comment this if you do this here rather than in a separate task
|
||||
|
||||
#ifdef ENABLE_SD_CARD
|
||||
if (SD_ready_next) {
|
||||
char fileLine[255];
|
||||
if (readFileLine(fileLine)) {
|
||||
SD_ready_next = false;
|
||||
report_status_message(gc_execute_line(fileLine));
|
||||
report_status_message(gc_execute_line(fileLine, CLIENT_SERIAL), CLIENT_SERIAL);
|
||||
}
|
||||
else {
|
||||
closeFile(); // close file and clear SD ready/running flags
|
||||
@@ -93,85 +99,92 @@ void protocol_main_loop()
|
||||
|
||||
// Process one line of incoming serial data, as the data becomes available. Performs an
|
||||
// initial filtering by removing spaces and comments and capitalizing all letters.
|
||||
while((c = serial_read()) != SERIAL_NO_DATA) {
|
||||
if ((c == '\n') || (c == '\r')) { // End of line reached
|
||||
|
||||
uint8_t client = CLIENT_SERIAL;
|
||||
for (client = 1; client <= CLIENT_COUNT; client++)
|
||||
{
|
||||
while((c = serial_read(client)) != SERIAL_NO_DATA) {
|
||||
if ((c == '\n') || (c == '\r')) { // End of line reached
|
||||
|
||||
protocol_execute_realtime(); // Runtime command check point.
|
||||
if (sys.abort) { return; } // Bail to calling function upon system abort
|
||||
protocol_execute_realtime(); // Runtime command check point.
|
||||
if (sys.abort) { return; } // Bail to calling function upon system abort
|
||||
|
||||
line[char_counter] = 0; // Set string termination character.
|
||||
#ifdef REPORT_ECHO_LINE_RECEIVED
|
||||
report_echo_line_received(line);
|
||||
#endif
|
||||
line[char_counter] = 0; // Set string termination character.
|
||||
#ifdef REPORT_ECHO_LINE_RECEIVED
|
||||
report_echo_line_received(line, client);
|
||||
#endif
|
||||
|
||||
// Direct and execute one line of formatted input, and report status of execution.
|
||||
if (line_flags & LINE_FLAG_OVERFLOW) {
|
||||
// Report line overflow error.
|
||||
report_status_message(STATUS_OVERFLOW);
|
||||
} else if (line[0] == 0) {
|
||||
// Empty or comment line. For syncing purposes.
|
||||
report_status_message(STATUS_OK);
|
||||
} else if (line[0] == '$') {
|
||||
// Grbl '$' system command
|
||||
report_status_message(system_execute_line(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);
|
||||
} else {
|
||||
// Parse and execute g-code block.
|
||||
report_status_message(gc_execute_line(line));
|
||||
}
|
||||
// Direct and execute one line of formatted input, and report status of execution.
|
||||
if (line_flags & LINE_FLAG_OVERFLOW) {
|
||||
// Report line overflow error.
|
||||
report_status_message(STATUS_OVERFLOW, client);
|
||||
} else if (line[0] == 0) {
|
||||
// Empty or comment line. For syncing purposes.
|
||||
report_status_message(STATUS_OK, client);
|
||||
} else if (line[0] == '$') {
|
||||
// Grbl '$' system command
|
||||
report_status_message(system_execute_line(line, client), client);
|
||||
} 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.
|
||||
report_status_message(gc_execute_line(line, client), client);
|
||||
}
|
||||
|
||||
// Reset tracking data for next line.
|
||||
line_flags = 0;
|
||||
char_counter = 0;
|
||||
// Reset tracking data for next line.
|
||||
line_flags = 0;
|
||||
char_counter = 0;
|
||||
|
||||
} else {
|
||||
} else {
|
||||
|
||||
if (line_flags) {
|
||||
// Throw away all (except EOL) comment characters and overflow characters.
|
||||
if (c == ')') {
|
||||
// End of '()' comment. Resume line allowed.
|
||||
if (line_flags & LINE_FLAG_COMMENT_PARENTHESES) { line_flags &= ~(LINE_FLAG_COMMENT_PARENTHESES); }
|
||||
}
|
||||
} else {
|
||||
if (c <= ' ') {
|
||||
// Throw away whitepace and control characters
|
||||
}
|
||||
/*
|
||||
else if (c == '/') {
|
||||
// Block delete NOT SUPPORTED. Ignore character.
|
||||
// NOTE: If supported, would simply need to check the system if block delete is enabled.
|
||||
}
|
||||
*/
|
||||
else if (c == '(') {
|
||||
// Enable comments flag and ignore all characters until ')' or EOL.
|
||||
// NOTE: This doesn't follow the NIST definition exactly, but is good enough for now.
|
||||
// In the future, we could simply remove the items within the comments, but retain the
|
||||
// comment control characters, so that the g-code parser can error-check it.
|
||||
line_flags |= LINE_FLAG_COMMENT_PARENTHESES;
|
||||
} else if (c == ';') {
|
||||
// NOTE: ';' comment to EOL is a LinuxCNC definition. Not NIST.
|
||||
line_flags |= LINE_FLAG_COMMENT_SEMICOLON;
|
||||
// TODO: Install '%' feature
|
||||
// } else if (c == '%') {
|
||||
// Program start-end percent sign NOT SUPPORTED.
|
||||
// NOTE: This maybe installed to tell Grbl when a program is running vs manual input,
|
||||
// where, during a program, the system auto-cycle start will continue to execute
|
||||
// everything until the next '%' sign. This will help fix resuming issues with certain
|
||||
// functions that empty the planner buffer to execute its task on-time.
|
||||
} else if (char_counter >= (LINE_BUFFER_SIZE-1)) {
|
||||
// Detect line buffer overflow and set flag.
|
||||
line_flags |= LINE_FLAG_OVERFLOW;
|
||||
} else if (c >= 'a' && c <= 'z') { // Upcase lowercase
|
||||
line[char_counter++] = c-'a'+'A';
|
||||
} else {
|
||||
line[char_counter++] = c;
|
||||
}
|
||||
}
|
||||
if (line_flags) {
|
||||
// Throw away all (except EOL) comment characters and overflow characters.
|
||||
if (c == ')') {
|
||||
// End of '()' comment. Resume line allowed.
|
||||
if (line_flags & LINE_FLAG_COMMENT_PARENTHESES) { line_flags &= ~(LINE_FLAG_COMMENT_PARENTHESES); }
|
||||
}
|
||||
} else {
|
||||
if (c <= ' ') {
|
||||
// Throw away whitepace and control characters
|
||||
}
|
||||
/*
|
||||
else if (c == '/') {
|
||||
// Block delete NOT SUPPORTED. Ignore character.
|
||||
// NOTE: If supported, would simply need to check the system if block delete is enabled.
|
||||
}
|
||||
*/
|
||||
else if (c == '(') {
|
||||
// Enable comments flag and ignore all characters until ')' or EOL.
|
||||
// NOTE: This doesn't follow the NIST definition exactly, but is good enough for now.
|
||||
// In the future, we could simply remove the items within the comments, but retain the
|
||||
// comment control characters, so that the g-code parser can error-check it.
|
||||
line_flags |= LINE_FLAG_COMMENT_PARENTHESES;
|
||||
} else if (c == ';') {
|
||||
// NOTE: ';' comment to EOL is a LinuxCNC definition. Not NIST.
|
||||
line_flags |= LINE_FLAG_COMMENT_SEMICOLON;
|
||||
// TODO: Install '%' feature
|
||||
// } else if (c == '%') {
|
||||
// Program start-end percent sign NOT SUPPORTED.
|
||||
// NOTE: This maybe installed to tell Grbl when a program is running vs manual input,
|
||||
// where, during a program, the system auto-cycle start will continue to execute
|
||||
// everything until the next '%' sign. This will help fix resuming issues with certain
|
||||
// functions that empty the planner buffer to execute its task on-time.
|
||||
} else if (char_counter >= (LINE_BUFFER_SIZE-1)) {
|
||||
// Detect line buffer overflow and set flag.
|
||||
line_flags |= LINE_FLAG_OVERFLOW;
|
||||
} else if (c >= 'a' && c <= 'z') { // Upcase lowercase
|
||||
line[char_counter++] = c-'a'+'A';
|
||||
} else {
|
||||
line[char_counter++] = c;
|
||||
}
|
||||
}
|
||||
|
||||
}
|
||||
}
|
||||
}
|
||||
} // while serial read
|
||||
} // for clients
|
||||
|
||||
|
||||
|
||||
// If there are no more characters in the serial read buffer to be processed and executed,
|
||||
// this indicates that g-code streaming has either filled the planner buffer or has
|
||||
@@ -189,7 +202,9 @@ void protocol_main_loop()
|
||||
set_stepper_disable(true);
|
||||
}
|
||||
}
|
||||
|
||||
#ifdef ENABLE_WIFI
|
||||
wifi_config.handle();
|
||||
#endif
|
||||
}
|
||||
|
||||
return; /* Never reached */
|
||||
@@ -280,7 +295,7 @@ void protocol_exec_rt_system()
|
||||
|
||||
// Execute and serial print status
|
||||
if (rt_exec & EXEC_STATUS_REPORT) {
|
||||
report_realtime_status();
|
||||
report_realtime_status(CLIENT_ALL);
|
||||
system_clear_exec_state_flag(EXEC_STATUS_REPORT);
|
||||
}
|
||||
|
||||
@@ -496,19 +511,28 @@ void protocol_exec_rt_system()
|
||||
if (rt_exec & (EXEC_COOLANT_FLOOD_OVR_TOGGLE | EXEC_COOLANT_MIST_OVR_TOGGLE)) {
|
||||
if ((sys.state == STATE_IDLE) || (sys.state & (STATE_CYCLE | STATE_HOLD))) {
|
||||
uint8_t coolant_state = gc_state.modal.coolant;
|
||||
#ifdef ENABLE_M7
|
||||
if (rt_exec & EXEC_COOLANT_MIST_OVR_TOGGLE) {
|
||||
if (coolant_state & COOLANT_MIST_ENABLE) { bit_false(coolant_state,COOLANT_MIST_ENABLE); }
|
||||
else { coolant_state |= COOLANT_MIST_ENABLE; }
|
||||
#ifdef COOLANT_FLOOD_PIN
|
||||
if (rt_exec & EXEC_COOLANT_FLOOD_OVR_TOGGLE)
|
||||
{
|
||||
if (coolant_state & COOLANT_FLOOD_ENABLE) {
|
||||
bit_false(coolant_state,COOLANT_FLOOD_ENABLE);
|
||||
}
|
||||
else {
|
||||
coolant_state |= COOLANT_FLOOD_ENABLE;
|
||||
}
|
||||
}
|
||||
if (rt_exec & EXEC_COOLANT_FLOOD_OVR_TOGGLE) {
|
||||
if (coolant_state & COOLANT_FLOOD_ENABLE) { bit_false(coolant_state,COOLANT_FLOOD_ENABLE); }
|
||||
else { coolant_state |= COOLANT_FLOOD_ENABLE; }
|
||||
#endif
|
||||
#ifdef COOLANT_MIST_PIN
|
||||
if (rt_exec & EXEC_COOLANT_MIST_OVR_TOGGLE) {
|
||||
if (coolant_state & COOLANT_MIST_ENABLE) {
|
||||
bit_false(coolant_state,COOLANT_MIST_ENABLE);
|
||||
}
|
||||
else {
|
||||
coolant_state |= COOLANT_MIST_ENABLE;
|
||||
}
|
||||
}
|
||||
#else
|
||||
if (coolant_state & COOLANT_FLOOD_ENABLE) { bit_false(coolant_state,COOLANT_FLOOD_ENABLE); }
|
||||
else { coolant_state |= COOLANT_FLOOD_ENABLE; }
|
||||
#endif
|
||||
#endif
|
||||
|
||||
coolant_set_state(coolant_state); // Report counter set in coolant_set_state().
|
||||
gc_state.modal.coolant = coolant_state;
|
||||
}
|
||||
|
@@ -4,7 +4,7 @@
|
||||
|
||||
Copyright (c) 2012-2016 Sungeun K. Jeon for Gnea Research LLC
|
||||
|
||||
2018 - Bart Dring This file was modifed for use on the ESP32
|
||||
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
|
||||
@@ -26,7 +26,7 @@
|
||||
as the protocol status messages, feedback messages, and status reports, are stored here.
|
||||
For the most part, these functions primarily are called from protocol.c methods. If a
|
||||
different style feedback is desired (i.e. JSON), then a user can change these following
|
||||
methods to accomodate their needs.
|
||||
methods to accommodate their needs.
|
||||
|
||||
|
||||
ESP32 Notes:
|
||||
@@ -50,21 +50,28 @@
|
||||
|
||||
|
||||
// this is a generic send function that everything should use, so interfaces could be added (Bluetooth, etc)
|
||||
void grbl_send(char *text)
|
||||
void grbl_send(uint8_t client, char *text)
|
||||
{
|
||||
#ifdef ENABLE_BLUETOOTH
|
||||
if (SerialBT.hasClient())
|
||||
{
|
||||
SerialBT.print(text);
|
||||
//delay(10); // possible fix for dropped characters
|
||||
}
|
||||
#endif
|
||||
#ifdef ENABLE_BLUETOOTH
|
||||
if (SerialBT.hasClient() && ( client == CLIENT_BT || client == CLIENT_ALL ) )
|
||||
{
|
||||
|
||||
SerialBT.print(text);
|
||||
//delay(10); // possible fix for dropped characters
|
||||
}
|
||||
#endif
|
||||
|
||||
#if defined (ENABLE_WIFI) && defined(ENABLE_HTTP) && defined(ENABLE_SERIAL2SOCKET_OUT)
|
||||
if ( client == CLIENT_WEBUI || client == CLIENT_ALL )
|
||||
Serial2Socket.write((const uint8_t*)text, strlen(text));
|
||||
#endif
|
||||
|
||||
Serial.print(text);
|
||||
if ( client == CLIENT_SERIAL || client == CLIENT_ALL )
|
||||
Serial.print(text);
|
||||
}
|
||||
|
||||
// This is a formating version of the grbl_send(...) function that work like printf
|
||||
void grbl_sendf(const char *format, ...)
|
||||
// This is a formating version of the grbl_send(CLIENT_ALL,...) function that work like printf
|
||||
void grbl_sendf(uint8_t client, const char *format, ...)
|
||||
{
|
||||
char loc_buf[64];
|
||||
char * temp = loc_buf;
|
||||
@@ -81,7 +88,7 @@ void grbl_sendf(const char *format, ...)
|
||||
}
|
||||
}
|
||||
len = vsnprintf(temp, len+1, format, arg);
|
||||
grbl_send(temp);
|
||||
grbl_send(client, temp);
|
||||
va_end(arg);
|
||||
if(len > 64){
|
||||
delete[] temp;
|
||||
@@ -128,21 +135,21 @@ void get_state(char *foo)
|
||||
// operation. Errors events can originate from the g-code parser, settings module, or asynchronously
|
||||
// from a critical error, such as a triggered hard limit. Interface should always monitor for these
|
||||
// responses.
|
||||
void report_status_message(uint8_t status_code)
|
||||
void report_status_message(uint8_t status_code, uint8_t client)
|
||||
{
|
||||
switch(status_code) {
|
||||
case STATUS_OK: // STATUS_OK
|
||||
#ifdef ENABLE_SD_CARD
|
||||
if (SD_file_running)
|
||||
if (get_sd_state(false) == SDCARD_BUSY_PRINTING)
|
||||
SD_ready_next = true; // flag so system_execute_line() will send the next line
|
||||
else
|
||||
grbl_send("ok\r\n");
|
||||
grbl_send(client,"ok\r\n");
|
||||
#else
|
||||
grbl_send("ok\r\n");
|
||||
grbl_send(client,"ok\r\n");
|
||||
#endif
|
||||
break;
|
||||
default:
|
||||
grbl_sendf("error:%d\r\n", status_code);
|
||||
grbl_sendf(client, "error:%d\r\n", status_code);
|
||||
}
|
||||
}
|
||||
|
||||
@@ -151,7 +158,7 @@ void report_status_message(uint8_t status_code)
|
||||
// Prints alarm messages.
|
||||
void report_alarm_message(uint8_t alarm_code)
|
||||
{
|
||||
grbl_sendf("ALARM:%d\r\n", alarm_code);
|
||||
grbl_sendf(CLIENT_ALL, "ALARM:%d\r\n", alarm_code); // OK to send to all clients
|
||||
delay_ms(500); // Force delay to ensure message clears serial write buffer.
|
||||
}
|
||||
|
||||
@@ -160,56 +167,50 @@ void report_alarm_message(uint8_t alarm_code)
|
||||
// messages such as setup warnings, switch toggling, and how to exit alarms.
|
||||
// NOTE: For interfaces, messages are always placed within brackets. And if silent mode
|
||||
// is installed, the message number codes are less than zero.
|
||||
void report_feedback_message(uint8_t message_code)
|
||||
void report_feedback_message(uint8_t message_code) // OK to send to all clients
|
||||
{
|
||||
switch(message_code) {
|
||||
case MESSAGE_CRITICAL_EVENT:
|
||||
grbl_sendf("[MSG:%s]\r\n", "Reset to continue"); break;
|
||||
grbl_send(CLIENT_ALL,"[MSG:Reset to continue]\r\n"); break;
|
||||
case MESSAGE_ALARM_LOCK:
|
||||
grbl_sendf("[MSG:%s]\r\n", "'$H'|'$X' to unlock"); break;
|
||||
grbl_send(CLIENT_ALL, "[MSG:'$H'|'$X' to unlock]\r\n"); break;
|
||||
case MESSAGE_ALARM_UNLOCK:
|
||||
grbl_sendf("[MSG:%s]\r\n", "Caution: Unlocked"); break;
|
||||
grbl_send(CLIENT_ALL, "[MSG:Caution: Unlocked]\r\n"); break;
|
||||
case MESSAGE_ENABLED:
|
||||
grbl_sendf("[MSG:%s]\r\n", "Enabled"); break;
|
||||
grbl_send(CLIENT_ALL, "[MSG:Enabled]\r\n"); break;
|
||||
case MESSAGE_DISABLED:
|
||||
grbl_sendf("[MSG:%s]\r\n", "Disabled"); break;
|
||||
grbl_send(CLIENT_ALL, "[MSG:Disabled]\r\n"); break;
|
||||
case MESSAGE_SAFETY_DOOR_AJAR:
|
||||
grbl_sendf("[MSG:%s]\r\n", "Check Door"); break;
|
||||
grbl_send(CLIENT_ALL, "[MSG:Check Door]\r\n"); break;
|
||||
case MESSAGE_CHECK_LIMITS:
|
||||
grbl_sendf("[MSG:%s]\r\n", "Check Limits"); break;
|
||||
grbl_send(CLIENT_ALL, "[MSG:Check Limits]\r\n"); break;
|
||||
case MESSAGE_PROGRAM_END:
|
||||
grbl_sendf("[MSG:%s]\r\n", "Pgm End"); break;
|
||||
grbl_send(CLIENT_ALL, "[MSG:Pgm End]\r\n"); break;
|
||||
case MESSAGE_RESTORE_DEFAULTS:
|
||||
grbl_sendf("[MSG:%s]\r\n", "Restoring defaults"); break;
|
||||
grbl_send(CLIENT_ALL, "[MSG:Restoring defaults]\r\n"); break;
|
||||
case MESSAGE_SPINDLE_RESTORE:
|
||||
grbl_sendf("[MSG:%s]\r\n", "Restoring spindle"); break;
|
||||
grbl_send(CLIENT_ALL, "[MSG:Restoring spindle]\r\n"); break;
|
||||
case MESSAGE_SLEEP_MODE:
|
||||
grbl_sendf("[MSG:%s]\r\n", "Sleeping"); break;
|
||||
grbl_send(CLIENT_ALL, "[MSG:Sleeping]\r\n"); break;
|
||||
}
|
||||
}
|
||||
|
||||
|
||||
// Welcome message
|
||||
void report_init_message()
|
||||
void report_init_message(uint8_t client)
|
||||
{
|
||||
grbl_send("\r\nGrbl " GRBL_VERSION " ['$' for help]\r\n");
|
||||
grbl_send(client,"\r\nGrbl " GRBL_VERSION " ['$' for help]\r\n");
|
||||
}
|
||||
|
||||
// Grbl help message
|
||||
void report_grbl_help() {
|
||||
grbl_send("[HLP:$$ $# $G $I $N $x=val $Nx=line $J=line $SLP $C $X $H $F ~ ! ? ctrl-x]\r\n");
|
||||
#ifdef VERBOSE_HELP
|
||||
#ifdef ENABLE_BLUETOOTH
|
||||
return; // to much data for BT until fixed
|
||||
#endif
|
||||
settings_help();
|
||||
#endif
|
||||
void report_grbl_help(uint8_t client) {
|
||||
grbl_send(client,"[HLP:$$ $# $G $I $N $x=val $Nx=line $J=line $SLP $C $X $H $F ~ ! ? ctrl-x]\r\n");
|
||||
}
|
||||
|
||||
|
||||
// Grbl global settings print out.
|
||||
// NOTE: The numbering scheme here must correlate to storing in settings.c
|
||||
void report_grbl_settings() {
|
||||
void report_grbl_settings(uint8_t client) {
|
||||
// Print Grbl settings.
|
||||
char setting[20];
|
||||
char rpt[800];
|
||||
@@ -264,7 +265,7 @@ void report_grbl_settings() {
|
||||
val += AXIS_SETTINGS_INCREMENT;
|
||||
}
|
||||
|
||||
grbl_send(rpt);
|
||||
grbl_send(client,rpt);
|
||||
}
|
||||
|
||||
|
||||
@@ -275,7 +276,7 @@ void report_grbl_settings() {
|
||||
// Prints current probe parameters. Upon a probe command, these parameters are updated upon a
|
||||
// successful probe or upon a failed probe with the G38.3 without errors command (if supported).
|
||||
// These values are retained until Grbl is power-cycled, whereby they will be re-zeroed.
|
||||
void report_probe_parameters()
|
||||
void report_probe_parameters(uint8_t client)
|
||||
{
|
||||
// Report in terms of machine position.
|
||||
float print_position[N_AXIS];
|
||||
@@ -293,14 +294,14 @@ void report_probe_parameters()
|
||||
sprintf(temp, ":%d]\r\n", sys.probe_succeeded);
|
||||
strcat(probe_rpt, temp);
|
||||
|
||||
grbl_send(probe_rpt); // send the report
|
||||
grbl_send(client, probe_rpt); // send the report
|
||||
}
|
||||
|
||||
|
||||
|
||||
|
||||
// Prints Grbl NGC parameters (coordinate offsets, probing)
|
||||
void report_ngc_parameters()
|
||||
void report_ngc_parameters(uint8_t client)
|
||||
{
|
||||
float coord_data[N_AXIS];
|
||||
uint8_t coord_select;
|
||||
@@ -311,7 +312,7 @@ void report_ngc_parameters()
|
||||
|
||||
for (coord_select = 0; coord_select <= SETTING_INDEX_NCOORD; coord_select++) {
|
||||
if (!(settings_read_coord_data(coord_select,coord_data))) {
|
||||
report_status_message(STATUS_SETTING_READ_FAIL);
|
||||
report_status_message(STATUS_SETTING_READ_FAIL, CLIENT_SERIAL);
|
||||
return;
|
||||
}
|
||||
strcat(ngc_rpt, "[G");
|
||||
@@ -342,15 +343,15 @@ void report_ngc_parameters()
|
||||
}
|
||||
strcat(ngc_rpt, temp);
|
||||
|
||||
grbl_send(ngc_rpt);
|
||||
grbl_send(client, ngc_rpt);
|
||||
|
||||
report_probe_parameters(); // TDO ======================= Print probe parameters. Not persistent in memory.
|
||||
report_probe_parameters(client);
|
||||
}
|
||||
|
||||
|
||||
|
||||
// Print current gcode parser mode state
|
||||
void report_gcode_modes()
|
||||
void report_gcode_modes(uint8_t client)
|
||||
{
|
||||
char temp[20];
|
||||
char modes_rpt[75];
|
||||
@@ -402,16 +403,14 @@ void report_gcode_modes()
|
||||
case SPINDLE_DISABLE : strcat(modes_rpt, " M5"); break;
|
||||
}
|
||||
|
||||
//report_util_gcode_modes_M();
|
||||
#ifdef ENABLE_M7
|
||||
if (gc_state.modal.coolant) { // Note: Multiple coolant states may be active at the same time.
|
||||
if (gc_state.modal.coolant & PL_COND_FLAG_COOLANT_MIST) { strcat(modes_rpt, " M7"); }
|
||||
if (gc_state.modal.coolant & PL_COND_FLAG_COOLANT_FLOOD) { strcat(modes_rpt, " M8"); }
|
||||
} else { strcat(modes_rpt, " M9"); }
|
||||
#else
|
||||
if (gc_state.modal.coolant) { strcat(modes_rpt, " M8"); }
|
||||
else { strcat(modes_rpt, " M9"); }
|
||||
#endif
|
||||
//report_util_gcode_modes_M(); // optional M7 and M8 should have been dealt with by here
|
||||
if (gc_state.modal.coolant) { // Note: Multiple coolant states may be active at the same time.
|
||||
if (gc_state.modal.coolant & PL_COND_FLAG_COOLANT_MIST) { strcat(modes_rpt, " M7"); }
|
||||
if (gc_state.modal.coolant & PL_COND_FLAG_COOLANT_FLOOD) { strcat(modes_rpt, " M8"); }
|
||||
}
|
||||
else {
|
||||
strcat(modes_rpt, " M9");
|
||||
}
|
||||
|
||||
sprintf(temp, " T%d", gc_state.tool);
|
||||
strcat(modes_rpt, temp);
|
||||
@@ -426,28 +425,25 @@ void report_gcode_modes()
|
||||
|
||||
strcat(modes_rpt, "]\r\n");
|
||||
|
||||
grbl_send(modes_rpt);
|
||||
grbl_send(client, modes_rpt);
|
||||
}
|
||||
|
||||
|
||||
|
||||
// Prints specified startup line
|
||||
void report_startup_line(uint8_t n, char *line)
|
||||
void report_startup_line(uint8_t n, char *line, uint8_t client)
|
||||
{
|
||||
grbl_sendf("$N%d=%s\r\n", n, line);
|
||||
grbl_sendf(client, "$N%d=%s\r\n", n, line); // OK to send to all
|
||||
}
|
||||
|
||||
void report_execute_startup_message(char *line, uint8_t status_code)
|
||||
{
|
||||
char temp[80];
|
||||
|
||||
grbl_sendf(">%s:", line);
|
||||
|
||||
report_status_message(status_code); // TODO reduce number of back to back BT sends
|
||||
void report_execute_startup_message(char *line, uint8_t status_code, uint8_t client)
|
||||
{
|
||||
grbl_sendf(client, ">%s:", line); // OK to send to all
|
||||
report_status_message(status_code, client);
|
||||
}
|
||||
|
||||
|
||||
// Prints build info line
|
||||
void report_build_info(char *line)
|
||||
void report_build_info(char *line, uint8_t client)
|
||||
{
|
||||
char build_info[50];
|
||||
|
||||
@@ -461,8 +457,8 @@ void report_build_info(char *line)
|
||||
#ifdef USE_LINE_NUMBERS
|
||||
strcat(build_info,"N");
|
||||
#endif
|
||||
#ifdef ENABLE_M7
|
||||
strcat(build_info,"M");
|
||||
#ifdef COOLANT_MIST_PIN
|
||||
strcat(build_info,"M"); // TODO Need to deal with M8...it could be disabled
|
||||
#endif
|
||||
#ifdef COREXY
|
||||
strcat(build_info,"C");
|
||||
@@ -510,7 +506,7 @@ void report_build_info(char *line)
|
||||
// These will likely have a comma delimiter to separate them.
|
||||
|
||||
strcat(build_info,"]\r\n");
|
||||
grbl_send(build_info);
|
||||
grbl_send(client, build_info); // ok to send to all
|
||||
}
|
||||
|
||||
|
||||
@@ -518,23 +514,17 @@ void report_build_info(char *line)
|
||||
|
||||
// Prints the character string line Grbl has received from the user, which has been pre-parsed,
|
||||
// and has been sent into protocol_execute_line() routine to be executed by Grbl.
|
||||
void report_echo_line_received(char *line)
|
||||
{
|
||||
char temp[80];
|
||||
|
||||
sprintf(temp, "[echo: %s]\r\n", line);
|
||||
|
||||
void report_echo_line_received(char *line, uint8_t client)
|
||||
{
|
||||
grbl_sendf(client, "[echo: %s]\r\n", line);
|
||||
}
|
||||
|
||||
//--------------------------------------------- Converted up to here ---------------------------------------------------------------------
|
||||
|
||||
|
||||
// Prints real-time data. This function grabs a real-time snapshot of the stepper subprogram
|
||||
// and the actual location of the CNC machine. Users may change the following function to their
|
||||
// specific needs, but the desired real-time data report must be as short as possible. This is
|
||||
// requires as it minimizes the computational overhead and allows grbl to keep running smoothly,
|
||||
// especially during g-code programs with fast, short line segments and high frequency reports (5-20Hz).
|
||||
void report_realtime_status()
|
||||
void report_realtime_status(uint8_t client)
|
||||
{
|
||||
uint8_t idx;
|
||||
int32_t current_position[N_AXIS]; // Copy current state of the system position variable
|
||||
@@ -607,7 +597,7 @@ void report_realtime_status()
|
||||
// Returns planner and serial read buffer states.
|
||||
#ifdef REPORT_FIELD_BUFFER_STATE
|
||||
if (bit_istrue(settings.status_report_mask,BITFLAG_RT_STATUS_BUFFER_STATE)) {
|
||||
sprintf(temp, "|Bf:%d,%d", plan_get_block_buffer_available(), serial_get_rx_buffer_available());
|
||||
sprintf(temp, "|Bf:%d,%d", plan_get_block_buffer_available(), serial_get_rx_buffer_available(CLIENT_SERIAL));
|
||||
strcat(status, temp);
|
||||
}
|
||||
#endif
|
||||
@@ -711,7 +701,7 @@ void report_realtime_status()
|
||||
#endif
|
||||
}
|
||||
if (cl_state & COOLANT_STATE_FLOOD) { strcat(status, "F"); }
|
||||
#ifdef ENABLE_M7
|
||||
#ifdef COOLANT_MIST_PIN // TODO Deal with M8 - Flood
|
||||
if (cl_state & COOLANT_STATE_MIST) { strcat(status, "M"); }
|
||||
#endif
|
||||
}
|
||||
@@ -719,61 +709,24 @@ void report_realtime_status()
|
||||
#endif
|
||||
|
||||
#ifdef ENABLE_SD_CARD
|
||||
if (SD_file_running) {
|
||||
sprintf(temp, "|SD:%4.2f", sd_report_perc_complete());
|
||||
if (get_sd_state(false) == SDCARD_BUSY_PRINTING) {
|
||||
sprintf(temp, "|SD:%4.2f,", sd_report_perc_complete());
|
||||
strcat(status, temp);
|
||||
|
||||
sd_get_current_filename(temp);
|
||||
strcat(status, temp);
|
||||
}
|
||||
#endif
|
||||
|
||||
strcat(status, ">\r\n");
|
||||
|
||||
grbl_send(status);
|
||||
grbl_send(client, status);
|
||||
}
|
||||
|
||||
void report_realtime_steps()
|
||||
{
|
||||
uint8_t idx;
|
||||
for (idx=0; idx< N_AXIS; idx++) {
|
||||
Serial.println(sys_position[idx]);
|
||||
grbl_sendf(CLIENT_ALL, "%ld\n", sys_position[idx]); // OK to send to all ... debug stuff
|
||||
}
|
||||
}
|
||||
|
||||
void settings_help()
|
||||
{
|
||||
Serial.println("[HLP ----------- Setting Descriptions -----------]");
|
||||
Serial.println("[HLP $0=Step Pulse Delay (3-255)]");
|
||||
Serial.println("[HLP $1=Step Idle Delay (0-254, 255 keeps motors on)]");
|
||||
Serial.println("[HLP $2=Step Pulse Invert Mask(00000ZYZ)]");
|
||||
Serial.println("[HLP $3=Direction Invert Mask(00000XYZ)]");
|
||||
Serial.println("[HLP $4=Step Enable Invert (boolean)]");
|
||||
Serial.println("[HLP $6=Invert Probe Pin (boolean)]");
|
||||
Serial.println("[HLP $10Status Report Options (See Wiki)]");
|
||||
Serial.println("[HLP $11=Junction Deviation (float millimeters)]");
|
||||
Serial.println("[HLP $12=Arc Tolerance (float millimeters)]");
|
||||
Serial.println("[HLP $13=Report in Inches (boolean)]");
|
||||
Serial.println("[HLP $20=Soft Limits Enable (boolean)]");
|
||||
Serial.println("[HLP $21=Hard Limits Enable (boolean)]");
|
||||
Serial.println("[HLP $22=Homing Enable (boolean)]");
|
||||
Serial.println("[HLP $23=Homing Direction Invert (00000ZYX)]");
|
||||
Serial.println("[HLP $24=Homing Feed Rate (mm/min)]");
|
||||
Serial.println("[HLP $25=Homing Seek Rate (mm/min)]");
|
||||
Serial.println("[HLP $26=Homing Switch Debounce Delay (milliseconds)]");
|
||||
Serial.println("[HLP $27=Homing Switch Pull-off Distance (millimeters)]");
|
||||
Serial.println("[HLP $30=Max Spindle Speed (RPM)]");
|
||||
Serial.println("[HLP $31=Min Spindle Speed (RPM)]");
|
||||
Serial.println("[HLP $32=Laser Mode Enable (boolean)]");
|
||||
Serial.println("[HLP $100-102= XYZ Axis Resolution (step/mm)]");
|
||||
Serial.println("[HLP $110-112= XYZ Axis Max Rate (mm/min)]");
|
||||
Serial.println("[HLP $120-122= XYZ Axis Acceleration (step/mm^2)]");
|
||||
Serial.println("[HLP $130-132= XYZ Axis max Travel (step/mm)]");
|
||||
|
||||
}
|
||||
|
||||
#ifdef DEBUG
|
||||
void report_realtime_debug()
|
||||
{
|
||||
|
||||
}
|
||||
#endif
|
||||
|
||||
|
||||
}
|
@@ -97,12 +97,18 @@
|
||||
#define MESSAGE_SPINDLE_RESTORE 10
|
||||
#define MESSAGE_SLEEP_MODE 11
|
||||
|
||||
#define CLIENT_SERIAL 1
|
||||
#define CLIENT_BT 2
|
||||
#define CLIENT_WEBUI 3
|
||||
#define CLIENT_ALL 0xFF
|
||||
#define CLIENT_COUNT 3 // total number of client types regardless if they are used
|
||||
|
||||
// functions to send data to the user.
|
||||
void grbl_send(char *text);
|
||||
void grbl_sendf(const char *format, ...);
|
||||
void grbl_send(uint8_t client, char *text);
|
||||
void grbl_sendf(uint8_t client, const char *format, ...);
|
||||
|
||||
// Prints system status messages.
|
||||
void report_status_message(uint8_t status_code);
|
||||
void report_status_message(uint8_t status_code, uint8_t client);
|
||||
void report_realtime_steps();
|
||||
|
||||
// Prints system alarm messages.
|
||||
@@ -112,40 +118,40 @@ void report_alarm_message(uint8_t alarm_code);
|
||||
void report_feedback_message(uint8_t message_code);
|
||||
|
||||
// Prints welcome message
|
||||
void report_init_message();
|
||||
void report_init_message(uint8_t client);
|
||||
|
||||
// Prints Grbl help and current global settings
|
||||
void report_grbl_help();
|
||||
void report_grbl_help(uint8_t client);
|
||||
|
||||
// Prints Grbl global settings
|
||||
void report_grbl_settings();
|
||||
void report_grbl_settings(uint8_t client);
|
||||
|
||||
// Prints an echo of the pre-parsed line received right before execution.
|
||||
void report_echo_line_received(char *line);
|
||||
void report_echo_line_received(char *line, uint8_t client);
|
||||
|
||||
// Prints realtime status report
|
||||
void report_realtime_status();
|
||||
void report_realtime_status(uint8_t client);
|
||||
|
||||
// Prints recorded probe position
|
||||
void report_probe_parameters();
|
||||
void report_probe_parameters(uint8_t client);
|
||||
|
||||
// Prints Grbl NGC parameters (coordinate offsets, probe)
|
||||
void report_ngc_parameters();
|
||||
void report_ngc_parameters(uint8_t client);
|
||||
|
||||
// Prints current g-code parser mode state
|
||||
void report_gcode_modes();
|
||||
void report_gcode_modes(uint8_t client);
|
||||
|
||||
// Prints startup line when requested and executed.
|
||||
void report_startup_line(uint8_t n, char *line);
|
||||
void report_execute_startup_message(char *line, uint8_t status_code);
|
||||
void report_startup_line(uint8_t n, char *line, uint8_t client);
|
||||
void report_execute_startup_message(char *line, uint8_t status_code, uint8_t client);
|
||||
|
||||
// Prints build info and user info
|
||||
void report_build_info(char *line);
|
||||
void report_build_info(char *line, uint8_t client);
|
||||
|
||||
#ifdef DEBUG
|
||||
void report_realtime_debug();
|
||||
#endif
|
||||
|
||||
void settings_help();
|
||||
|
||||
|
||||
#endif
|
||||
|
@@ -25,22 +25,24 @@
|
||||
|
||||
portMUX_TYPE myMutex = portMUX_INITIALIZER_UNLOCKED;
|
||||
|
||||
uint8_t serial_rx_buffer[RX_RING_BUFFER];
|
||||
uint8_t serial_rx_buffer_head = 0;
|
||||
volatile uint8_t serial_rx_buffer_tail = 0;
|
||||
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};
|
||||
|
||||
|
||||
// Returns the number of bytes available in the RX serial buffer.
|
||||
uint8_t serial_get_rx_buffer_available()
|
||||
uint8_t serial_get_rx_buffer_available(uint8_t client)
|
||||
{
|
||||
uint8_t rtail = serial_rx_buffer_tail; // Copy to limit multiple calls to volatile
|
||||
if (serial_rx_buffer_head >= rtail) { return(RX_BUFFER_SIZE - (serial_rx_buffer_head-rtail)); }
|
||||
return((rtail-serial_rx_buffer_head-1));
|
||||
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));
|
||||
}
|
||||
|
||||
void serial_init()
|
||||
{
|
||||
Serial.begin(BAUD_RATE);
|
||||
Serial.begin(BAUD_RATE);
|
||||
|
||||
// create a task to check for incoming data
|
||||
xTaskCreatePinnedToCore( serialCheckTask, // task
|
||||
@@ -51,43 +53,66 @@ void serial_init()
|
||||
&serialCheckTaskHandle,
|
||||
0 // core
|
||||
);
|
||||
|
||||
}
|
||||
|
||||
|
||||
// this task runs and checks for data on all interfaces, currently
|
||||
// only hardware serial port is checked
|
||||
// This was normally done in an interrupt on 8-bit Grbl
|
||||
// this task runs and checks for data on all interfaces
|
||||
// REaltime stuff is acted upon, then characters are added to the appropriate buffer
|
||||
void serialCheckTask(void *pvParameters)
|
||||
{
|
||||
uint8_t data;
|
||||
uint8_t next_head;
|
||||
uint8_t client; // who send the data
|
||||
|
||||
uint8_t client_idx = 0; // index of data buffer
|
||||
|
||||
while(true) // run continuously
|
||||
{
|
||||
{
|
||||
while (Serial.available()
|
||||
#ifdef ENABLE_BLUETOOTH
|
||||
while (Serial.available() || (SerialBT.hasClient() && SerialBT.available()))
|
||||
#else
|
||||
while (Serial.available())
|
||||
|| (SerialBT.hasClient() && SerialBT.available())
|
||||
#endif
|
||||
#if defined (ENABLE_WIFI) && defined(ENABLE_HTTP) && defined(ENABLE_SERIAL2SOCKET_IN)
|
||||
|| Serial2Socket.available()
|
||||
#endif
|
||||
)
|
||||
{
|
||||
if (Serial.available())
|
||||
data = Serial.read();
|
||||
else
|
||||
if (Serial.available())
|
||||
{
|
||||
client = CLIENT_SERIAL;
|
||||
data = Serial.read();
|
||||
}
|
||||
else
|
||||
{ //currently is wifi or BT but better to prepare both can be live
|
||||
#ifdef ENABLE_BLUETOOTH
|
||||
data = SerialBT.read();
|
||||
Serial.write(data); // echo all data to serial
|
||||
if(SerialBT.hasClient() && SerialBT.available()){
|
||||
client = CLIENT_BT;
|
||||
data = SerialBT.read();
|
||||
//Serial.write(data); // echo all data to serial
|
||||
} else {
|
||||
#endif
|
||||
}
|
||||
|
||||
|
||||
#if defined (ENABLE_WIFI) && defined(ENABLE_HTTP) && defined(ENABLE_SERIAL2SOCKET_IN)
|
||||
client = CLIENT_WEBUI;
|
||||
data = Serial2Socket.read();
|
||||
#endif
|
||||
#ifdef ENABLE_BLUETOOTH
|
||||
}
|
||||
#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(); break; // Call motion control reset routine.
|
||||
case CMD_STATUS_REPORT: report_realtime_status(); break; // direct call instead of setting flag
|
||||
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 :
|
||||
@@ -116,8 +141,10 @@ void serialCheckTask(void *pvParameters)
|
||||
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;
|
||||
#ifdef ENABLE_M7
|
||||
#endif
|
||||
#ifdef COOLANT_MIST_PIN
|
||||
case CMD_COOLANT_MIST_OVR_TOGGLE: system_set_exec_accessory_override_flag(EXEC_COOLANT_MIST_OVR_TOGGLE); break;
|
||||
#endif
|
||||
}
|
||||
@@ -125,28 +152,135 @@ void serialCheckTask(void *pvParameters)
|
||||
} else { // Write character to buffer
|
||||
|
||||
vTaskEnterCritical(&myMutex);
|
||||
next_head = serial_rx_buffer_head + 1;
|
||||
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) {
|
||||
serial_rx_buffer[serial_rx_buffer_head] = data;
|
||||
serial_rx_buffer_head = next_head;
|
||||
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;
|
||||
}
|
||||
vTaskExitCritical(&myMutex);
|
||||
}
|
||||
} // switch data
|
||||
|
||||
|
||||
|
||||
} // if something available
|
||||
vTaskDelay(1 / portTICK_RATE_MS); // Yield to other tasks
|
||||
} // while(true)
|
||||
}
|
||||
|
||||
void serial_reset_read_buffer()
|
||||
// ==================== 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()
|
||||
{
|
||||
serial_rx_buffer_tail = serial_rx_buffer_head;
|
||||
uint8_t data;
|
||||
uint8_t next_head;
|
||||
uint8_t client; // who send the data
|
||||
|
||||
uint8_t client_idx = 0; // index of data buffer
|
||||
|
||||
|
||||
while (Serial.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
|
||||
{ //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 {
|
||||
#endif
|
||||
#if defined (ENABLE_WIFI) && defined(ENABLE_HTTP) && defined(ENABLE_SERIAL2SOCKET_IN)
|
||||
client = CLIENT_WEBUI;
|
||||
data = Serial2Socket.read();
|
||||
#endif
|
||||
#ifdef ENABLE_BLUETOOTH
|
||||
}
|
||||
#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(); 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
|
||||
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);
|
||||
}
|
||||
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
|
||||
|
||||
|
||||
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 = 1; 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.
|
||||
@@ -154,18 +288,20 @@ 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 serial_read(uint8_t client)
|
||||
{
|
||||
uint8_t tail = serial_rx_buffer_tail; // Temporary serial_rx_buffer_tail (to optimize for volatile)
|
||||
if (serial_rx_buffer_head == tail) {
|
||||
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[tail];
|
||||
uint8_t data = serial_rx_buffer[client_idx][tail];
|
||||
|
||||
tail++;
|
||||
if (tail == RX_RING_BUFFER) { tail = 0; }
|
||||
serial_rx_buffer_tail = tail;
|
||||
serial_rx_buffer_tail[client_idx] = tail;
|
||||
vTaskExitCritical(&myMutex);
|
||||
return data;
|
||||
}
|
||||
|
@@ -40,17 +40,19 @@
|
||||
static TaskHandle_t serialCheckTaskHandle = 0;
|
||||
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 serial_read(uint8_t client);
|
||||
|
||||
// See if the character is an action command like feedhold or jogging. If so, do the action and return true
|
||||
uint8_t check_action_command(uint8_t data);
|
||||
|
||||
void serial_init();
|
||||
void serial_reset_read_buffer();
|
||||
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 serial_get_rx_buffer_available(uint8_t client);
|
||||
|
||||
#endif
|
||||
|
@@ -41,9 +41,9 @@ void settings_init()
|
||||
EEPROM.begin(EEPROM_SIZE);
|
||||
|
||||
if(!read_global_settings()) {
|
||||
report_status_message(STATUS_SETTING_READ_FAIL);
|
||||
report_status_message(STATUS_SETTING_READ_FAIL, CLIENT_SERIAL);
|
||||
settings_restore(SETTINGS_RESTORE_ALL); // Force restore all EEPROM data.
|
||||
report_grbl_settings();
|
||||
report_grbl_settings(CLIENT_SERIAL); // only the serial could be working at this point
|
||||
}
|
||||
}
|
||||
|
||||
@@ -331,9 +331,7 @@ uint8_t get_step_pin_mask(uint8_t axis_idx)
|
||||
|
||||
// Returns direction pin mask according to Grbl internal axis indexing.
|
||||
uint8_t get_direction_pin_mask(uint8_t axis_idx)
|
||||
{
|
||||
if ( axis_idx == X_AXIS ) { return((1<<X_DIRECTION_BIT)); }
|
||||
if ( axis_idx == Y_AXIS ) { return((1<<Y_DIRECTION_BIT)); }
|
||||
return((1<<Z_DIRECTION_BIT));
|
||||
{
|
||||
return(1<<axis_idx);
|
||||
}
|
||||
|
||||
|
@@ -3,7 +3,7 @@
|
||||
Part of Grbl
|
||||
Copyright (c) 2014-2016 Sungeun K. Jeon for Gnea Research LLC
|
||||
|
||||
2018 - Bart Dring This file was modifed for use on the ESP32
|
||||
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
|
||||
@@ -23,37 +23,76 @@
|
||||
void spindle_init()
|
||||
{
|
||||
|
||||
// Use DIR and Enable if pins are defined
|
||||
#ifdef SPINDLE_ENABLE_PIN
|
||||
pinMode(SPINDLE_ENABLE_PIN, OUTPUT);
|
||||
#endif
|
||||
|
||||
#ifdef SPINDLE_DIR_PIN
|
||||
pinMode(SPINDLE_DIR_PIN, OUTPUT);
|
||||
#endif
|
||||
|
||||
#ifdef SPINDLE_PWM_PIN
|
||||
// use the LED control feature to setup PWM https://esp-idf.readthedocs.io/en/v1.0/api/ledc.html
|
||||
ledcSetup(SPINDLE_PWM_CHANNEL, SPINDLE_PWM_BASE_FREQ, SPINDLE_PWM_BIT_PRECISION); // setup the channel
|
||||
ledcAttachPin(SPINDLE_PWM_PIN, SPINDLE_PWM_CHANNEL); // attach the PWM to the pin
|
||||
|
||||
// Start with PWM off
|
||||
#endif
|
||||
|
||||
// Start with spindle off off
|
||||
spindle_stop();
|
||||
}
|
||||
|
||||
void spindle_stop()
|
||||
{
|
||||
grbl_analogWrite(SPINDLE_PWM_CHANNEL, 0);
|
||||
spindle_set_enable(false);
|
||||
#ifdef SPINDLE_PWM_PIN
|
||||
grbl_analogWrite(SPINDLE_PWM_CHANNEL, 0);
|
||||
#endif
|
||||
}
|
||||
|
||||
uint8_t spindle_get_state()
|
||||
uint8_t spindle_get_state() // returns SPINDLE_STATE_DISABLE, SPINDLE_STATE_CW or SPINDLE_STATE_CCW
|
||||
{
|
||||
// TODO Update this when direction and enable pin are added
|
||||
if (ledcRead(SPINDLE_PWM_CHANNEL) == 0) // Check the PWM value
|
||||
// TODO Update this when direction and enable pin are added
|
||||
#ifndef SPINDLE_PWM_PIN
|
||||
return(SPINDLE_STATE_DISABLE);
|
||||
#endif
|
||||
|
||||
if (ledcRead(SPINDLE_PWM_CHANNEL) == 0) // Check the PWM value
|
||||
return(SPINDLE_STATE_DISABLE);
|
||||
else
|
||||
return(SPINDLE_STATE_CW); // only CW is supported right now.
|
||||
{
|
||||
#ifdef SPINDLE_DIR_PIN
|
||||
if (digitalRead(SPINDLE_DIR_PIN))
|
||||
return (SPINDLE_STATE_CW);
|
||||
else
|
||||
return(SPINDLE_STATE_CCW);
|
||||
#else
|
||||
return(SPINDLE_STATE_CW);
|
||||
#endif
|
||||
}
|
||||
}
|
||||
|
||||
void spindle_set_speed(uint8_t pwm_value)
|
||||
{
|
||||
grbl_analogWrite(SPINDLE_PWM_CHANNEL, pwm_value);
|
||||
{
|
||||
#ifndef SPINDLE_PWM_PIN
|
||||
return;
|
||||
#endif
|
||||
|
||||
#ifndef SPINDLE_ENABLE_OFF_WITH_ZERO_SPEED
|
||||
spindle_set_enable(true);
|
||||
#else
|
||||
spindle_set_enable(pwm_value != 0);
|
||||
#endif
|
||||
grbl_analogWrite(SPINDLE_PWM_CHANNEL, pwm_value);
|
||||
}
|
||||
|
||||
// Called by spindle_set_state() and step segment generator. Keep routine small and efficient.
|
||||
uint8_t spindle_compute_pwm_value(float rpm)
|
||||
{
|
||||
uint8_t pwm_value;
|
||||
|
||||
rpm *= (0.010*sys.spindle_speed_ovr);
|
||||
|
||||
pwm_value = map(rpm, settings.rpm_min, settings.rpm_max, SPINDLE_PWM_OFF_VALUE, SPINDLE_PWM_MAX_VALUE);
|
||||
// TODO_ESP32 .. make it 16 bit
|
||||
|
||||
@@ -70,12 +109,15 @@ void spindle_set_state(uint8_t state, float rpm)
|
||||
} else {
|
||||
|
||||
// TODO ESP32 Enable and direction control
|
||||
|
||||
#ifdef SPINDLE_DIR_PIN
|
||||
digitalWrite(SPINDLE_DIR_PIN, state == SPINDLE_ENABLE_CW);
|
||||
#endif
|
||||
|
||||
// NOTE: Assumes all calls to this function is when Grbl is not moving or must remain off.
|
||||
if (settings.flags & BITFLAG_LASER_MODE) {
|
||||
if (state == SPINDLE_ENABLE_CCW) { rpm = 0.0; } // TODO: May need to be rpm_min*(100/MAX_SPINDLE_SPEED_OVERRIDE);
|
||||
}
|
||||
|
||||
spindle_set_speed(spindle_compute_pwm_value(rpm));
|
||||
}
|
||||
sys.report_ovr_counter = 0; // Set to report change immediately
|
||||
@@ -98,4 +140,14 @@ void grbl_analogWrite(uint8_t chan, uint32_t duty)
|
||||
}
|
||||
}
|
||||
|
||||
void spindle_set_enable(bool enable)
|
||||
{
|
||||
#ifdef SPINDLE_ENABLE_PIN
|
||||
#ifndef INVERT_SPINDLE_ENABLE_PIN
|
||||
digitalWrite(SPINDLE_ENABLE_PIN, enable); // turn off (low) with zero speed
|
||||
#else
|
||||
digitalWrite(SPINDLE_ENABLE_PIN, !enable); // turn off (high) with zero speed
|
||||
#endif
|
||||
#endif
|
||||
}
|
||||
|
||||
|
@@ -29,7 +29,6 @@
|
||||
#define SPINDLE_STATE_DISABLE 0 // Must be zero.
|
||||
#define SPINDLE_STATE_CW bit(0)
|
||||
#define SPINDLE_STATE_CCW bit(1)
|
||||
|
||||
|
||||
void spindle_init();
|
||||
void spindle_stop();
|
||||
@@ -37,8 +36,8 @@
|
||||
void spindle_set_speed(uint8_t pwm_value);
|
||||
uint8_t spindle_compute_pwm_value(float rpm);
|
||||
void spindle_set_state(uint8_t state, float rpm);
|
||||
void spindle_sync(uint8_t state, float rpm);
|
||||
|
||||
void grbl_analogWrite(uint8_t chan, uint32_t duty);
|
||||
void spindle_sync(uint8_t state, float rpm);
|
||||
void grbl_analogWrite(uint8_t chan, uint32_t duty);
|
||||
void spindle_set_enable(bool enable);
|
||||
|
||||
#endif
|
||||
|
@@ -341,17 +341,31 @@ void stepper_init()
|
||||
{
|
||||
|
||||
// make the direction pins outputs
|
||||
pinMode(X_DIRECTION_PIN, OUTPUT);
|
||||
pinMode(Y_DIRECTION_PIN, OUTPUT);
|
||||
pinMode(Z_DIRECTION_PIN, OUTPUT);
|
||||
#ifdef X_DIRECTION_PIN
|
||||
pinMode(X_DIRECTION_PIN, OUTPUT);
|
||||
#endif
|
||||
#ifdef Y_DIRECTION_PIN
|
||||
pinMode(Y_DIRECTION_PIN, OUTPUT);
|
||||
#endif
|
||||
#ifdef Z_DIRECTION_PIN
|
||||
pinMode(Z_DIRECTION_PIN, OUTPUT);
|
||||
#endif
|
||||
|
||||
// make the step pins outputs
|
||||
pinMode(X_STEP_PIN, OUTPUT);
|
||||
pinMode(Y_STEP_PIN, OUTPUT);
|
||||
pinMode(Z_STEP_PIN, OUTPUT);
|
||||
// make the step pins outputs
|
||||
#ifdef X_STEP_PIN
|
||||
pinMode(X_STEP_PIN, OUTPUT);
|
||||
#endif
|
||||
#ifdef Y_STEP_PIN
|
||||
pinMode(Y_STEP_PIN, OUTPUT);
|
||||
#endif
|
||||
#ifdef Z_STEP_PIN
|
||||
pinMode(Z_STEP_PIN, OUTPUT);
|
||||
#endif
|
||||
|
||||
// make the stepper disable pin an output
|
||||
pinMode(STEPPERS_DISABLE_PIN, OUTPUT);
|
||||
#ifdef STEPPERS_DISABLE_PIN
|
||||
pinMode(STEPPERS_DISABLE_PIN, OUTPUT);
|
||||
#endif
|
||||
|
||||
// setup stepper timer interrupt
|
||||
|
||||
@@ -444,17 +458,30 @@ void st_reset()
|
||||
void set_direction_pins_on(uint8_t onMask)
|
||||
{
|
||||
// inverts are applied in step generation
|
||||
digitalWrite(X_DIRECTION_PIN, (onMask & (1<<X_AXIS)));
|
||||
digitalWrite(Y_DIRECTION_PIN, (onMask & (1<<Y_AXIS)));
|
||||
digitalWrite(Z_DIRECTION_PIN, (onMask & (1<<Z_AXIS)));
|
||||
#ifdef X_DIRECTION_PIN
|
||||
digitalWrite(X_DIRECTION_PIN, (onMask & (1<<X_AXIS)));
|
||||
#endif
|
||||
#ifdef Y_DIRECTION_PIN
|
||||
digitalWrite(Y_DIRECTION_PIN, (onMask & (1<<Y_AXIS)));
|
||||
#endif
|
||||
#ifdef Z_DIRECTION_PIN
|
||||
digitalWrite(Z_DIRECTION_PIN, (onMask & (1<<Z_AXIS)));
|
||||
#endif
|
||||
}
|
||||
|
||||
void set_stepper_pins_on(uint8_t onMask)
|
||||
{
|
||||
onMask ^= settings.step_invert_mask; // invert pins as required by invert mask
|
||||
digitalWrite(X_STEP_PIN, (onMask & (1<<X_AXIS)));
|
||||
digitalWrite(Y_STEP_PIN, (onMask & (1<<Y_AXIS)));
|
||||
digitalWrite(Z_STEP_PIN, (onMask & (1<<Z_AXIS)));
|
||||
|
||||
#ifdef X_STEP_PIN
|
||||
digitalWrite(X_STEP_PIN, (onMask & (1<<X_AXIS)));
|
||||
#endif
|
||||
#ifdef Y_STEP_PIN
|
||||
digitalWrite(Y_STEP_PIN, (onMask & (1<<Y_AXIS)));
|
||||
#endif
|
||||
#ifdef Z_STEP_PIN
|
||||
digitalWrite(Z_STEP_PIN, (onMask & (1<<Z_AXIS)));
|
||||
#endif
|
||||
}
|
||||
|
||||
|
||||
@@ -1027,7 +1054,10 @@ void IRAM_ATTR Stepper_Timer_Stop()
|
||||
void set_stepper_disable(uint8_t isOn) // isOn = true // to disable
|
||||
{
|
||||
if (bit_istrue(settings.flags,BITFLAG_INVERT_ST_ENABLE)) { isOn = !isOn; } // Apply pin invert.
|
||||
digitalWrite(STEPPERS_DISABLE_PIN, isOn );
|
||||
|
||||
#ifdef STEPPERS_DISABLE_PIN
|
||||
digitalWrite(STEPPERS_DISABLE_PIN, isOn );
|
||||
#endif
|
||||
}
|
||||
|
||||
|
||||
|
@@ -70,11 +70,11 @@ void system_execute_startup(char *line)
|
||||
for (n=0; n < N_STARTUP_LINE; n++) {
|
||||
if (!(settings_read_startup_line(n, line))) {
|
||||
line[0] = 0;
|
||||
report_execute_startup_message(line,STATUS_SETTING_READ_FAIL);
|
||||
report_execute_startup_message(line,STATUS_SETTING_READ_FAIL, CLIENT_SERIAL);
|
||||
} else {
|
||||
if (line[0] != 0) {
|
||||
uint8_t status_code = gc_execute_line(line);
|
||||
report_execute_startup_message(line,status_code);
|
||||
uint8_t status_code = gc_execute_line(line, CLIENT_SERIAL);
|
||||
report_execute_startup_message(line,status_code, CLIENT_SERIAL);
|
||||
}
|
||||
}
|
||||
}
|
||||
@@ -88,30 +88,30 @@ void system_execute_startup(char *line)
|
||||
// the lines that are processed afterward, not necessarily real-time during a cycle,
|
||||
// since there are motions already stored in the buffer. However, this 'lag' should not
|
||||
// be an issue, since these commands are not typically used during a cycle.
|
||||
uint8_t system_execute_line(char *line)
|
||||
uint8_t system_execute_line(char *line, uint8_t client)
|
||||
{
|
||||
uint8_t char_counter = 1;
|
||||
uint8_t helper_var = 0; // Helper variable
|
||||
float parameter, value;
|
||||
|
||||
switch( line[char_counter] ) {
|
||||
case 0 : report_grbl_help(); break;
|
||||
case 0 : report_grbl_help(client); break;
|
||||
case 'J' : // Jogging
|
||||
// Execute only if in IDLE or JOG states.
|
||||
if (sys.state != STATE_IDLE && sys.state != STATE_JOG) { return(STATUS_IDLE_ERROR); }
|
||||
if(line[2] != '=') { return(STATUS_INVALID_STATEMENT); }
|
||||
return(gc_execute_line(line)); // NOTE: $J= is ignored inside g-code parser and used to detect jog motions.
|
||||
return(gc_execute_line(line, client)); // NOTE: $J= is ignored inside g-code parser and used to detect jog motions.
|
||||
break;
|
||||
case '$': case 'G': case 'C': case 'X':
|
||||
if ( line[2] != 0 ) { return(STATUS_INVALID_STATEMENT); }
|
||||
switch( line[1] ) {
|
||||
case '$' : // Prints Grbl settings
|
||||
if ( sys.state & (STATE_CYCLE | STATE_HOLD) ) { return(STATUS_IDLE_ERROR); } // Block during cycle. Takes too long to print.
|
||||
else { report_grbl_settings(); }
|
||||
else { report_grbl_settings(client); }
|
||||
break;
|
||||
case 'G' : // Prints gcode parser state
|
||||
// TODO: Move this to realtime commands for GUIs to request this data during suspend-state.
|
||||
report_gcode_modes();
|
||||
report_gcode_modes(client);
|
||||
break;
|
||||
case 'C' : // Set check g-code mode [IDLE/CHECK]
|
||||
// Perform reset when toggling off. Check g-code mode should only work if Grbl
|
||||
@@ -143,7 +143,7 @@ uint8_t system_execute_line(char *line)
|
||||
switch( line[1] ) {
|
||||
case '#' : // Print Grbl NGC parameters
|
||||
if ( line[2] != 0 ) { return(STATUS_INVALID_STATEMENT); }
|
||||
else { report_ngc_parameters(); }
|
||||
else { report_ngc_parameters(client); }
|
||||
break;
|
||||
case 'H' : // Perform homing cycle [IDLE/ALARM]
|
||||
if (bit_isfalse(settings.flags,BITFLAG_HOMING_ENABLE)) {return(STATUS_SETTING_DISABLED); }
|
||||
@@ -174,7 +174,7 @@ uint8_t system_execute_line(char *line)
|
||||
case 'I' : // Print or store build info. [IDLE/ALARM]
|
||||
if ( line[++char_counter] == 0 ) {
|
||||
settings_read_build_info(line);
|
||||
report_build_info(line);
|
||||
report_build_info(line, client);
|
||||
#ifdef ENABLE_BUILD_INFO_WRITE_COMMAND
|
||||
} else { // Store startup line [IDLE/ALARM]
|
||||
if(line[char_counter++] != '=') { return(STATUS_INVALID_STATEMENT); }
|
||||
@@ -207,9 +207,9 @@ uint8_t system_execute_line(char *line)
|
||||
if ( line[++char_counter] == 0 ) { // Print startup lines
|
||||
for (helper_var=0; helper_var < N_STARTUP_LINE; helper_var++) {
|
||||
if (!(settings_read_startup_line(helper_var, line))) {
|
||||
report_status_message(STATUS_SETTING_READ_FAIL);
|
||||
report_status_message(STATUS_SETTING_READ_FAIL, CLIENT_SERIAL);
|
||||
} else {
|
||||
report_startup_line(helper_var,line);
|
||||
report_startup_line(helper_var,line, client);
|
||||
}
|
||||
}
|
||||
break;
|
||||
@@ -218,6 +218,9 @@ uint8_t system_execute_line(char *line)
|
||||
helper_var = true; // Set helper_var to flag storing method.
|
||||
// No break. Continues into default: to read remaining command characters.
|
||||
}
|
||||
case 'W':
|
||||
//TODO
|
||||
break;
|
||||
#ifdef ENABLE_SD_CARD // ==================== SD Card ============================
|
||||
case 'F':
|
||||
char fileLine[255];
|
||||
@@ -244,7 +247,7 @@ uint8_t system_execute_line(char *line)
|
||||
closeFile();
|
||||
}
|
||||
else {
|
||||
report_status_message(gc_execute_line(fileLine)); // execute the first line
|
||||
report_status_message(gc_execute_line(fileLine, CLIENT_SERIAL), CLIENT_SERIAL); // execute the first line
|
||||
}
|
||||
}
|
||||
else {
|
||||
@@ -262,7 +265,7 @@ uint8_t system_execute_line(char *line)
|
||||
line[char_counter-helper_var] = line[char_counter];
|
||||
} while (line[char_counter++] != 0);
|
||||
// Execute gcode block to ensure block is valid.
|
||||
helper_var = gc_execute_line(line); // Set helper_var to returned status code.
|
||||
helper_var = gc_execute_line(line, CLIENT_SERIAL); // Set helper_var to returned status code.
|
||||
if (helper_var) { return(helper_var); }
|
||||
else {
|
||||
helper_var = trunc(parameter); // Set helper_var to int value of parameter
|
||||
|
@@ -189,7 +189,7 @@ void system_clear_exec_accessory_overrides();
|
||||
|
||||
// Execute the startup script lines stored in EEPROM upon initialization
|
||||
void system_execute_startup(char *line);
|
||||
uint8_t system_execute_line(char *line);
|
||||
uint8_t system_execute_line(char *line, uint8_t client);
|
||||
|
||||
void system_flag_wco_change();
|
||||
|
||||
|
@@ -50,7 +50,6 @@ Using SD Card
|
||||
### Roadmap
|
||||
|
||||
- Add Wifi support and a web page interface
|
||||
- Add spindle enable and direction.
|
||||
|
||||
### Credits
|
||||
|
||||
@@ -68,5 +67,9 @@ Start asking questions...I'll put the frequent ones here.
|
||||
|
||||
|
||||
|
||||
### Donation
|
||||
|
||||
This project requires a lot of work and often expensive items for testing. Please consider a donation to it.
|
||||
|
||||
[](https://www.paypal.com/cgi-bin/webscr?cmd=_s-xclick&hosted_button_id=TKNJ9Z775VXB2)
|
||||
|
||||
|
Reference in New Issue
Block a user