1
0
mirror of https://github.com/bdring/Grbl_Esp32.git synced 2025-08-18 12:21:39 +02:00

Added Spindle Invert and Major Spindle Cleanup

This commit is contained in:
bdring
2019-10-11 14:51:08 -05:00
parent f0e5a82105
commit 1b38108ca1
6 changed files with 219 additions and 193 deletions

View File

@@ -59,95 +59,94 @@
*/
#define CPU_MAP_NAME "CPU_MAP_DEFAULT - Demo Only No I/O!"
// the following items currently need to be defined, but no i/o needs to be mapped
// fixing soon
#define LIMIT_MASK 0 // no limit pins
#endif
#ifdef CPU_MAP_ESP32
// This is the CPU Map for the ESP32 Development Controller
// https://github.com/bdring/Grbl_ESP32_Development_Controller
// https://www.tindie.com/products/33366583/grbl_esp32-cnc-development-board-v35/
// Select the version (uncomment one of them)
#define CPU_MAP_V3p5 // version 3.5 and earlier
//#define CPU_MAP_V4 // version 4 or higher (in developement)
#define USE_RMT_STEPS
// 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.
#if (defined CPU_MAP_V4)
#define CPU_MAP_NAME "CPU_MAP_ESP32_V4"
#define X_DIRECTION_PIN GPIO_NUM_14
#define Y_STEP_PIN GPIO_NUM_26
#define Y_DIRECTION_PIN GPIO_NUM_15
#define COOLANT_FLOOD_PIN GPIO_NUM_25
#define SPINDLE_PWM_PIN GPIO_NUM_2
#define X_LIMIT_PIN GPIO_NUM_17
#define Z_LIMIT_PIN GPIO_NUM_16
#elif (defined CPU_MAP_V3p5)
#define CPU_MAP_NAME "CPU_MAP_ESP32_V3.5"
#define X_DIRECTION_PIN GPIO_NUM_26
#define Y_STEP_PIN GPIO_NUM_14
#define Y_DIRECTION_PIN GPIO_NUM_25
#define COOLANT_FLOOD_PIN GPIO_NUM_16
#define SPINDLE_PWM_PIN GPIO_NUM_17
#define X_LIMIT_PIN GPIO_NUM_2
#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 Z_STEP_PIN GPIO_NUM_27
#define Z_DIRECTION_PIN GPIO_NUM_33
#define Z_RMT_CHANNEL 2
// OK to comment out to use pin for other features
#define STEPPERS_DISABLE_PIN GPIO_NUM_13
#define COOLANT_MIST_PIN GPIO_NUM_21
#define SPINDLE_PWM_CHANNEL 0
// 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)
#define SPINDLE_PWM_BASE_FREQ 5000 // Hz
#define SPINDLE_PWM_BIT_PRECISION 8 // be sure to match this with SPINDLE_PWM_MAX_VALUE
#define SPINDLE_PWM_BIT_PRECISION 8
#define SPINDLE_PWM_OFF_VALUE 0
#define SPINDLE_PWM_MAX_VALUE 255 // (2^SPINDLE_PWM_BIT_PRECISION)
#define SPINDLE_PWM_MAX_VALUE 255
//#define INVERT_SPINDLE_PWM
#ifndef SPINDLE_PWM_MIN_VALUE
#define SPINDLE_PWM_MIN_VALUE 1 // Must be greater than zero.
#define SPINDLE_PWM_MIN_VALUE 1 // Must be greater than zero.
#endif
#define SPINDLE_ENABLE_PIN GPIO_NUM_22
#define SPINDLE_PWM_RANGE (SPINDLE_PWM_MAX_VALUE-SPINDLE_PWM_MIN_VALUE)
#endif
// see versions for X and Z
#define Y_LIMIT_PIN GPIO_NUM_4
#define LIMIT_MASK B111
#ifdef CPU_MAP_ESP32
// 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 CPU_MAP_NAME "CPU_MAP_ESP32"
#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
#define Z_STEP_PIN GPIO_NUM_27
#define Z_DIRECTION_PIN GPIO_NUM_33
#define Z_RMT_CHANNEL 2
// OK to comment out to use pin for other features
#define STEPPERS_DISABLE_PIN GPIO_NUM_13
// *** 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
// 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)
#define SPINDLE_PWM_BASE_FREQ 5000 // Hz
#define SPINDLE_PWM_BIT_PRECISION 8 // be sure to match this with SPINDLE_PWM_MAX_VALUE
#define SPINDLE_PWM_OFF_VALUE 0
#define SPINDLE_PWM_MAX_VALUE 255 // (2^SPINDLE_PWM_BIT_PRECISION)
#ifndef SPINDLE_PWM_MIN_VALUE
#define SPINDLE_PWM_MIN_VALUE 1 // Must be greater than zero.
#endif
#define SPINDLE_ENABLE_PIN GPIO_NUM_22
#define SPINDLE_PWM_RANGE (SPINDLE_PWM_MAX_VALUE-SPINDLE_PWM_MIN_VALUE)
// 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_PIN GPIO_NUM_2
#define Y_LIMIT_PIN GPIO_NUM_4
#define Z_LIMIT_PIN GPIO_NUM_15
#define LIMIT_MASK B111
#define PROBE_PIN GPIO_NUM_32
#define CONTROL_SAFETY_DOOR_PIN GPIO_NUM_35 // 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
#define PROBE_PIN GPIO_NUM_32
#define CONTROL_SAFETY_DOOR_PIN GPIO_NUM_35 // 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
#endif
#ifdef CPU_MAP_ESPDUINO_32
@@ -189,7 +188,6 @@
#define SPINDLE_PWM_MIN_VALUE 1 // Must be greater than zero.
#endif
#define SPINDLE_PWM_RANGE (SPINDLE_PWM_MAX_VALUE-SPINDLE_PWM_MIN_VALUE)
#define SPINDLE_DIR_PIN GPIO_NUM_18 // Uno D13
@@ -260,8 +258,6 @@
#define SPINDLE_PWM_MIN_VALUE SPINDLE_PWM_OFF_VALUE // Must be greater than zero.
#endif
#define SPINDLE_PWM_RANGE (SPINDLE_PWM_MAX_VALUE-SPINDLE_PWM_MIN_VALUE)
#define SPINDLE_ENABLE_PIN GPIO_NUM_22
// if these spindle function pins are defined, they will be activated in the code
@@ -336,8 +332,6 @@
#define SPINDLE_PWM_MIN_VALUE 1 // Must be greater than zero.
#endif
#define SPINDLE_PWM_RANGE (SPINDLE_PWM_MAX_VALUE-SPINDLE_PWM_MIN_VALUE)
#define USING_SERVO // uncomment to use this feature
//#define USING_SOLENOID // uncomment to use this feature
@@ -486,8 +480,6 @@
#endif
#define DEFAULTS_MIDTBOT
#define SPINDLE_PWM_RANGE (SPINDLE_PWM_MAX_VALUE-SPINDLE_PWM_MIN_VALUE)
#define SERVO_PEN_PIN GPIO_NUM_27
#ifdef DEFAULTS_GENERIC
@@ -608,7 +600,6 @@
#define SPINDLE_PWM_MIN_VALUE 1 // Must be greater than zero.
#endif
#define SPINDLE_PWM_RANGE (SPINDLE_PWM_MAX_VALUE-SPINDLE_PWM_MIN_VALUE)
//#define USE_PEN_SERVO
//#define SERVO_PEN_PIN GPIO_NUM_16
@@ -722,8 +713,6 @@
#define SPINDLE_PWM_MIN_VALUE 1 // Must be greater than zero.
#endif
#define SPINDLE_PWM_RANGE (SPINDLE_PWM_MAX_VALUE-SPINDLE_PWM_MIN_VALUE)
#define SERVO_Y_PIN GPIO_NUM_14
#define SERVO_Y_CHANNEL_NUM 6
#define SERVO_Y_RANGE_MIN 0.0
@@ -818,8 +807,6 @@
#define SPINDLE_PWM_MIN_VALUE 1 // Must be greater than zero.
#endif
#define SPINDLE_PWM_RANGE (SPINDLE_PWM_MAX_VALUE-SPINDLE_PWM_MIN_VALUE)
// define Y and Z as servos
#define USE_SERVO_AXES
#define SERVO_Y_PIN GPIO_NUM_27
@@ -980,8 +967,6 @@
#define SPINDLE_PWM_MIN_VALUE 1 // Must be greater than zero.
#endif
#define SPINDLE_PWM_RANGE (SPINDLE_PWM_MAX_VALUE-SPINDLE_PWM_MIN_VALUE)
// Note: Only uncomment this if USE_SPINDLE_RELAY is commented out.
// Relay can be used for spindle or either coolant
//#define COOLANT_FLOOD_PIN GPIO_NUM_2
@@ -1084,8 +1069,6 @@
#define SPINDLE_PWM_MIN_VALUE 1 // Must be greater than zero.
#endif
#define SPINDLE_PWM_RANGE (SPINDLE_PWM_MAX_VALUE-SPINDLE_PWM_MIN_VALUE)
// 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
@@ -1189,8 +1172,6 @@
#define SPINDLE_PWM_MIN_VALUE 1 // Must be greater than zero.
#endif
#define SPINDLE_PWM_RANGE (SPINDLE_PWM_MAX_VALUE-SPINDLE_PWM_MIN_VALUE)
#define X_LIMIT_PIN GPIO_NUM_2
#define Y_LIMIT_PIN GPIO_NUM_4
#define LIMIT_MASK B11
@@ -1291,7 +1272,6 @@
#define SPINDLE_PWM_OFF_VALUE 0
#define SPINDLE_PWM_MAX_VALUE 255 // (2^SPINDLE_PWM_BIT_PRECISION)
#define SPINDLE_PWM_MIN_VALUE SPINDLE_PWM_OFF_VALUE // Must be greater than zero.
#define SPINDLE_PWM_RANGE (SPINDLE_PWM_MAX_VALUE-SPINDLE_PWM_MIN_VALUE)
// defaults ... <Idle|MPos:-497.000,-3.000,0.000,-3.000,-497.000,0.000|FS:0,0>
#ifdef DEFAULTS_GENERIC

View File

@@ -320,6 +320,9 @@ uint8_t gc_execute_line(char *line, uint8_t client)
case 3:
case 4:
case 5:
#ifndef SPINDLE_PWM_PIN
grbl_send(CLIENT_SERIAL, "[MSG:No spindle pin defined]\r\n");
#endif
word_bit = MODAL_GROUP_M7;
switch(int_value) {
case 3:

View File

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

View File

@@ -24,32 +24,47 @@ static float pwm_gradient; // Precalulated value to speed up rpm to PWM conversi
void spindle_init()
{
pwm_gradient = SPINDLE_PWM_RANGE/(settings.rpm_max-settings.rpm_min);
// 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://docs.espressif.com/projects/esp-idf/en/latest/api-reference/peripherals/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
#endif
// Start with spindle off off
spindle_stop();
#ifdef INVERT_SPINDLE_PWM
grbl_send(CLIENT_SERIAL, "[MSG: INVERT_SPINDLE_PWM]\r\n");
#endif
#ifdef INVERT_SPINDLE_ENABLE_PIN
grbl_send(CLIENT_SERIAL, "[MSG: INVERT_SPINDLE_ENABLE_PIN]\r\n");
#endif
pwm_gradient = SPINDLE_PWM_RANGE/(settings.rpm_max-settings.rpm_min);
// 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
// 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, 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 spindle off off
spindle_stop();
#endif
}
void spindle_stop()
{
spindle_set_enable(false);
#ifdef SPINDLE_PWM_PIN
grbl_analogWrite(SPINDLE_PWM_CHANNEL, SPINDLE_PWM_OFF_VALUE);
#ifndef INVERT_SPINDLE_PWM
grbl_analogWrite(SPINDLE_PWM_CHANNEL, SPINDLE_PWM_OFF_VALUE);
#else
grbl_analogWrite(SPINDLE_PWM_CHANNEL, (1<<SPINDLE_PWM_BIT_PRECISION) - 1);
#endif
#endif
}
@@ -58,95 +73,118 @@ uint8_t spindle_get_state() // returns SPINDLE_STATE_DISABLE, SPINDLE_STATE_CW
// TODO Update this when direction and enable pin are added
#ifndef SPINDLE_PWM_PIN
return(SPINDLE_STATE_DISABLE);
#endif
#else
if (ledcRead(SPINDLE_PWM_CHANNEL) == 0) // Check the PWM value
return(SPINDLE_STATE_DISABLE);
else
{
#ifdef SPINDLE_DIR_PIN
if (digitalRead(SPINDLE_DIR_PIN))
return (SPINDLE_STATE_CW);
else
return(SPINDLE_STATE_CCW);
#else
return(SPINDLE_STATE_CW);
#endif
}
if (ledcRead(SPINDLE_PWM_CHANNEL) == 0) // Check the PWM value
return(SPINDLE_STATE_DISABLE);
else
{
#ifdef SPINDLE_DIR_PIN
if (digitalRead(SPINDLE_DIR_PIN))
return (SPINDLE_STATE_CW);
else
return(SPINDLE_STATE_CCW);
#else
return(SPINDLE_STATE_CW);
#endif
}
#endif
}
void spindle_set_speed(uint32_t pwm_value)
{
#ifndef SPINDLE_PWM_PIN
return;
#else
#ifndef SPINDLE_ENABLE_OFF_WITH_ZERO_SPEED
spindle_set_enable(true);
#else
spindle_set_enable(pwm_value != 0);
#endif
#ifndef INVERT_SPINDLE_PWM
grbl_analogWrite(SPINDLE_PWM_CHANNEL, pwm_value);
#else
if (pwm_value == 0) {
grbl_analogWrite(SPINDLE_PWM_CHANNEL, (1<<SPINDLE_PWM_BIT_PRECISION));
}
else {
grbl_analogWrite(SPINDLE_PWM_CHANNEL, (1<<SPINDLE_PWM_BIT_PRECISION) - pwm_value - 1);
}
#endif
#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.
uint32_t spindle_compute_pwm_value(float rpm)
{
uint32_t pwm_value;
rpm *= (0.010*sys.spindle_speed_ovr); // Scale by spindle speed override value.
// Calculate PWM register value based on rpm max/min settings and programmed rpm.
if ((settings.rpm_min >= settings.rpm_max) || (rpm >= settings.rpm_max)) {
// No PWM range possible. Set simple on/off spindle control pin state.
sys.spindle_speed = settings.rpm_max;
pwm_value = SPINDLE_PWM_MAX_VALUE;
} else if (rpm <= settings.rpm_min) {
if (rpm == 0.0) { // S0 disables spindle
sys.spindle_speed = 0.0;
pwm_value = SPINDLE_PWM_OFF_VALUE;
} else { // Set minimum PWM output
sys.spindle_speed = settings.rpm_min;
pwm_value = SPINDLE_PWM_MIN_VALUE;
}
} else {
// Compute intermediate PWM value with linear spindle speed model.
// NOTE: A nonlinear model could be installed here, if required, but keep it VERY light-weight.
sys.spindle_speed = rpm;
pwm_value = floor((rpm-settings.rpm_min)*pwm_gradient) + SPINDLE_PWM_MIN_VALUE;
}
return(pwm_value);
#ifdef SPINDLE_PWM_PIN
uint32_t pwm_value;
rpm *= (0.010*sys.spindle_speed_ovr); // Scale by spindle speed override value.
// Calculate PWM register value based on rpm max/min settings and programmed rpm.
if ((settings.rpm_min >= settings.rpm_max) || (rpm >= settings.rpm_max)) {
// No PWM range possible. Set simple on/off spindle control pin state.
sys.spindle_speed = settings.rpm_max;
pwm_value = SPINDLE_PWM_MAX_VALUE;
} else if (rpm <= settings.rpm_min) {
if (rpm == 0.0) { // S0 disables spindle
sys.spindle_speed = 0.0;
pwm_value = SPINDLE_PWM_OFF_VALUE;
} else { // Set minimum PWM output
sys.spindle_speed = settings.rpm_min;
pwm_value = SPINDLE_PWM_MIN_VALUE;
}
} else {
// Compute intermediate PWM value with linear spindle speed model.
// NOTE: A nonlinear model could be installed here, if required, but keep it VERY light-weight.
sys.spindle_speed = rpm;
pwm_value = floor((rpm-settings.rpm_min)*pwm_gradient) + SPINDLE_PWM_MIN_VALUE;
}
return(pwm_value);
#else
return(0); // no SPINDLE_PWM_PIN
#endif
}
void spindle_set_state(uint8_t state, float rpm)
{
if (sys.abort) { return; } // Block during abort.
if (state == SPINDLE_DISABLE) { // Halt or set spindle direction and rpm.
sys.spindle_speed = 0.0;
spindle_stop();
} else {
#ifdef SPINDLE_PWM_PIN
if (sys.abort) { return; } // Block during abort.
if (state == SPINDLE_DISABLE) { // Halt or set spindle direction and rpm.
sys.spindle_speed = 0.0;
spindle_stop();
} else {
// TODO ESP32 Enable and direction control
#ifdef SPINDLE_DIR_PIN
digitalWrite(SPINDLE_DIR_PIN, state == SPINDLE_ENABLE_CW);
#endif
// 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);
}
// 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
spindle_set_speed(spindle_compute_pwm_value(rpm));
}
sys.report_ovr_counter = 0; // Set to report change immediately
#endif
}
void spindle_sync(uint8_t state, float rpm)
{
if (sys.state == STATE_CHECK_MODE) { return; }
protocol_buffer_synchronize(); // Empty planner buffer to ensure spindle is set when programmed.
spindle_set_state(state,rpm);
if (sys.state == STATE_CHECK_MODE) {
return;
}
protocol_buffer_synchronize(); // Empty planner buffer to ensure spindle is set when programmed.
spindle_set_state(state,rpm);
}
@@ -154,7 +192,7 @@ void grbl_analogWrite(uint8_t chan, uint32_t duty)
{
if (ledcRead(chan) != duty) // reduce unnecessary calls to ledcWrite()
{
// grbl_sendf(CLIENT_SERIAL, "[MSG: Spindle duty: %d of %d]\r\n", duty, SPINDLE_PWM_MAX_VALUE); // debug statement
ledcWrite(chan, duty);
}
}

View File

@@ -23,6 +23,8 @@
#include "grbl.h"
#define SPINDLE_PWM_RANGE (SPINDLE_PWM_MAX_VALUE-SPINDLE_PWM_MIN_VALUE)
#define SPINDLE_NO_SYNC false
#define SPINDLE_FORCE_SYNC true

View File

@@ -282,7 +282,7 @@ void IRAM_ATTR onStepperDriverTimer(void *para) // ISR It is time to take a ste
} else {
// Segment buffer empty. Shutdown.
st_go_idle();
#ifdef VARIABLE_SPINDLE
#if ( (defined VARIABLE_SPINDLE) && (defined SPINDLE_PWM_PIN) )
if (!(sys.state & STATE_JOG)) { // added to prevent ... jog after probing crash
// Ensure pwm is set properly upon completion of rate-controlled motion.
if (st.exec_block->is_pwm_rate_adjusted) {
@@ -1316,7 +1316,10 @@ void st_prep_buffer()
prep.current_spindle_pwm = spindle_compute_pwm_value(rpm);
} else {
sys.spindle_speed = 0.0;
prep.current_spindle_pwm = SPINDLE_PWM_OFF_VALUE;
#if ( (defined VARIABLE_SPINDLE) && (defined SPINDLE_PWM_PIN) )
prep.current_spindle_pwm = SPINDLE_PWM_OFF_VALUE;
#endif
}
bit_false(sys.step_control,STEP_CONTROL_UPDATE_SPINDLE_PWM);
}