diff --git a/Grbl_Esp32/config.h b/Grbl_Esp32/config.h index 6726a622..093af036 100644 --- a/Grbl_Esp32/config.h +++ b/Grbl_Esp32/config.h @@ -39,17 +39,17 @@ Some features should not be changed. See notes below. #define config_h #include -//#define ESP_DEBUG +// !!!! Most Important Configuration Item !!!! +// #define the CPU map you want to use +// The CPU map is the main definition of the machine/controller you want to use +// These are typically found in the cpu_map.h file. +// See Github repo wiki for more details +#define CPU_MAP_TEST_DRIVE // these are defined in cpu_map.h + #define N_AXIS 3 // Number of axes defined (valid range: 3 to 6) -// Define CPU pin map and default settings. -// NOTE: OEMs can avoid the need to maintain/update the defaults.h and cpu_map.h files and use only -// one configuration file by placing their specific defaults and pin map at the bottom of this file. -// If doing so, simply comment out these two defines and see instructions below. -#define CPU_MAP_TEST_DRIVE // these are defined in cpu_map.h #define VERBOSE_HELP // adds addition help info, but could confuse some senders - // Serial baud rate #define BAUD_RATE 115200 diff --git a/Grbl_Esp32/cpu_map.h b/Grbl_Esp32/cpu_map.h index 26dbe271..f704182a 100644 --- a/Grbl_Esp32/cpu_map.h +++ b/Grbl_Esp32/cpu_map.h @@ -59,8 +59,6 @@ */ #define CPU_MAP_NAME "CPU_MAP_DEFAULT - Demo Only No I/O!" - #define CONTROL_FEED_HOLD_PIN GPIO_NUM_21 // Uno A1 - #define LIMIT_MASK 0 // no limit pins #endif @@ -99,16 +97,10 @@ #define Z_LIMIT_PIN GPIO_NUM_15 #endif - #define X_STEP_PIN GPIO_NUM_12 - - #define X_RMT_CHANNEL 0 - - // #define Y_STEP_PIN (see versions above) - #define Y_RMT_CHANNEL 1 + #define X_STEP_PIN GPIO_NUM_12 #define Z_STEP_PIN GPIO_NUM_27 - #define Z_DIRECTION_PIN GPIO_NUM_33 - #define Z_RMT_CHANNEL 2 + #define Z_DIRECTION_PIN GPIO_NUM_33 // OK to comment out to use pin for other features #define STEPPERS_DISABLE_PIN GPIO_NUM_13 @@ -138,44 +130,44 @@ // !!!! Experimental Untested !!!!! // This is a CPU MAP for ESPDUINO-32 Boards and Protoneer V3 boards // Note: Probe pin is mapped, but will require a 10k external pullup to 3.3V to work. + + // Rebooting...See this issue https://github.com/bdring/Grbl_Esp32/issues/314 + #define CPU_MAP_NAME "CPU_MAP_ESPDUINO_32" #define USE_RMT_STEPS - #define X_STEP_PIN GPIO_NUM_26 // Uno D2 - #define X_DIRECTION_PIN GPIO_NUM_16 // Uno D5 - #define X_RMT_CHANNEL 0 + #define X_STEP_PIN GPIO_NUM_26 + #define X_DIRECTION_PIN GPIO_NUM_16 - #define Y_STEP_PIN GPIO_NUM_25 // Uno D3 - #define Y_DIRECTION_PIN GPIO_NUM_27 // Uno D6 - #define Y_RMT_CHANNEL 1 + #define Y_STEP_PIN GPIO_NUM_25 + #define Y_DIRECTION_PIN GPIO_NUM_27 - #define Z_STEP_PIN GPIO_NUM_17 // Uno D4 - #define Z_DIRECTION_PIN GPIO_NUM_14 // Uno D7 - #define Z_RMT_CHANNEL 2 + #define Z_STEP_PIN GPIO_NUM_17 + #define Z_DIRECTION_PIN GPIO_NUM_14 // OK to comment out to use pin for other features - #define STEPPERS_DISABLE_PIN GPIO_NUM_12 // Uno D8 + #define STEPPERS_DISABLE_PIN GPIO_NUM_12 - #define SPINDLE_PWM_PIN GPIO_NUM_19 // Uno D11 + #define SPINDLE_PWM_PIN GPIO_NUM_19 #define SPINDLE_PWM_CHANNEL 0 #define SPINDLE_PWM_BIT_PRECISION 8 // be sure to match this with SPINDLE_PWM_MAX_VALUE - #define SPINDLE_DIR_PIN GPIO_NUM_18 // Uno D13 + #define SPINDLE_DIR_PIN GPIO_NUM_18 - #define COOLANT_FLOOD_PIN GPIO_NUM_34 // Uno A3 - #define COOLANT_MIST_PIN GPIO_NUM_36// Uno A4 + #define COOLANT_FLOOD_PIN GPIO_NUM_34 + #define COOLANT_MIST_PIN GPIO_NUM_36 - #define X_LIMIT_PIN GPIO_NUM_13 // Uno D9 - #define Y_LIMIT_PIN GPIO_NUM_5 // Uno D10 - #define Z_LIMIT_PIN GPIO_NUM_19 // Uno D12 + #define X_LIMIT_PIN GPIO_NUM_13 + #define Y_LIMIT_PIN GPIO_NUM_5 + #define Z_LIMIT_PIN GPIO_NUM_19 #define LIMIT_MASK B111 - #define PROBE_PIN GPIO_NUM_39 // Uno A5 + #define PROBE_PIN GPIO_NUM_39 // comment out #define IGNORE_CONTROL_PINS in config.h to use control pins - #define CONTROL_RESET_PIN GPIO_NUM_2 // Uno A0 - #define CONTROL_FEED_HOLD_PIN GPIO_NUM_4 // Uno A1 - #define CONTROL_CYCLE_START_PIN GPIO_NUM_35 // Uno A2 ... ESP32 needs external pullup + #define CONTROL_RESET_PIN GPIO_NUM_2 + #define CONTROL_FEED_HOLD_PIN GPIO_NUM_4 + #define CONTROL_CYCLE_START_PIN GPIO_NUM_35 // ESP32 needs external pullup #endif #ifdef CPU_MAP_ESP32_ESC_SPINDLE @@ -185,20 +177,19 @@ // https://github.com/bdring/Grbl_Esp32/wiki/BESC-Spindle-Feature #define CPU_MAP_NAME "CPU_MAP_ESP32_ESC_SPINDLE" + + #define SHOW_EXTENDED_SETTINGS #define USE_RMT_STEPS #define X_STEP_PIN GPIO_NUM_12 - #define X_DIRECTION_PIN GPIO_NUM_14 - #define X_RMT_CHANNEL 0 + #define X_DIRECTION_PIN GPIO_NUM_14 #define Y_STEP_PIN GPIO_NUM_26 - #define Y_DIRECTION_PIN GPIO_NUM_15// #define Y_STEP_PIN (see versions above) - #define Y_RMT_CHANNEL 1 + #define Y_DIRECTION_PIN GPIO_NUM_15// #define Y_STEP_PIN (see versions above) #define Z_STEP_PIN GPIO_NUM_27 - #define Z_DIRECTION_PIN GPIO_NUM_33 - #define Z_RMT_CHANNEL 2 + #define Z_DIRECTION_PIN GPIO_NUM_33 // OK to comment out to use pin for other features #define STEPPERS_DISABLE_PIN GPIO_NUM_13 @@ -209,9 +200,12 @@ // Begin RC ESC Based Spindle Information ====================== #define SPINDLE_PWM_BIT_PRECISION 16 // 16 bit recommended for ESC (don't change) + + /* Important ESC Settings $33=50 // Hz this is the typical good frequency for an ESC + #define DEFAULT_SPINDLE_FREQ 5000.0 // $33 Hz (extended set) Determine the typical min and max pulse length of your ESC min_pulse is typically 1ms (0.001 sec) or less @@ -223,10 +217,16 @@ (pulse / PWM_period) - min_pulse = (0.001 / 0.02) = 0.035 = 3.5% so ... $33 and $34 = 3.5 + min_pulse = (0.001 / 0.02) = 0.05 = 5% so ... $34 and $35 = 5.0 max_pulse = (0.002 / .02) = 0.1 = 10% so ... $36=10 */ + #define DEFAULT_SPINDLE_FREQ 50.0 + #define DEFAULT_SPINDLE_OFF_VALUE 5.0 + #define DEFAULT_SPINDLE_MIN_VALUE 5.0 + #define DEFAULT_SPINDLE_MAX_VALUE 10.0 + + // End RC ESC Based Spindle #defines =========================== @@ -260,13 +260,10 @@ #define PEN_LASER_V2 #define X_STEP_PIN GPIO_NUM_12 - #define X_DIRECTION_PIN GPIO_NUM_26 - #define X_RMT_CHANNEL 0 - + #define X_DIRECTION_PIN GPIO_NUM_26 #define Y_STEP_PIN GPIO_NUM_14 - #define Y_DIRECTION_PIN GPIO_NUM_25 - #define Y_RMT_CHANNEL 1 + #define Y_DIRECTION_PIN GPIO_NUM_25 #define STEPPERS_DISABLE_PIN GPIO_NUM_13 @@ -362,11 +359,9 @@ #define X_STEP_PIN GPIO_NUM_12 #define Y_STEP_PIN GPIO_NUM_14 - #define X_RMT_CHANNEL 0 #define X_DIRECTION_PIN GPIO_NUM_26 #define Y_DIRECTION_PIN GPIO_NUM_25 - #define Y_RMT_CHANNEL 1 #ifndef COREXY // maybe set in config.h #define COREXY @@ -827,7 +822,6 @@ #define X_DRIVER_TMC2130 // Which Driver Type? #define X_CS_PIN GPIO_NUM_17 //chip select #define X_RSENSE 0.11f // .11 Ohm - #define X_RMT_CHANNEL 0 #define Y_STEP_PIN GPIO_NUM_14 #define Y_DIRECTION_PIN GPIO_NUM_25 @@ -835,7 +829,6 @@ #define Y_DRIVER_TMC2130 // Which Driver Type? #define Y_CS_PIN GPIO_NUM_16 //chip select #define Y_RSENSE 0.11f // .11 Ohm - #define Y_RMT_CHANNEL 1 // OK to comment out to use pin for other features #define STEPPERS_DISABLE_PIN GPIO_NUM_13 @@ -844,6 +837,7 @@ #define USE_SERVO_AXES #endif + #define SERVO_Z_PIN GPIO_NUM_27 #define SERVO_Z_CHANNEL_NUM 5 #define SERVO_Z_RANGE_MIN 0.0 @@ -852,17 +846,13 @@ #define SERVO_Z_HOME_POS SERVO_Z_RANGE_MAX // move to max during homing #define SERVO_Z_MPOS false // will not use mpos, uses work coordinates - // *** 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 + // Comment out servo pin and uncomment spindle pwm pin to use the servo PWM to control a spindle + /* + #define SPINDLE_PWM_PIN GPIO_NUM_27 #define SPINDLE_PWM_CHANNEL 0 #define SPINDLE_PWM_BIT_PRECISION 8 // be sure to match this with SPINDLE_PWM_MAX_VALUE - + */ // #define X_LIMIT_PIN See version section #define Y_LIMIT_PIN GPIO_NUM_4 @@ -884,21 +874,17 @@ #define X_STEP_PIN GPIO_NUM_12 #define X_DIRECTION_PIN GPIO_NUM_26 - #define X_RMT_CHANNEL 0 #define Y_STEP_PIN GPIO_NUM_14 #define Y_DIRECTION_PIN GPIO_NUM_25 - #define Y_RMT_CHANNEL 1 // Z is a servo #define A_STEP_PIN GPIO_NUM_27 #define A_DIRECTION_PIN GPIO_NUM_33 - #define A_RMT_CHANNEL 2 #define B_STEP_PIN GPIO_NUM_15 #define B_DIRECTION_PIN GPIO_NUM_32 - #define B_RMT_CHANNEL 3 // C is a servo @@ -1035,7 +1021,6 @@ #define X_DRIVER_TMC2130 // Which Driver Type? #define X_CS_PIN GPIO_NUM_17 // Daisy Chain, all share same CS pin #define X_RSENSE 0.11f // .11 Ohm - #define X_RMT_CHANNEL 0 #define Y_STEP_PIN GPIO_NUM_27 #define Y_DIRECTION_PIN GPIO_NUM_26 @@ -1043,7 +1028,6 @@ #define Y_DRIVER_TMC2130 // Which Driver Type? #define Y_CS_PIN X_CS_PIN // Daisy Chain, all share same CS pin #define Y_RSENSE 0.11f // .11 Ohm - #define Y_RMT_CHANNEL 1 #define Z_STEP_PIN GPIO_NUM_15 #define Z_DIRECTION_PIN GPIO_NUM_2 @@ -1051,7 +1035,6 @@ #define Z_DRIVER_TMC2130 // Which Driver Type? #define Z_CS_PIN X_CS_PIN // Daisy Chain, all share same CS pin #define Z_RSENSE 0.11f // .11 Ohm - #define Z_RMT_CHANNEL 2 #define A_STEP_PIN GPIO_NUM_33 #define A_DIRECTION_PIN GPIO_NUM_32 @@ -1059,7 +1042,6 @@ #define A_DRIVER_TMC2130 // Which Driver Type? #define A_CS_PIN X_CS_PIN // Daisy Chain, all share same CS pin #define A_RSENSE 0.11f // .11 Ohm - #define A_RMT_CHANNEL 3 #define STEPPERS_DISABLE_PIN GPIO_NUM_13 diff --git a/Grbl_Esp32/grbl.h b/Grbl_Esp32/grbl.h index 33135184..94dc289c 100644 --- a/Grbl_Esp32/grbl.h +++ b/Grbl_Esp32/grbl.h @@ -20,7 +20,7 @@ // Grbl versioning system #define GRBL_VERSION "1.1f" -#define GRBL_VERSION_BUILD "20200110" +#define GRBL_VERSION_BUILD "20200115" //#include #include diff --git a/Grbl_Esp32/grbl_trinamic.cpp b/Grbl_Esp32/grbl_trinamic.cpp index 8616cf23..15ee5655 100644 --- a/Grbl_Esp32/grbl_trinamic.cpp +++ b/Grbl_Esp32/grbl_trinamic.cpp @@ -134,12 +134,16 @@ void Trinamic_Init() { + uint8_t testResult; + grbl_sendf(CLIENT_SERIAL, "[MSG:TMCStepper Init using Library Ver 0x%06x]\r\n", TMCSTEPPER_VERSION); SPI.begin(); #ifdef X_TRINAMIC TRINAMIC_X.begin(); // Initiate pins and registries + testResult = TRINAMIC_X.test_connection(); + trinamic_test_response(testResult, "X"); TRINAMIC_X.toff(5); TRINAMIC_X.microsteps(settings.microsteps[X_AXIS]); TRINAMIC_X.rms_current(settings.current[X_AXIS] * 1000.0, settings.hold_current[X_AXIS]/100.0); @@ -149,6 +153,8 @@ void Trinamic_Init() #ifdef Y_TRINAMIC TRINAMIC_Y.begin(); // Initiate pins and registries + testResult = TRINAMIC_Y.test_connection(); + trinamic_test_response(testResult, "Y"); TRINAMIC_Y.toff(5); TRINAMIC_Y.microsteps(settings.microsteps[Y_AXIS]); TRINAMIC_Y.rms_current(settings.current[Y_AXIS] * 1000.0, settings.hold_current[Y_AXIS]/100.0); @@ -158,6 +164,8 @@ void Trinamic_Init() #ifdef Z_TRINAMIC TRINAMIC_Z.begin(); // Initiate pins and registries + testResult = TRINAMIC_Z.test_connection(); + trinamic_test_response(testResult, "Z"); TRINAMIC_Z.toff(5); TRINAMIC_Z.microsteps(settings.microsteps[Z_AXIS]); TRINAMIC_Z.rms_current(settings.current[Z_AXIS] * 1000.0, settings.hold_current[Z_AXIS]/100.0); @@ -167,6 +175,8 @@ void Trinamic_Init() #ifdef A_TRINAMIC TRINAMIC_A.begin(); // Initiate pins and registries + testResult = TRINAMIC_A.test_connection(); + trinamic_test_response(testResult, "A"); TRINAMIC_A.toff(5); TRINAMIC_A.microsteps(settings.microsteps[A_AXIS]); TRINAMIC_A.rms_current(settings.current[A_AXIS] * 1000.0, settings.hold_current[A_AXIS]/100.0); @@ -176,6 +186,8 @@ void Trinamic_Init() #ifdef B_TRINAMIC TRINAMIC_B.begin(); // Initiate pins and registries + testResult = TRINAMIC_B.test_connection(); + trinamic_test_response(testResult, "B"); TRINAMIC_B.toff(5); TRINAMIC_B.microsteps(settings.microsteps[B_AXIS]); TRINAMIC_B.rms_current(settings.current[B_AXIS] * 1000.0, settings.hold_current[B_AXIS]/100.0); @@ -185,6 +197,8 @@ void Trinamic_Init() #ifdef C_TRINAMIC TRINAMIC_C.begin(); // Initiate pins and registries + testResult = TRINAMIC_C.test_connection(); + trinamic_test_response(testResult, "C"); TRINAMIC_C.toff(5); TRINAMIC_C.microsteps(settings.microsteps[C_AXIS]); TRINAMIC_C.rms_current(settings.current[C_AXIS] * 1000.0, settings.hold_current[C_AXIS]/100.0); @@ -228,4 +242,19 @@ void trinamic_change_settings() #endif } +void trinamic_test_response(uint8_t result, const char *axis) +{ + grbl_sendf(CLIENT_SERIAL, "[MSG:%s Trinamic driver test ", axis); + if (result) { + grbl_sendf(CLIENT_SERIAL, "failed."); + switch(result) { + case 1: grbl_sendf(CLIENT_SERIAL, " Check connection]\r\n"); break; + case 2: grbl_sendf(CLIENT_SERIAL, " Check motor power]\r\n"); break; + } + } + else { + grbl_sendf(CLIENT_SERIAL, "passed]\r\n"); + } +} + #endif \ No newline at end of file diff --git a/Grbl_Esp32/grbl_trinamic.h b/Grbl_Esp32/grbl_trinamic.h index 9723124a..574430a3 100644 --- a/Grbl_Esp32/grbl_trinamic.h +++ b/Grbl_Esp32/grbl_trinamic.h @@ -27,6 +27,7 @@ #include // https://github.com/teemuatlut/TMCStepper void Trinamic_Init(); void trinamic_change_settings(); + void trinamic_test_response(uint8_t result, const char *axis); #endif #endif \ No newline at end of file diff --git a/Grbl_Esp32/polar_coaster.h b/Grbl_Esp32/polar_coaster.h index a7826172..6d570a02 100644 --- a/Grbl_Esp32/polar_coaster.h +++ b/Grbl_Esp32/polar_coaster.h @@ -33,9 +33,7 @@ #define USE_RMT_STEPS #define X_STEP_PIN GPIO_NUM_15 -#define X_RMT_CHANNEL 0 #define Y_STEP_PIN GPIO_NUM_2 -#define Y_RMT_CHANNEL 1 #define X_DIRECTION_PIN GPIO_NUM_25 #define Y_DIRECTION_PIN GPIO_NUM_26 diff --git a/Grbl_Esp32/report.cpp b/Grbl_Esp32/report.cpp index 73a85b5e..1d20b2db 100644 --- a/Grbl_Esp32/report.cpp +++ b/Grbl_Esp32/report.cpp @@ -275,16 +275,23 @@ void report_init_message(uint8_t client) // Grbl help message 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_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(uint8_t client) { +// Extended setting will be displayed if force_extended is true or #ifdef SHOW_EXTENDED_SETTINGS +void report_grbl_settings(uint8_t client, uint8_t show_extended) { // Print Grbl settings. char setting[20]; - char rpt[1000]; + char rpt[1000]; + + #ifdef SHOW_EXTENDED_SETTINGS + show_extended = true; + #endif + + grbl_sendf(CLIENT_SERIAL, "[MSG:Extended %d]\r\n", show_extended); rpt[0] = '\0'; @@ -322,7 +329,7 @@ void report_grbl_settings(uint8_t client) { strcat(rpt, "$32=0\r\n"); #endif - #ifdef SHOW_EXTENDED_SETTINGS + if (show_extended) { sprintf(setting, "$33=%5.3f\r\n", settings.spindle_pwm_freq); strcat(rpt, setting); sprintf(setting, "$34=%3.3f\r\n", settings.spindle_pwm_off_value); strcat(rpt, setting); sprintf(setting, "$35=%3.3f\r\n", settings.spindle_pwm_min_value); strcat(rpt, setting); @@ -334,9 +341,8 @@ void report_grbl_settings(uint8_t client) { for (uint8_t index = 0; index= 100 for axis settings. Up to 255. #define AXIS_SETTINGS_INCREMENT 10 // Must be greater than the number of axis settings diff --git a/Grbl_Esp32/spindle_control.cpp b/Grbl_Esp32/spindle_control.cpp index 8877bf37..6250399c 100644 --- a/Grbl_Esp32/spindle_control.cpp +++ b/Grbl_Esp32/spindle_control.cpp @@ -22,17 +22,17 @@ #ifdef SPINDLE_PWM_PIN static float pwm_gradient; // Precalulated value to speed up rpm to PWM conversions. -float spindle_pwm_period; -float spindle_pwm_off_value; -float spindle_pwm_min_value; -float spindle_pwm_max_value; +uint32_t spindle_pwm_period; // how many counts in 1 period +uint32_t spindle_pwm_off_value; +uint32_t spindle_pwm_min_value; +uint32_t spindle_pwm_max_value; #endif void spindle_init() { #ifdef SPINDLE_PWM_PIN - + grbl_sendf(CLIENT_SERIAL, "[MSG:Spindle init on pin %d]\r\n", SPINDLE_PWM_PIN); #ifdef INVERT_SPINDLE_PWM grbl_send(CLIENT_SERIAL, "[MSG: INVERT_SPINDLE_PWM]\r\n"); #endif @@ -41,27 +41,21 @@ void spindle_init() grbl_send(CLIENT_SERIAL, "[MSG: INVERT_SPINDLE_ENABLE_PIN]\r\n"); #endif - spindle_pwm_period = SPINDLE_PULSE_RES_COUNT; - - - spindle_pwm_off_value = (spindle_pwm_period * settings.spindle_pwm_off_value / 100); - spindle_pwm_min_value = (spindle_pwm_period * settings.spindle_pwm_min_value / 100); - spindle_pwm_max_value = (spindle_pwm_period * settings.spindle_pwm_max_value / 100); - - //pwm_gradient = (settings.spindle_pwm_max_value - settings.spindle_pwm_min_value)/(settings.rpm_max-settings.rpm_min); - pwm_gradient = (spindle_pwm_max_value-spindle_pwm_min_value)/(settings.rpm_max-settings.rpm_min); - - - if ( (F_TIMERS / (uint32_t)settings.spindle_pwm_freq) < spindle_pwm_max_value) { - /* - PWM Generator is based on 80,000,000 Hz counter - Therefor the freq determines the resolution 80,000,000 / freq = max resolution - For 5000 that is 80,000,000 / 5000 = 16000 - Round down to nearest bit count for SPINDLE_PWM_MAX_VALUE = 13bits (8192) - */ - grbl_sendf(CLIENT_SERIAL, "[MSG: Warning! Spindle freq %5.0f too high for requested PWM max %5.2f%% (%5.0f)]\r\n", settings.spindle_pwm_freq, settings.spindle_pwm_max_value, spindle_pwm_max_value); + // determine how many PWM counts are in eqach PWM cycle + spindle_pwm_period = ((1< settings.spindle_pwm_min_value) { + grbl_sendf(CLIENT_SERIAL, "[MSG: Warning spindle min pwm is greater than max. Check $35 and $36]\r\n", pwm_gradient); } + // pre-caculate some PWM count values + spindle_pwm_off_value = (spindle_pwm_period * settings.spindle_pwm_off_value / 100.0); + spindle_pwm_min_value = (spindle_pwm_period * settings.spindle_pwm_min_value / 100.0); + spindle_pwm_max_value = (spindle_pwm_period * settings.spindle_pwm_max_value / 100.0); + + // The pwm_gradient is the pwm duty cycle units per rpm + pwm_gradient = (spindle_pwm_max_value-spindle_pwm_min_value)/(settings.rpm_max-settings.rpm_min); + // Use DIR and Enable if pins are defined #ifdef SPINDLE_ENABLE_PIN pinMode(SPINDLE_ENABLE_PIN, OUTPUT); @@ -73,15 +67,15 @@ void spindle_init() // use the LED control feature to setup PWM https://docs.espressif.com/projects/esp-idf/en/latest/api-reference/peripherals/ledc.html ledcSetup(SPINDLE_PWM_CHANNEL, (double)settings.spindle_pwm_freq, SPINDLE_PWM_BIT_PRECISION); // setup the channel - ledcAttachPin(SPINDLE_PWM_PIN, SPINDLE_PWM_CHANNEL); // attach the PWM to the pin + ledcAttachPin(SPINDLE_PWM_PIN, SPINDLE_PWM_CHANNEL); // attach the PWM to the pin // Start with spindle off off - spindle_stop(); + spindle_stop(); #endif } void spindle_stop() -{ +{ spindle_set_enable(false); #ifdef SPINDLE_PWM_PIN @@ -119,6 +113,7 @@ uint8_t spindle_get_state() // returns SPINDLE_STATE_DISABLE, SPINDLE_STATE_CW void spindle_set_speed(uint32_t pwm_value) { #ifndef SPINDLE_PWM_PIN + //grbl_sendf(CLIENT_SERIAL, "[MSG: set speed...no pin defined]\r\n"); return; #else #ifndef SPINDLE_ENABLE_OFF_WITH_ZERO_SPEED @@ -160,7 +155,7 @@ uint32_t spindle_compute_pwm_value(float rpm){ #ifdef ENABLE_PIECEWISE_LINEAR_SPINDLE pwm_value = piecewise_linear_fit(rpm); #else - pwm_value = floor((rpm - settings.rpm_min)*pwm_gradient) + settings.spindle_pwm_min_value; + pwm_value = floor((rpm - settings.rpm_min)*pwm_gradient) + spindle_pwm_min_value; #endif } return(pwm_value); @@ -211,9 +206,7 @@ void spindle_sync(uint8_t state, float rpm) void grbl_analogWrite(uint8_t chan, uint32_t duty) { if (ledcRead(chan) != duty) // reduce unnecessary calls to ledcWrite() - { - // Useful for debug, but too many messages in laser mode - // grbl_sendf(CLIENT_SERIAL, "[MSG: grbl_analogWrite %d]\r\n", duty); + { ledcWrite(chan, duty); } } diff --git a/Grbl_Esp32/spindle_control.h b/Grbl_Esp32/spindle_control.h index fd4147d4..068661ef 100644 --- a/Grbl_Esp32/spindle_control.h +++ b/Grbl_Esp32/spindle_control.h @@ -31,7 +31,7 @@ #define SPINDLE_STATE_CW bit(0) #define SPINDLE_STATE_CCW bit(1) -#define SPINDLE_PULSE_RES_COUNT ((1<is_pwm_rate_adjusted) { - spindle_set_speed(settings.spindle_pwm_off_value); + spindle_set_speed(spindle_pwm_off_value); } } @@ -1325,7 +1325,7 @@ void st_prep_buffer() } else { sys.spindle_speed = 0.0; #if ( (defined VARIABLE_SPINDLE) && (defined SPINDLE_PWM_PIN) ) - prep.current_spindle_pwm = settings.spindle_pwm_off_value; + prep.current_spindle_pwm = spindle_pwm_off_value ; #endif } diff --git a/Grbl_Esp32/stepper.h b/Grbl_Esp32/stepper.h index d2dd6bbd..d99a9d01 100644 --- a/Grbl_Esp32/stepper.h +++ b/Grbl_Esp32/stepper.h @@ -47,6 +47,14 @@ #define PREP_FLAG_PARKING bit(2) #define PREP_FLAG_DECEL_OVERRIDE bit(3) +// which RMT channels to use with the axes +#define X_RMT_CHANNEL 0 +#define Y_RMT_CHANNEL 1 +#define Z_RMT_CHANNEL 2 +#define A_RMT_CHANNEL 3 +#define B_RMT_CHANNEL 4 +#define C_RMT_CHANNEL 5 + // Define Adaptive Multi-Axis Step-Smoothing(AMASS) levels and cutoff frequencies. The highest level // frequency bin starts at 0Hz and ends at its cutoff frequency. The next lower level frequency bin // starts at the next higher cutoff frequency, and so on. The cutoff frequencies for each level must diff --git a/Grbl_Esp32/system.cpp b/Grbl_Esp32/system.cpp index fbfd2264..dd54e371 100644 --- a/Grbl_Esp32/system.cpp +++ b/Grbl_Esp32/system.cpp @@ -183,13 +183,18 @@ uint8_t system_execute_line(char *line, uint8_t client) if(line[2] != '=') { return(STATUS_INVALID_STATEMENT); } 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': + case '$': case 'G': case 'C': case 'X': case '+': if ( line[2] != 0 ) { return(STATUS_INVALID_STATEMENT); } switch( line[1] ) { - case '$' : // Prints Grbl settings + case '$': 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(client); } - break; + else { + if (line[1] == '$') + report_grbl_settings(client, false); // entended settings depend on SHOW_EXTENDED_SETTINGS + else + report_grbl_settings(client, true); // force display of extended settings + } + 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(client); diff --git a/doc/csv/setting_codes_en_US.csv b/doc/csv/setting_codes_en_US.csv index 55362625..71571e40 100644 --- a/doc/csv/setting_codes_en_US.csv +++ b/doc/csv/setting_codes_en_US.csv @@ -21,10 +21,10 @@ "30","Maximum spindle speed","RPM","Maximum spindle speed. Sets PWM to 100% duty cycle." "31","Minimum spindle speed","RPM","Minimum spindle speed. Sets PWM to 0.4% or lowest duty cycle." "32","Laser-mode enable","boolean","Enables laser mode. Consecutive G1/2/3 commands will not halt when spindle speed is changed." -"33","Spindle PWM Freq","16-bit","Spindle PWM Freq" -"34","Spindle PWM Off Value","16-bit","Spindle PWM Off Value" -"35","Spindle PWM Min Value","16-bit","Spindle PWM Min Value" -"36","Spindle PWM Max Value","16-bit","Spindle PWM Max Value" +"33","Spindle PWM Freq","16-bit","Spindle PWM Freq (reboot to take effect)" +"34","Spindle PWM Off Value","16-bit","Spindle PWM Off Value (reboot to take effect)" +"35","Spindle PWM Min Value","16-bit","Spindle PWM Min Value (reboot to take effect)" +"36","Spindle PWM Max Value","16-bit","Spindle PWM Max Value (reboot to take effect)" "80-84","User integer Values","unsigned 16-bit","Reserved for custom machine use" "90-94","User Floating point value","float","Reserved for custom machine use" "100","X-axis travel resolution","step/mm","X-axis travel resolution in steps per millimeter."