1
0
mirror of https://github.com/bdring/Grbl_Esp32.git synced 2025-09-02 10:53:01 +02:00
This commit is contained in:
bdring
2019-06-27 09:15:17 -05:00
12 changed files with 143 additions and 121 deletions

View File

@@ -326,7 +326,7 @@ bool COMMANDS::execute_internal_command (int cmd, String cmd_params, level_authe
}
Preferences prefs;
prefs.begin(NAMESPACE, false);
if (prefs.putString(AP_PWD_ENTRY, parameter) == 0){
if (prefs.putString(AP_PWD_ENTRY, parameter) != parameter.length()){
response = false;
if(espresponse)espresponse->println ("Error: Set failed!");
} else if(espresponse)espresponse->println ("ok");
@@ -940,11 +940,12 @@ bool COMMANDS::execute_internal_command (int cmd, String cmd_params, level_authe
return false;
}
#endif
int8_t vi;
espresponse->print("{\"EEPROM\":[");
if(espresponse->client() != CLIENT_WEBUI)espresponse->println("");
prefs.begin(NAMESPACE, true);
#ifdef ENABLE_WIFI
int8_t vi;
//1 - Hostname
espresponse->print ("{\"F\":\"network\",\"P\":\"");
espresponse->print (HOSTNAME_ENTRY);
@@ -1223,7 +1224,11 @@ bool COMMANDS::execute_internal_command (int cmd, String cmd_params, level_authe
if (! (styp == "B" || styp == "S" || styp == "A" || styp == "I" || styp == "F") ) {
response = false;
}
if (sval.length() == 0) {
if ((sval.length() == 0)
#if defined (ENABLE_WIFI)
&& !((spos==AP_PWD_ENTRY) || (spos==STA_PWD_ENTRY))
#endif
){
response = false;
}
@@ -1281,7 +1286,7 @@ bool COMMANDS::execute_internal_command (int cmd, String cmd_params, level_authe
}
//String value
if (styp == "S") {
if (prefs.putString(spos.c_str(), sval) == 0) {
if (prefs.putString(spos.c_str(), sval) != sval.length()) {
response = false;
} else {
#if defined (ENABLE_WIFI)

View File

@@ -749,10 +749,10 @@
#endif
#ifdef CPU_MAP_MPCNC
#ifdef CPU_MAP_MPCNC_V1P2
// This is the CPU Map for the Buildlog.net MPCNC controller
#define CPU_MAP_NAME "CPU_MAP_MPCNC"
#define CPU_MAP_NAME "CPU_MAP_MPCNC_V1P2"
// switch to the correct default settings
#ifdef DEFAULTS_GENERIC
@@ -778,11 +778,10 @@
#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 STEPPERS_DISABLE_PIN GPIO_NUM_13
// Note: if you use PWM rather than relay, you could map GPIO_NUM_17 to mist or flood
#define USE_SPINDLE_RELAY
// Note: if you use PWM rather than relay, you could map GPIO_NUM_2 to mist or flood
//#define USE_SPINDLE_RELAY
#ifdef USE_SPINDLE_RELAY
#define SPINDLE_PWM_PIN GPIO_NUM_2
@@ -810,13 +809,17 @@
// Note: Only uncomment this if USE_SPINDLE_RELAY is commented out.
// Relay can be used for Spindle or Coolant
//#define COOLANT_FLOOD_PIN GPIO_NUM_17
//#define COOLANT_FLOOD_PIN GPIO_NUM_2
#define X_LIMIT_PIN GPIO_NUM_17
#define Y_LIMIT_PIN GPIO_NUM_4
#define Z_LIMIT_PIN GPIO_NUM_15
#define LIMIT_MASK B111
#ifndef ENABLE_SOFTWARE_DEBOUNCE // V1P2 does not have R/C filters
#define ENABLE_SOFTWARE_DEBOUNCE
#endif
#define PROBE_PIN GPIO_NUM_35
// The default value in config.h is wrong for this controller
@@ -826,7 +829,15 @@
#define INVERT_CONTROL_PIN_MASK B1110
// Note: check the #define IGNORE_CONTROL_PINS is the way you want in config.h
// Note: defualt is #define IGNORE_CONTROL_PINS in config.h
// uncomment to these lines to use them
#ifdef IGNORE_CONTROL_PINS
#undef IGNORE_CONTROL_PINS
#endif
#define CONTROL_RESET_PIN GPIO_NUM_34 // needs external pullup
#define CONTROL_FEED_HOLD_PIN GPIO_NUM_36 // needs external pullup
#define CONTROL_CYCLE_START_PIN GPIO_NUM_39 // needs external pullup
@@ -896,7 +907,7 @@
// Relay can be used for Spindle or Coolant
//#define COOLANT_FLOOD_PIN GPIO_NUM_17
#define X_LIMIT_PIN GPIO_NUM_2
#define X_LIMIT_PIN GPIO_NUM_34
#define Y_LIMIT_PIN GPIO_NUM_4
#define Z_LIMIT_PIN GPIO_NUM_15
#define LIMIT_MASK B111
@@ -908,10 +919,10 @@
#undef INVERT_CONTROL_PIN_MASK
#endif
#define INVERT_CONTROL_PIN_MASK B1110
#define INVERT_CONTROL_PIN_MASK B1100
// Note: check the #define IGNORE_CONTROL_PINS is the way you want in config.h
#define CONTROL_RESET_PIN GPIO_NUM_34 // needs external pullup
//#define CONTROL_RESET_PIN GPIO_NUM_34 // needs external pullup
#define CONTROL_FEED_HOLD_PIN GPIO_NUM_36 // needs external pullup
#define CONTROL_CYCLE_START_PIN GPIO_NUM_39 // needs external pullup

View File

@@ -83,53 +83,58 @@
#endif
#ifdef DEFAULTS_MPCNC
// Grbl generic default settings. Should work across different machines.
#define DEFAULT_STEP_PULSE_MICROSECONDS 3
#define DEFAULT_STEPPER_IDLE_LOCK_TIME 255 // 255 = Keep steppers on
#define DEFAULT_STEPPING_INVERT_MASK 0 // uint8_t
#define DEFAULT_DIRECTION_INVERT_MASK 0 // uint8_t
#define DEFAULT_INVERT_ST_ENABLE 0 // boolean
#define DEFAULT_INVERT_LIMIT_PINS 1 // boolean
#define DEFAULT_INVERT_PROBE_PIN 0 // boolean
#define DEFAULT_STATUS_REPORT_MASK 1
#define DEFAULT_JUNCTION_DEVIATION 0.01 // mm
#define DEFAULT_ARC_TOLERANCE 0.002 // mm
#define DEFAULT_REPORT_INCHES 0 // false
#define DEFAULT_SOFT_LIMIT_ENABLE 0 // false
#define DEFAULT_HARD_LIMIT_ENABLE 0 // false
#define DEFAULT_HOMING_ENABLE 1 // false
#define DEFAULT_HOMING_DIR_MASK 3 // move positive dir Z,negative X,Y
#define DEFAULT_HOMING_FEED_RATE 600.0 // mm/min
#define DEFAULT_HOMING_SEEK_RATE 2000.0 // mm/min
#define DEFAULT_HOMING_DEBOUNCE_DELAY 250 // msec (0-65k)
#define DEFAULT_HOMING_PULLOFF 1.5 // mm
// Grbl generic default settings. Should work across different machines.
#define DEFAULT_STEP_PULSE_MICROSECONDS 3
#define DEFAULT_STEPPER_IDLE_LOCK_TIME 255 // 255 = Keep steppers on
#define DEFAULT_STEPPING_INVERT_MASK 0 // uint8_t
#define DEFAULT_DIRECTION_INVERT_MASK 0 // uint8_t
#define DEFAULT_INVERT_ST_ENABLE 0 // boolean
#define DEFAULT_INVERT_LIMIT_PINS 1 // boolean
#define DEFAULT_INVERT_PROBE_PIN 0 // boolean
#define DEFAULT_STATUS_REPORT_MASK 1
#define DEFAULT_JUNCTION_DEVIATION 0.01 // mm
#define DEFAULT_ARC_TOLERANCE 0.002 // mm
#define DEFAULT_REPORT_INCHES 0 // false
#define DEFAULT_SOFT_LIMIT_ENABLE 0 // false
#define DEFAULT_HARD_LIMIT_ENABLE 0 // false
#define DEFAULT_HOMING_ENABLE 1 // false
#define DEFAULT_HOMING_DIR_MASK 3 // move positive dir Z,negative X,Y
#define DEFAULT_HOMING_FEED_RATE 600.0 // mm/min
#define DEFAULT_HOMING_SEEK_RATE 2000.0 // mm/min
#define DEFAULT_HOMING_DEBOUNCE_DELAY 250 // msec (0-65k)
#define DEFAULT_HOMING_PULLOFF 1.5 // mm
#ifdef USE_SPINDLE_RELAY
#define DEFAULT_SPINDLE_RPM_MAX 1.0 // must be 1 so PWM duty is alway 100% to prevent relay damage
#else
#define DEFAULT_SPINDLE_RPM_MAX 1000.0 // can be change to your spindle max
#endif
#define DEFAULT_SPINDLE_RPM_MIN 0.0 // rpm
#define DEFAULT_LASER_MODE 0 // false
#define DEFAULT_X_STEPS_PER_MM 200.0
#define DEFAULT_Y_STEPS_PER_MM 200.0
#define DEFAULT_Z_STEPS_PER_MM 800.0
#define DEFAULT_X_MAX_RATE 8000.0 // mm/min
#define DEFAULT_Y_MAX_RATE 8000.0 // mm/min
#define DEFAULT_Z_MAX_RATE 3000.0 // mm/min
#define DEFAULT_X_ACCELERATION (200.0*60*60) // 10*60*60 mm/min^2 = 10 mm/sec^2
#define DEFAULT_Y_ACCELERATION (200.0*60*60) // 10*60*60 mm/min^2 = 10 mm/sec^2
#define DEFAULT_Z_ACCELERATION (100.0*60*60) // 10*60*60 mm/min^2 = 10 mm/sec^2
#define DEFAULT_X_MAX_TRAVEL 500.0 // mm NOTE: Must be a positive value.
#define DEFAULT_Y_MAX_TRAVEL 500.0 // mm NOTE: Must be a positive value.
#define DEFAULT_Z_MAX_TRAVEL 80.0 // mm NOTE: Must be a positive value.
#define DEFAULT_SPINDLE_RPM_MAX 1.0 // rpm used for spindle relay
#define DEFAULT_SPINDLE_RPM_MIN 0.0 // rpm
#define DEFAULT_LASER_MODE 0 // false
#define DEFAULT_X_STEPS_PER_MM 200.0
#define DEFAULT_Y_STEPS_PER_MM 200.0
#define DEFAULT_Z_STEPS_PER_MM 800.0
#define DEFAULT_X_MAX_RATE 8000.0 // mm/min
#define DEFAULT_Y_MAX_RATE 8000.0 // mm/min
#define DEFAULT_Z_MAX_RATE 3000.0 // mm/min
#define DEFAULT_X_ACCELERATION (200.0*60*60) // 10*60*60 mm/min^2 = 10 mm/sec^2
#define DEFAULT_Y_ACCELERATION (200.0*60*60) // 10*60*60 mm/min^2 = 10 mm/sec^2
#define DEFAULT_Z_ACCELERATION (100.0*60*60) // 10*60*60 mm/min^2 = 10 mm/sec^2
#define DEFAULT_X_MAX_TRAVEL 500.0 // mm NOTE: Must be a positive value.
#define DEFAULT_Y_MAX_TRAVEL 500.0 // mm NOTE: Must be a positive value.
#define DEFAULT_Z_MAX_TRAVEL 80.0 // mm NOTE: Must be a positive value.
#endif

View File

@@ -20,7 +20,7 @@
// Grbl versioning system
#define GRBL_VERSION "1.1f"
#define GRBL_VERSION_BUILD "20190602"
#define GRBL_VERSION_BUILD "20190622"
//#include <sdkconfig.h>
#include <Arduino.h>

View File

@@ -23,6 +23,8 @@
#ifdef USE_PEN_SERVO
static TaskHandle_t servoSyncTaskHandle = 0;
// used to delay turn on
bool servo_pen_enable = false;

View File

@@ -67,8 +67,6 @@
#ifndef servo_h
#define servo_h
static TaskHandle_t servoSyncTaskHandle = 0;
void servo_init();
void servo_disable();
bool validate_servo_settings(bool verbose);

View File

@@ -23,6 +23,8 @@
#ifdef USE_PEN_SOLENOID
static TaskHandle_t solenoidSyncTaskHandle = 0;
// used to delay turn on
bool solenoid_pen_enable;
uint16_t solenoide_hold_count;

View File

@@ -46,7 +46,7 @@
#ifndef solenoid_h
#define solenoid_h
static TaskHandle_t solenoidSyncTaskHandle = 0;
void solenoid_init();
void solenoid_disable();
void solenoidSyncTask(void *pvParameters);

View File

@@ -198,6 +198,58 @@ static st_prep_t prep;
*/
#ifdef USE_RMT_STEPS
// Set stepper pulse output pins
inline IRAM_ATTR static void stepperRMT_Outputs()
{
#ifdef X_STEP_PIN
if(st.step_outbits & (1<<X_AXIS)) {
#ifndef X_STEP_B_PIN // if not a ganged axis
RMT.conf_ch[X_RMT_CHANNEL].conf1.mem_rd_rst = 1;
RMT.conf_ch[X_RMT_CHANNEL].conf1.tx_start = 1;
#else // it is a ganged axis
if ( (ganged_mode == SQUARING_MODE_DUAL) || (ganged_mode == SQUARING_MODE_A) ) {
RMT.conf_ch[X_RMT_CHANNEL].conf1.mem_rd_rst = 1;
RMT.conf_ch[X_RMT_CHANNEL].conf1.tx_start = 1; }
if ( (ganged_mode == SQUARING_MODE_DUAL) || (ganged_mode == SQUARING_MODE_B) ) {
RMT.conf_ch[X_B_RMT_CHANNEL].conf1.mem_rd_rst = 1;
RMT.conf_ch[X_B_RMT_CHANNEL].conf1.tx_start = 1;
}
#endif
}
#endif
#ifdef Y_STEP_PIN
if(st.step_outbits & (1<<Y_AXIS)) {
#ifndef Y_STEP_B_PIN // if not a ganged axis
RMT.conf_ch[Y_RMT_CHANNEL].conf1.mem_rd_rst = 1;
RMT.conf_ch[Y_RMT_CHANNEL].conf1.tx_start = 1;
#else // it is a ganged axis
if ( (ganged_mode == SQUARING_MODE_DUAL) || (ganged_mode == SQUARING_MODE_A) ) {
RMT.conf_ch[Y_RMT_CHANNEL].conf1.mem_rd_rst = 1;
RMT.conf_ch[Y_RMT_CHANNEL].conf1.tx_start = 1;
}
if ( (ganged_mode == SQUARING_MODE_DUAL) || (ganged_mode == SQUARING_MODE_B) ) {
RMT.conf_ch[Y_B_RMT_CHANNEL].conf1.mem_rd_rst = 1;
RMT.conf_ch[Y_B_RMT_CHANNEL].conf1.tx_start = 1;
}
#endif
}
#endif
#ifdef Z_STEP_PIN
if(st.step_outbits & (1<<Z_AXIS)) {
RMT.conf_ch[Z_RMT_CHANNEL].conf1.mem_rd_rst = 1;
RMT.conf_ch[Z_RMT_CHANNEL].conf1.tx_start = 1;
}
#endif
}
#endif
// TODO: Replace direct updating of the int32 position counters in the ISR somehow. Perhaps use smaller
// int8 variables and update position counters only when a segment completes. This can get complicated
// with probing and homing cycles that require true real-time positions.
@@ -670,57 +722,6 @@ void set_stepper_pins_on(uint8_t onMask)
}
#endif
#ifdef USE_RMT_STEPS
// Set stepper pulse output pins
inline IRAM_ATTR static void stepperRMT_Outputs()
{
#ifdef X_STEP_PIN
if(st.step_outbits & (1<<X_AXIS)) {
#ifndef X_STEP_B_PIN // if not a ganged axis
RMT.conf_ch[X_RMT_CHANNEL].conf1.mem_rd_rst = 1;
RMT.conf_ch[X_RMT_CHANNEL].conf1.tx_start = 1;
#else // it is a ganged axis
if ( (ganged_mode == SQUARING_MODE_DUAL) || (ganged_mode == SQUARING_MODE_A) ) {
RMT.conf_ch[X_RMT_CHANNEL].conf1.mem_rd_rst = 1;
RMT.conf_ch[X_RMT_CHANNEL].conf1.tx_start = 1; }
if ( (ganged_mode == SQUARING_MODE_DUAL) || (ganged_mode == SQUARING_MODE_B) ) {
RMT.conf_ch[X_B_RMT_CHANNEL].conf1.mem_rd_rst = 1;
RMT.conf_ch[X_B_RMT_CHANNEL].conf1.tx_start = 1;
}
#endif
}
#endif
#ifdef Y_STEP_PIN
if(st.step_outbits & (1<<Y_AXIS)) {
#ifndef Y_STEP_B_PIN // if not a ganged axis
RMT.conf_ch[Y_RMT_CHANNEL].conf1.mem_rd_rst = 1;
RMT.conf_ch[Y_RMT_CHANNEL].conf1.tx_start = 1;
#else // it is a ganged axis
if ( (ganged_mode == SQUARING_MODE_DUAL) || (ganged_mode == SQUARING_MODE_A) ) {
RMT.conf_ch[Y_RMT_CHANNEL].conf1.mem_rd_rst = 1;
RMT.conf_ch[Y_RMT_CHANNEL].conf1.tx_start = 1;
}
if ( (ganged_mode == SQUARING_MODE_DUAL) || (ganged_mode == SQUARING_MODE_B) ) {
RMT.conf_ch[Y_B_RMT_CHANNEL].conf1.mem_rd_rst = 1;
RMT.conf_ch[Y_B_RMT_CHANNEL].conf1.tx_start = 1;
}
#endif
}
#endif
#ifdef Z_STEP_PIN
if(st.step_outbits & (1<<Z_AXIS)) {
RMT.conf_ch[Z_RMT_CHANNEL].conf1.mem_rd_rst = 1;
RMT.conf_ch[Z_RMT_CHANNEL].conf1.tx_start = 1;
}
#endif
}
#endif
// Stepper shutdown
void st_go_idle()
{

View File

@@ -83,7 +83,6 @@ void IRAM_ATTR onSteppertimer();
void IRAM_ATTR onStepperOffTimer();
void stepper_init();
void initRMT();
inline IRAM_ATTR static void stepperRMT_Outputs();
// Enable steppers, but cycle does not start unless called by motion control or realtime command.
void st_wake_up();

View File

@@ -475,7 +475,7 @@ void WiFiConfig::reset_settings(){
error = true;
}
sval = DEFAULT_STA_PWD;
if (prefs.putString(STA_PWD_ENTRY, sval) == 0){
if (prefs.putString(STA_PWD_ENTRY, sval) != sval.length()){
error = true;
}
sval = DEFAULT_AP_SSID;
@@ -483,7 +483,7 @@ void WiFiConfig::reset_settings(){
error = true;
}
sval = DEFAULT_AP_PWD;
if (prefs.putString(AP_PWD_ENTRY, sval) == 0){
if (prefs.putString(AP_PWD_ENTRY, sval) != sval.length()){
error = true;
}

View File

@@ -6,7 +6,7 @@
### Project Overview
[![Build Status](https://travis-ci.org/bdring/Grbl_Esp32.svg?branch=master)](https://travis-ci.org/bdring/Grbl_Esp32)
[![Build Status](https://travis-ci.com/odaki/Grbl_Esp32.svg?branch=master)](https://travis-ci.com/odaki/Grbl_Esp32)
This is a port of [Grbl](https://github.com/gnea/grbl) for the ESP32. The ESP32 is potentially a great target for Grbl for the following reasons
@@ -54,4 +54,3 @@ Start asking questions...I'll put the frequent ones here.
This project requires a lot of work and often expensive items for testing. Please consider a safe, secure and highly appreciated donation via the PayPal link below.
[![](https://www.paypalobjects.com/en_US/i/btn/btn_donateCC_LG.gif)](https://www.paypal.com/cgi-bin/webscr?cmd=_s-xclick&hosted_button_id=TKNJ9Z775VXB2)