mirror of
https://github.com/bdring/Grbl_Esp32.git
synced 2025-09-02 19:02:35 +02:00
A Work in progress
- Messy code - Does not work yet.
This commit is contained in:
@@ -115,11 +115,11 @@ Some features should not be changed. See notes below.
|
||||
//#define CONNECT_TO_SSID "your SSID"
|
||||
//#define SSID_PASSWORD "your SSID password"
|
||||
//CONFIGURE_EYECATCH_BEGIN (DO NOT MODIFY THIS LINE)
|
||||
#define ENABLE_BLUETOOTH // enable bluetooth
|
||||
//#define ENABLE_BLUETOOTH // enable bluetooth
|
||||
|
||||
#define ENABLE_SD_CARD // enable use of SD Card to run jobs
|
||||
|
||||
#define ENABLE_WIFI //enable wifi
|
||||
//#define ENABLE_WIFI //enable wifi
|
||||
|
||||
#define ENABLE_HTTP //enable HTTP and all related services
|
||||
#define ENABLE_OTA //enable OTA
|
||||
|
@@ -8,7 +8,7 @@
|
||||
|
||||
// !!! For initial testing, start with test_drive.h which disables
|
||||
// all I/O pins
|
||||
#include "Machines/test_drive.h"
|
||||
#include "Machines/3axis_v4.h"
|
||||
|
||||
// !!! For actual use, change the line above to select a board
|
||||
// from Machines/, for example:
|
||||
|
@@ -464,7 +464,7 @@ void protocol_exec_rt_system() {
|
||||
last_s_override = MIN(last_s_override, MAX_SPINDLE_SPEED_OVERRIDE);
|
||||
last_s_override = MAX(last_s_override, MIN_SPINDLE_SPEED_OVERRIDE);
|
||||
if (last_s_override != sys.spindle_speed_ovr) {
|
||||
bit_true(sys.step_control, STEP_CONTROL_UPDATE_SPINDLE_PWM);
|
||||
bit_true(sys.step_control, STEP_CONTROL_UPDATE_SPINDLE_RPM);
|
||||
sys.spindle_speed_ovr = last_s_override;
|
||||
sys.report_ovr_counter = 0; // Set to report change immediately
|
||||
}
|
||||
@@ -657,7 +657,7 @@ static void protocol_exec_rt_suspend() {
|
||||
if (bit_isfalse(sys.suspend, SUSPEND_RESTART_RETRACT)) {
|
||||
if (bit_istrue(settings.flags, BITFLAG_LASER_MODE)) {
|
||||
// When in laser mode, ignore spindle spin-up delay. Set to turn on laser when cycle starts.
|
||||
bit_true(sys.step_control, STEP_CONTROL_UPDATE_SPINDLE_PWM);
|
||||
bit_true(sys.step_control, STEP_CONTROL_UPDATE_SPINDLE_RPM);
|
||||
} else {
|
||||
spindle_set_state((restore_condition & (PL_COND_FLAG_SPINDLE_CW | PL_COND_FLAG_SPINDLE_CCW)), restore_spindle_speed);
|
||||
delay_sec(SAFETY_DOOR_SPINDLE_DELAY, DELAY_MODE_SYS_SUSPEND);
|
||||
@@ -716,7 +716,7 @@ static void protocol_exec_rt_suspend() {
|
||||
report_feedback_message(MESSAGE_SPINDLE_RESTORE);
|
||||
if (bit_istrue(settings.flags, BITFLAG_LASER_MODE)) {
|
||||
// When in laser mode, ignore spindle spin-up delay. Set to turn on laser when cycle starts.
|
||||
bit_true(sys.step_control, STEP_CONTROL_UPDATE_SPINDLE_PWM);
|
||||
bit_true(sys.step_control, STEP_CONTROL_UPDATE_SPINDLE_RPM);
|
||||
} else
|
||||
spindle_set_state((restore_condition & (PL_COND_FLAG_SPINDLE_CW | PL_COND_FLAG_SPINDLE_CCW)), restore_spindle_speed);
|
||||
}
|
||||
@@ -727,10 +727,10 @@ static void protocol_exec_rt_suspend() {
|
||||
}
|
||||
} else {
|
||||
// Handles spindle state during hold. NOTE: Spindle speed overrides may be altered during hold state.
|
||||
// NOTE: STEP_CONTROL_UPDATE_SPINDLE_PWM is automatically reset upon resume in step generator.
|
||||
if (bit_istrue(sys.step_control, STEP_CONTROL_UPDATE_SPINDLE_PWM)) {
|
||||
// NOTE: STEP_CONTROL_UPDATE_SPINDLE_RPM is automatically reset upon resume in step generator.
|
||||
if (bit_istrue(sys.step_control, STEP_CONTROL_UPDATE_SPINDLE_RPM)) {
|
||||
spindle_set_state((restore_condition & (PL_COND_FLAG_SPINDLE_CW | PL_COND_FLAG_SPINDLE_CCW)), restore_spindle_speed);
|
||||
bit_false(sys.step_control, STEP_CONTROL_UPDATE_SPINDLE_PWM);
|
||||
bit_false(sys.step_control, STEP_CONTROL_UPDATE_SPINDLE_RPM);
|
||||
}
|
||||
}
|
||||
}
|
||||
|
@@ -19,9 +19,15 @@
|
||||
*/
|
||||
|
||||
#include "grbl.h"
|
||||
#include "tools/SpindleClass.h"
|
||||
#include "tools/SpindleClass.cpp"
|
||||
|
||||
int8_t spindle_pwm_chan_num;
|
||||
|
||||
// define a spindle type
|
||||
//RelaySpindle my_spindle;
|
||||
Laser my_spindle;
|
||||
|
||||
#ifdef SPINDLE_PWM_PIN
|
||||
static float pwm_gradient; // Precalulated value to speed up rpm to PWM conversions.
|
||||
uint32_t spindle_pwm_period; // how many counts in 1 period
|
||||
@@ -31,142 +37,30 @@ int8_t spindle_pwm_chan_num;
|
||||
#endif
|
||||
|
||||
void spindle_init() {
|
||||
#ifdef SPINDLE_PWM_PIN
|
||||
#ifdef INVERT_SPINDLE_PWM
|
||||
grbl_msg_sendf(CLIENT_SERIAL, MSG_LEVEL_INFO, "INVERT_SPINDLE_PWM");
|
||||
#endif
|
||||
#ifdef INVERT_SPINDLE_ENABLE_PIN
|
||||
grbl_msg_sendf(CLIENT_SERIAL, MSG_LEVEL_INFO, "INVERT_SPINDLE_ENABLE_PIN");
|
||||
#endif
|
||||
// determine how many PWM counts are in eqach PWM cycle
|
||||
spindle_pwm_period = ((1 << SPINDLE_PWM_BIT_PRECISION) - 1);
|
||||
if (settings.spindle_pwm_min_value > settings.spindle_pwm_min_value)
|
||||
grbl_msg_sendf(CLIENT_SERIAL, MSG_LEVEL_INFO, "Warning spindle min pwm is greater than max. Check $35 and $36");
|
||||
// pre-caculate some PWM count values
|
||||
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);
|
||||
#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
|
||||
spindle_pwm_chan_num = sys_get_next_PWM_chan_num();
|
||||
ledcSetup(spindle_pwm_chan_num, (double)settings.spindle_pwm_freq, SPINDLE_PWM_BIT_PRECISION); // setup the channel
|
||||
ledcAttachPin(SPINDLE_PWM_PIN, spindle_pwm_chan_num); // attach the PWM to the pin
|
||||
// Start with spindle off off
|
||||
spindle_stop();
|
||||
#endif
|
||||
my_spindle.init();
|
||||
my_spindle.config_message();
|
||||
}
|
||||
|
||||
void spindle_stop() {
|
||||
spindle_set_enable(false);
|
||||
#ifdef SPINDLE_PWM_PIN
|
||||
#ifndef INVERT_SPINDLE_PWM
|
||||
grbl_analogWrite(spindle_pwm_chan_num, spindle_pwm_off_value);
|
||||
#else
|
||||
grbl_analogWrite(spindle_pwm_chan_num, (1 << SPINDLE_PWM_BIT_PRECISION)); // TO DO...wrong for min_pwm
|
||||
#endif
|
||||
#endif
|
||||
my_spindle.stop();
|
||||
}
|
||||
|
||||
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
|
||||
#ifndef SPINDLE_PWM_PIN
|
||||
return (SPINDLE_STATE_DISABLE);
|
||||
#else
|
||||
if (ledcRead(spindle_pwm_chan_num) == 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
|
||||
uint8_t spindle_get_state() {
|
||||
return my_spindle.get_state();
|
||||
}
|
||||
|
||||
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
|
||||
spindle_set_enable(true);
|
||||
#else
|
||||
spindle_set_enable(pwm_value != 0);
|
||||
#endif
|
||||
#ifndef INVERT_SPINDLE_PWM
|
||||
grbl_analogWrite(spindle_pwm_chan_num, pwm_value);
|
||||
#else
|
||||
grbl_analogWrite(spindle_pwm_chan_num, (1 << SPINDLE_PWM_BIT_PRECISION) - pwm_value);
|
||||
#endif
|
||||
#endif
|
||||
my_spindle.set_pwm(pwm_value);
|
||||
}
|
||||
|
||||
uint32_t spindle_compute_pwm_value(float rpm) {
|
||||
#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;
|
||||
#ifdef ENABLE_PIECEWISE_LINEAR_SPINDLE
|
||||
pwm_value = piecewise_linear_fit(rpm);
|
||||
#else
|
||||
pwm_value = floor((rpm - settings.rpm_min) * pwm_gradient) + spindle_pwm_min_value;
|
||||
#endif
|
||||
}
|
||||
return (pwm_value);
|
||||
#else
|
||||
return (0); // no SPINDLE_PWM_PIN
|
||||
#endif
|
||||
return 0;
|
||||
}
|
||||
|
||||
|
||||
// Called by spindle_set_state() and step segment generator. Keep routine small and efficient.
|
||||
void spindle_set_state(uint8_t state, float rpm) {
|
||||
#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
|
||||
// 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
|
||||
#endif
|
||||
my_spindle.set_state(state, rpm);
|
||||
}
|
||||
|
||||
|
||||
@@ -179,24 +73,11 @@ void spindle_sync(uint8_t state, float rpm) {
|
||||
|
||||
|
||||
void grbl_analogWrite(uint8_t chan, uint32_t duty) {
|
||||
// Remember the old duty cycle in memory instead of reading
|
||||
// it from the I/O peripheral because I/O reads are quite
|
||||
// a bit slower than memory reads.
|
||||
static uint32_t old_duty = 0;
|
||||
if (old_duty != duty) { // reduce unnecessary calls to ledcWrite()
|
||||
old_duty = duty;
|
||||
ledcWrite(chan, 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
|
||||
|
||||
}
|
||||
|
||||
uint32_t piecewise_linear_fit(float rpm) {
|
||||
|
@@ -22,6 +22,7 @@
|
||||
#define spindle_control_h
|
||||
|
||||
#include "grbl.h"
|
||||
#include "tools/SpindleClass.h"
|
||||
|
||||
|
||||
#define SPINDLE_NO_SYNC false
|
||||
@@ -32,6 +33,7 @@
|
||||
#define SPINDLE_STATE_CCW bit(1)
|
||||
|
||||
extern uint32_t spindle_pwm_off_value;
|
||||
extern Laser my_spindle;
|
||||
|
||||
void spindle_init();
|
||||
void spindle_stop();
|
||||
|
@@ -37,9 +37,7 @@ typedef struct {
|
||||
uint32_t steps[N_AXIS];
|
||||
uint32_t step_event_count;
|
||||
uint8_t direction_bits;
|
||||
#ifdef VARIABLE_SPINDLE
|
||||
uint8_t is_pwm_rate_adjusted; // Tracks motions that require constant laser power/rate
|
||||
#endif
|
||||
} st_block_t;
|
||||
static st_block_t st_block_buffer[SEGMENT_BUFFER_SIZE - 1];
|
||||
|
||||
@@ -56,9 +54,7 @@ typedef struct {
|
||||
#else
|
||||
uint8_t prescaler; // Without AMASS, a prescaler is required to adjust for slow timing.
|
||||
#endif
|
||||
#ifdef VARIABLE_SPINDLE
|
||||
uint16_t spindle_pwm;
|
||||
#endif
|
||||
uint16_t spindle_rpm; // TODO get rid of this.
|
||||
} segment_t;
|
||||
static segment_t segment_buffer[SEGMENT_BUFFER_SIZE];
|
||||
|
||||
@@ -145,10 +141,11 @@ typedef struct {
|
||||
float accelerate_until; // Acceleration ramp end measured from end of block (mm)
|
||||
float decelerate_after; // Deceleration ramp start measured from end of block (mm)
|
||||
|
||||
#ifdef VARIABLE_SPINDLE
|
||||
|
||||
float inv_rate; // Used by PWM laser mode to speed up segment calculations.
|
||||
uint16_t current_spindle_pwm;
|
||||
#endif
|
||||
uint16_t current_spindle_pwm; // todo remove
|
||||
float current_spindle_rpm;
|
||||
|
||||
} st_prep_t;
|
||||
static st_prep_t prep;
|
||||
|
||||
@@ -283,20 +280,20 @@ void IRAM_ATTR onStepperDriverTimer(void* para) { // ISR It is time to take a st
|
||||
st.steps[C_AXIS] = st.exec_block->steps[C_AXIS] >> st.exec_segment->amass_level;
|
||||
#endif
|
||||
#endif
|
||||
#ifdef VARIABLE_SPINDLE
|
||||
|
||||
// Set real-time spindle output as segment is loaded, just prior to the first step.
|
||||
spindle_set_speed(st.exec_segment->spindle_pwm);
|
||||
#endif
|
||||
spindle_set_speed(st.exec_segment->spindle_rpm);
|
||||
|
||||
} else {
|
||||
// Segment buffer empty. Shutdown.
|
||||
st_go_idle();
|
||||
#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)
|
||||
spindle_set_speed(spindle_pwm_off_value);
|
||||
}
|
||||
#endif
|
||||
|
||||
system_set_exec_state_flag(EXEC_CYCLE_STOP); // Flag main program for cycle end
|
||||
return; // Nothing to do but exit.
|
||||
}
|
||||
@@ -677,37 +674,37 @@ void set_direction_pins_on(uint8_t onMask) {
|
||||
#ifdef X_DIRECTION_PIN
|
||||
digitalWrite(X_DIRECTION_PIN, (onMask & (1 << X_AXIS)));
|
||||
#endif
|
||||
#ifdef X2_DIRECTION_PIN // optional ganged axis
|
||||
#ifdef X2_DIRECTION_PIN // optional ganged axis
|
||||
digitalWrite(X2_DIRECTION_PIN, (onMask & (1 << X_AXIS)));
|
||||
#endif
|
||||
#ifdef Y_DIRECTION_PIN
|
||||
digitalWrite(Y_DIRECTION_PIN, (onMask & (1 << Y_AXIS)));
|
||||
#endif
|
||||
#ifdef Y2_DIRECTION_PIN // optional ganged axis
|
||||
#ifdef Y2_DIRECTION_PIN // optional ganged axis
|
||||
digitalWrite(Y2_DIRECTION_PIN, (onMask & (1 << Y_AXIS)));
|
||||
#endif
|
||||
#ifdef Z_DIRECTION_PIN
|
||||
digitalWrite(Z_DIRECTION_PIN, (onMask & (1 << Z_AXIS)));
|
||||
#endif
|
||||
#ifdef Z2_DIRECTION_PIN // optional ganged axis
|
||||
#ifdef Z2_DIRECTION_PIN // optional ganged axis
|
||||
digitalWrite(Z2_DIRECTION_PIN, (onMask & (1 << Z_AXIS)));
|
||||
#endif
|
||||
#ifdef A_DIRECTION_PIN
|
||||
digitalWrite(A_DIRECTION_PIN, (onMask & (1 << A_AXIS)));
|
||||
#endif
|
||||
#ifdef A2_DIRECTION_PIN // optional ganged axis
|
||||
#ifdef A2_DIRECTION_PIN // optional ganged axis
|
||||
digitalWrite(A2_DIRECTION_PIN, (onMask & (1 << A_AXIS)));
|
||||
#endif
|
||||
#ifdef B_DIRECTION_PIN
|
||||
digitalWrite(B_DIRECTION_PIN, (onMask & (1 << B_AXIS)));
|
||||
#endif
|
||||
#ifdef B2_DIRECTION_PIN // optional ganged axis
|
||||
#ifdef B2_DIRECTION_PIN // optional ganged axis
|
||||
digitalWrite(B2_DIRECTION_PIN, (onMask & (1 << B_AXIS)));
|
||||
#endif
|
||||
#ifdef C_DIRECTION_PIN
|
||||
digitalWrite(C_DIRECTION_PIN, (onMask & (1 << C_AXIS)));
|
||||
#endif
|
||||
#ifdef C2_DIRECTION_PIN // optional ganged axis
|
||||
#ifdef C2_DIRECTION_PIN // optional ganged axis
|
||||
digitalWrite(C2_DIRECTION_PIN, (onMask & (1 << C_AXIS)));
|
||||
#endif
|
||||
}
|
||||
@@ -986,18 +983,9 @@ void st_prep_buffer() {
|
||||
prep.recalculate_flag &= ~(PREP_FLAG_DECEL_OVERRIDE);
|
||||
} else
|
||||
prep.current_speed = sqrt(pl_block->entry_speed_sqr);
|
||||
#ifdef VARIABLE_SPINDLE
|
||||
// Setup laser mode variables. PWM rate adjusted motions will always complete a motion with the
|
||||
// spindle off.
|
||||
st_prep_block->is_pwm_rate_adjusted = false;
|
||||
if (settings.flags & BITFLAG_LASER_MODE) {
|
||||
if (pl_block->condition & PL_COND_FLAG_SPINDLE_CCW) {
|
||||
// Pre-compute inverse programmed rate to speed up PWM updating per step segment.
|
||||
prep.inv_rate = 1.0 / pl_block->programmed_rate;
|
||||
st_prep_block->is_pwm_rate_adjusted = true;
|
||||
}
|
||||
}
|
||||
#endif
|
||||
|
||||
st_prep_block->is_pwm_rate_adjusted = my_spindle.isRateAdjusted();
|
||||
|
||||
}
|
||||
/* ---------------------------------------------------------------------------------
|
||||
Compute the velocity profile of a new planner block based on its entry and exit
|
||||
@@ -1083,9 +1071,9 @@ void st_prep_buffer() {
|
||||
prep.maximum_speed = prep.exit_speed;
|
||||
}
|
||||
}
|
||||
#ifdef VARIABLE_SPINDLE
|
||||
bit_true(sys.step_control, STEP_CONTROL_UPDATE_SPINDLE_PWM); // Force update whenever updating block.
|
||||
#endif
|
||||
|
||||
bit_true(sys.step_control, STEP_CONTROL_UPDATE_SPINDLE_RPM); // Force update whenever updating block.
|
||||
|
||||
}
|
||||
// Initialize new segment
|
||||
segment_t* prep_segment = &segment_buffer[segment_buffer_head];
|
||||
@@ -1189,11 +1177,11 @@ void st_prep_buffer() {
|
||||
}
|
||||
}
|
||||
} while (mm_remaining > prep.mm_complete); // **Complete** Exit loop. Profile complete.
|
||||
#ifdef VARIABLE_SPINDLE
|
||||
|
||||
/* -----------------------------------------------------------------------------------
|
||||
Compute spindle speed PWM output for step segment
|
||||
*/
|
||||
if (st_prep_block->is_pwm_rate_adjusted || (sys.step_control & STEP_CONTROL_UPDATE_SPINDLE_PWM)) {
|
||||
if (st_prep_block->is_pwm_rate_adjusted || (sys.step_control & STEP_CONTROL_UPDATE_SPINDLE_RPM)) {
|
||||
if (pl_block->condition & (PL_COND_FLAG_SPINDLE_CW | PL_COND_FLAG_SPINDLE_CCW)) {
|
||||
float rpm = pl_block->spindle_speed;
|
||||
// NOTE: Feed and rapid overrides are independent of PWM value and do not alter laser power/rate.
|
||||
@@ -1201,17 +1189,16 @@ void st_prep_buffer() {
|
||||
rpm *= (prep.current_speed * prep.inv_rate);
|
||||
// If current_speed is zero, then may need to be rpm_min*(100/MAX_SPINDLE_SPEED_OVERRIDE)
|
||||
// but this would be instantaneous only and during a motion. May not matter at all.
|
||||
prep.current_spindle_pwm = spindle_compute_pwm_value(rpm);
|
||||
prep.current_spindle_rpm = my_spindle.set_rpm(rpm);
|
||||
} else {
|
||||
sys.spindle_speed = 0.0;
|
||||
#if ( (defined VARIABLE_SPINDLE) && (defined SPINDLE_PWM_PIN) )
|
||||
prep.current_spindle_pwm = spindle_pwm_off_value ;
|
||||
#endif
|
||||
prep.current_spindle_rpm = 0.0;
|
||||
|
||||
}
|
||||
bit_false(sys.step_control, STEP_CONTROL_UPDATE_SPINDLE_PWM);
|
||||
bit_false(sys.step_control, STEP_CONTROL_UPDATE_SPINDLE_RPM);
|
||||
}
|
||||
prep_segment->spindle_pwm = prep.current_spindle_pwm; // Reload segment PWM value
|
||||
#endif
|
||||
prep_segment->spindle_rpm = prep.current_spindle_rpm; // Reload segment PWM value
|
||||
|
||||
/* -----------------------------------------------------------------------------------
|
||||
Compute segment step rate, steps to execute, and apply necessary rate corrections.
|
||||
NOTE: Steps are computed by direct scalar conversion of the millimeter distance
|
||||
|
@@ -125,7 +125,7 @@ extern system_t sys;
|
||||
#define STEP_CONTROL_END_MOTION bit(0)
|
||||
#define STEP_CONTROL_EXECUTE_HOLD bit(1)
|
||||
#define STEP_CONTROL_EXECUTE_SYS_MOTION bit(2)
|
||||
#define STEP_CONTROL_UPDATE_SPINDLE_PWM bit(3)
|
||||
#define STEP_CONTROL_UPDATE_SPINDLE_RPM bit(3)
|
||||
|
||||
// Define control pin index for Grbl internal use. Pin maps may change, but these values don't.
|
||||
//#ifdef ENABLE_SAFETY_DOOR_INPUT_PIN
|
||||
|
174
Grbl_Esp32/tools/SpindleClass.cpp
Normal file
174
Grbl_Esp32/tools/SpindleClass.cpp
Normal file
@@ -0,0 +1,174 @@
|
||||
#include "grbl.h"
|
||||
#include "SpindleClass.h"
|
||||
|
||||
bool Spindle::isRateAdjusted() {
|
||||
return false; // default for basic spindles is false
|
||||
}
|
||||
|
||||
void PWMSpindle::init() {
|
||||
_pwm_period = ((1 << SPINDLE_PWM_BIT_PRECISION) - 1);
|
||||
if (settings.spindle_pwm_min_value > settings.spindle_pwm_min_value)
|
||||
grbl_msg_sendf(CLIENT_SERIAL, MSG_LEVEL_INFO, "Warning spindle min pwm is greater than max. Check $35 and $36");
|
||||
// pre-caculate some PWM count values
|
||||
_pwm_off_value = (_pwm_period * settings.spindle_pwm_off_value / 100.0);
|
||||
_pwm_min_value = (_pwm_period * settings.spindle_pwm_min_value / 100.0);
|
||||
_pwm_max_value = (_pwm_period * settings.spindle_pwm_max_value / 100.0);
|
||||
// The pwm_gradient is the pwm duty cycle units per rpm
|
||||
_pwm_gradient = (_pwm_max_value - _pwm_min_value) / (settings.rpm_max - settings.rpm_min);
|
||||
|
||||
|
||||
_spindle_pwm_chan_num = sys_get_next_PWM_chan_num();
|
||||
ledcSetup(_spindle_pwm_chan_num, (double)settings.spindle_pwm_freq, SPINDLE_PWM_BIT_PRECISION); // setup the channel
|
||||
ledcAttachPin(SPINDLE_PWM_PIN, _spindle_pwm_chan_num); // attach the PWM to the pin
|
||||
|
||||
#ifdef SPINDLE_ENABLE_PIN
|
||||
pinMode(SPINDLE_ENABLE_PIN, OUTPUT);
|
||||
#endif
|
||||
#ifdef SPINDLE_DIR_PIN
|
||||
pinMode(SPINDLE_DIR_PIN, OUTPUT);
|
||||
#endif
|
||||
}
|
||||
|
||||
float PWMSpindle::set_rpm(float rpm) {
|
||||
uint32_t pwm_value;
|
||||
|
||||
// apply overrides and limits
|
||||
rpm *= (0.010 * sys.spindle_speed_ovr); // Scale by spindle speed override value (percent)
|
||||
|
||||
// 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 = _pwm_max_value;
|
||||
} else if (rpm <= settings.rpm_min) {
|
||||
if (rpm == 0.0) { // S0 disables spindle
|
||||
sys.spindle_speed = 0.0;
|
||||
pwm_value = _pwm_off_value;
|
||||
} else { // Set minimum PWM output
|
||||
sys.spindle_speed = settings.rpm_min;
|
||||
pwm_value = _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;
|
||||
#ifdef ENABLE_PIECEWISE_LINEAR_SPINDLE
|
||||
pwm_value = piecewise_linear_fit(rpm);
|
||||
#else
|
||||
pwm_value = floor((rpm - settings.rpm_min) * _pwm_gradient) + _pwm_min_value;
|
||||
#endif
|
||||
}
|
||||
|
||||
set_pwm(pwm_value);
|
||||
return rpm;
|
||||
}
|
||||
|
||||
void PWMSpindle::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 {
|
||||
set_spindle_dir_pin(state == SPINDLE_ENABLE_CW);
|
||||
set_rpm(rpm);
|
||||
}
|
||||
sys.report_ovr_counter = 0; // Set to report change immediately
|
||||
}
|
||||
|
||||
uint8_t PWMSpindle::get_state() {
|
||||
|
||||
|
||||
if (_current_pwm_duty == 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
|
||||
}
|
||||
}
|
||||
|
||||
void PWMSpindle::stop() {
|
||||
// inverts are delt with in methods
|
||||
set_enable_pin(false);
|
||||
set_pwm(0);
|
||||
}
|
||||
|
||||
// prints the startup message of the spindle config
|
||||
void PWMSpindle :: config_message() {
|
||||
grbl_msg_sendf(CLIENT_SERIAL, MSG_LEVEL_INFO, "PWM spindle on GPIO %d, freq %.2fHz, Res %d bits", SPINDLE_PWM_PIN, settings.spindle_pwm_freq, SPINDLE_PWM_BIT_PRECISION);
|
||||
}
|
||||
|
||||
|
||||
void PWMSpindle::set_pwm(uint32_t duty) {
|
||||
// to prevent excessive calls to ledcWrite, make sure duty hass changed
|
||||
if (duty == _current_pwm_duty)
|
||||
return;
|
||||
|
||||
_current_pwm_duty = duty;
|
||||
|
||||
#ifdef INVERT_SPINDLE_PWM
|
||||
duty = (1 << SPINDLE_PWM_BIT_PRECISION) - duty;
|
||||
#endif
|
||||
|
||||
ledcWrite(_spindle_pwm_chan_num, duty);
|
||||
}
|
||||
|
||||
void PWMSpindle::set_enable_pin(bool enable) {
|
||||
#ifdef SPINDLE_ENABLE_PIN
|
||||
#ifndef INVERT_SPINDLE_ENABLE_PIN
|
||||
digitalWrite(SPINDLE_ENABLE_PIN, enable);
|
||||
#else
|
||||
digitalWrite(SPINDLE_ENABLE_PIN, !enable);
|
||||
#endif
|
||||
#endif
|
||||
}
|
||||
|
||||
void PWMSpindle::set_spindle_dir_pin(bool Clockwise) {
|
||||
#ifdef SPINDLE_DIR_PIN
|
||||
digitalWrite(SPINDLE_DIR_PIN, state == SPINDLE_ENABLE_CW);
|
||||
#endif
|
||||
}
|
||||
|
||||
// ========================= RelaySpindle ==================================
|
||||
/*
|
||||
This is the same as a PWM spindle, but is a digital rather than PWM output
|
||||
*/
|
||||
|
||||
void RelaySpindle::init() {
|
||||
pinMode(SPINDLE_PWM_PIN, OUTPUT);
|
||||
#ifdef SPINDLE_ENABLE_PIN
|
||||
pinMode(SPINDLE_ENABLE_PIN, OUTPUT);
|
||||
#endif
|
||||
#ifdef SPINDLE_DIR_PIN
|
||||
pinMode(SPINDLE_DIR_PIN, OUTPUT);
|
||||
#endif
|
||||
}
|
||||
|
||||
// prints the startup message of the spindle config
|
||||
void RelaySpindle :: config_message() {
|
||||
grbl_msg_sendf(CLIENT_SERIAL, MSG_LEVEL_INFO, "Relay spindle on GPIO %d", SPINDLE_PWM_PIN);
|
||||
}
|
||||
|
||||
void RelaySpindle::set_pwm(uint32_t duty) {
|
||||
#ifdef INVERT_SPINDLE_PWM
|
||||
duty = (duty == 0); // flip duty
|
||||
#endif
|
||||
digitalWrite(SPINDLE_PWM_PIN, duty > 0); // anything greater
|
||||
}
|
||||
|
||||
|
||||
// ====================== Laser =============================
|
||||
|
||||
|
||||
bool Laser :: isRateAdjusted() {
|
||||
// must be in $32=1 (laser mode) and M4 (CCW rotation)
|
||||
return ( settings.flags & BITFLAG_LASER_MODE );
|
||||
}
|
61
Grbl_Esp32/tools/SpindleClass.h
Normal file
61
Grbl_Esp32/tools/SpindleClass.h
Normal file
@@ -0,0 +1,61 @@
|
||||
#include "grbl.h"
|
||||
|
||||
#ifndef SPINDLE_CLASS_H
|
||||
#define SPINDLE_CLASS_H
|
||||
|
||||
class Spindle {
|
||||
public:
|
||||
virtual void init();
|
||||
virtual float set_rpm(float rpm);
|
||||
virtual void set_pwm(uint32_t duty);
|
||||
virtual void set_state(uint8_t state, float rpm);
|
||||
virtual uint8_t get_state();
|
||||
virtual void stop();
|
||||
virtual void config_message();
|
||||
virtual bool isRateAdjusted();
|
||||
|
||||
//bool _isRateAdjused = false;
|
||||
|
||||
};
|
||||
|
||||
class PWMSpindle : public Spindle {
|
||||
public:
|
||||
void init();
|
||||
float set_rpm(float rpm);
|
||||
void set_state(uint8_t state, float rpm);
|
||||
uint8_t get_state();
|
||||
void stop();
|
||||
void config_message();
|
||||
virtual void set_pwm(uint32_t duty);
|
||||
|
||||
private:
|
||||
int8_t _spindle_pwm_chan_num;
|
||||
int32_t _current_pwm_duty;
|
||||
|
||||
float _pwm_gradient; // Precalulated value to speed up rpm to PWM conversions.
|
||||
uint32_t _pwm_period; // how many counts in 1 period
|
||||
uint32_t _pwm_off_value;
|
||||
uint32_t _pwm_min_value;
|
||||
uint32_t _pwm_max_value;
|
||||
|
||||
|
||||
void set_enable_pin(bool enable_pin);
|
||||
void set_spindle_dir_pin(bool Clockwise);
|
||||
};
|
||||
|
||||
class RelaySpindle : public PWMSpindle {
|
||||
public:
|
||||
void init();
|
||||
void config_message();
|
||||
void set_pwm(uint32_t duty);
|
||||
private:
|
||||
|
||||
};
|
||||
|
||||
class Laser : public PWMSpindle {
|
||||
public:
|
||||
bool isRateAdjusted();
|
||||
};
|
||||
|
||||
|
||||
#endif
|
Reference in New Issue
Block a user