mirror of
https://github.com/bdring/Grbl_Esp32.git
synced 2025-09-02 19:02:35 +02:00
Updates after testing
- Spindle updates after changing $32 laser mode - Fixed mistake where RPM could twice in stepper interrupt - Added config_message to Laser - Still needs more testing, but no known errors now.
This commit is contained in:
@@ -451,7 +451,7 @@ Some features should not be changed. See notes below.
|
|||||||
// enable pin will output 5V for maximum RPM with 256 intermediate levels and 0V when disabled.
|
// enable pin will output 5V for maximum RPM with 256 intermediate levels and 0V when disabled.
|
||||||
// NOTE: IMPORTANT for Arduino Unos! When enabled, the Z-limit pin D11 and spindle enable pin D12 switch!
|
// NOTE: IMPORTANT for Arduino Unos! When enabled, the Z-limit pin D11 and spindle enable pin D12 switch!
|
||||||
// The hardware PWM output on pin D11 is required for variable spindle output voltages.
|
// The hardware PWM output on pin D11 is required for variable spindle output voltages.
|
||||||
#define VARIABLE_SPINDLE // Default enabled. Comment to disable.
|
#define VARIABLE_SPINDLE // Don't edit this for Grbl_ESP32
|
||||||
|
|
||||||
// Alters the behavior of the spindle enable pin. By default Grbl will not disable the enable pin if
|
// Alters the behavior of the spindle enable pin. By default Grbl will not disable the enable pin if
|
||||||
// spindle speed is zero and M3/4 is active, but still sets the PWM output to zero. This allows the users
|
// spindle speed is zero and M3/4 is active, but still sets the PWM output to zero. This allows the users
|
||||||
|
@@ -369,12 +369,11 @@ uint8_t settings_store_global_setting(uint8_t parameter, float value) {
|
|||||||
case 30: settings.rpm_max = std::max(value, 1.0f); spindle_init(); break; // Re-initialize spindle rpm calibration (min of 1)
|
case 30: settings.rpm_max = std::max(value, 1.0f); spindle_init(); break; // Re-initialize spindle rpm calibration (min of 1)
|
||||||
case 31: settings.rpm_min = value; spindle_init(); break; // Re-initialize spindle rpm calibration
|
case 31: settings.rpm_min = value; spindle_init(); break; // Re-initialize spindle rpm calibration
|
||||||
case 32:
|
case 32:
|
||||||
#ifdef VARIABLE_SPINDLE
|
if (int_value)
|
||||||
if (int_value) settings.flags |= BITFLAG_LASER_MODE;
|
settings.flags |= BITFLAG_LASER_MODE;
|
||||||
else settings.flags &= ~BITFLAG_LASER_MODE;
|
else
|
||||||
#else
|
settings.flags &= ~BITFLAG_LASER_MODE;
|
||||||
return (STATUS_SETTING_DISABLED_LASER);
|
spindle_init(); // update the spindle class
|
||||||
#endif
|
|
||||||
break;
|
break;
|
||||||
case 33: settings.spindle_pwm_freq = value; spindle_init(); break; // Re-initialize spindle pwm calibration
|
case 33: settings.spindle_pwm_freq = value; spindle_init(); break; // Re-initialize spindle pwm calibration
|
||||||
case 34: settings.spindle_pwm_off_value = value; spindle_init(); break; // Re-initialize spindle pwm calibration
|
case 34: settings.spindle_pwm_off_value = value; spindle_init(); break; // Re-initialize spindle pwm calibration
|
||||||
|
@@ -28,7 +28,7 @@
|
|||||||
int8_t spindle_pwm_chan_num;
|
int8_t spindle_pwm_chan_num;
|
||||||
|
|
||||||
// define a spindle type
|
// define a spindle type
|
||||||
DacSpindle my_spindle;
|
Laser my_spindle;
|
||||||
//NullSpindle my_spindle;
|
//NullSpindle my_spindle;
|
||||||
|
|
||||||
void spindle_init() {
|
void spindle_init() {
|
||||||
|
@@ -33,7 +33,7 @@
|
|||||||
#define SPINDLE_STATE_CCW bit(1)
|
#define SPINDLE_STATE_CCW bit(1)
|
||||||
|
|
||||||
//extern uint32_t spindle_pwm_off_value;
|
//extern uint32_t spindle_pwm_off_value;
|
||||||
extern DacSpindle my_spindle;
|
extern Laser my_spindle;
|
||||||
|
|
||||||
void spindle_init();
|
void spindle_init();
|
||||||
void spindle_stop();
|
void spindle_stop();
|
||||||
|
@@ -143,7 +143,7 @@ typedef struct {
|
|||||||
|
|
||||||
|
|
||||||
float inv_rate; // Used by PWM laser mode to speed up segment calculations.
|
float inv_rate; // Used by PWM laser mode to speed up segment calculations.
|
||||||
uint16_t current_spindle_pwm; // todo remove
|
//uint16_t current_spindle_pwm; // todo remove
|
||||||
float current_spindle_rpm;
|
float current_spindle_rpm;
|
||||||
|
|
||||||
} st_prep_t;
|
} st_prep_t;
|
||||||
@@ -283,7 +283,9 @@ void IRAM_ATTR onStepperDriverTimer(void* para) { // ISR It is time to take a st
|
|||||||
|
|
||||||
// Set real-time spindle output as segment is loaded, just prior to the first step.
|
// Set real-time spindle output as segment is loaded, just prior to the first step.
|
||||||
//spindle_set_speed(st.exec_segment->spindle_rpm);
|
//spindle_set_speed(st.exec_segment->spindle_rpm);
|
||||||
my_spindle.set_rpm(st.exec_segment->spindle_rpm);
|
//grbl_send(CLIENT_SERIAL, "A_");
|
||||||
|
my_spindle.set_rpm(prep.current_spindle_rpm);
|
||||||
|
|
||||||
|
|
||||||
} else {
|
} else {
|
||||||
// Segment buffer empty. Shutdown.
|
// Segment buffer empty. Shutdown.
|
||||||
@@ -293,6 +295,7 @@ void IRAM_ATTR onStepperDriverTimer(void* para) { // ISR It is time to take a st
|
|||||||
// Ensure pwm is set properly upon completion of rate-controlled motion.
|
// Ensure pwm is set properly upon completion of rate-controlled motion.
|
||||||
if (st.exec_block->is_pwm_rate_adjusted) {
|
if (st.exec_block->is_pwm_rate_adjusted) {
|
||||||
//spindle_set_speed(spindle_pwm_off_value);
|
//spindle_set_speed(spindle_pwm_off_value);
|
||||||
|
//grbl_send(CLIENT_SERIAL, "B_");
|
||||||
my_spindle.set_rpm(0.0);
|
my_spindle.set_rpm(0.0);
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
@@ -987,7 +990,14 @@ void st_prep_buffer() {
|
|||||||
} else
|
} else
|
||||||
prep.current_speed = sqrt(pl_block->entry_speed_sqr);
|
prep.current_speed = sqrt(pl_block->entry_speed_sqr);
|
||||||
|
|
||||||
st_prep_block->is_pwm_rate_adjusted = my_spindle.isRateAdjusted();
|
//st_prep_block->is_pwm_rate_adjusted = my_spindle.isRateAdjusted();
|
||||||
|
if (my_spindle.isRateAdjusted() ){ // 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;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
}
|
}
|
||||||
/* ---------------------------------------------------------------------------------
|
/* ---------------------------------------------------------------------------------
|
||||||
@@ -1188,11 +1198,15 @@ void st_prep_buffer() {
|
|||||||
if (pl_block->condition & (PL_COND_FLAG_SPINDLE_CW | PL_COND_FLAG_SPINDLE_CCW)) {
|
if (pl_block->condition & (PL_COND_FLAG_SPINDLE_CW | PL_COND_FLAG_SPINDLE_CCW)) {
|
||||||
float rpm = pl_block->spindle_speed;
|
float rpm = pl_block->spindle_speed;
|
||||||
// NOTE: Feed and rapid overrides are independent of PWM value and do not alter laser power/rate.
|
// NOTE: Feed and rapid overrides are independent of PWM value and do not alter laser power/rate.
|
||||||
if (st_prep_block->is_pwm_rate_adjusted)
|
if (st_prep_block->is_pwm_rate_adjusted) {
|
||||||
rpm *= (prep.current_speed * prep.inv_rate);
|
rpm *= (prep.current_speed * prep.inv_rate);
|
||||||
|
//grbl_msg_sendf(CLIENT_SERIAL, MSG_LEVEL_INFO, "RPM %.2f", rpm);
|
||||||
|
//grbl_msg_sendf(CLIENT_SERIAL, MSG_LEVEL_INFO, "Rates CV %.2f IV %.2f RPM %.2f", prep.current_speed, prep.inv_rate, rpm);
|
||||||
|
}
|
||||||
// If current_speed is zero, then may need to be rpm_min*(100/MAX_SPINDLE_SPEED_OVERRIDE)
|
// 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.
|
// but this would be instantaneous only and during a motion. May not matter at all.
|
||||||
prep.current_spindle_rpm = my_spindle.set_rpm(rpm);
|
//prep.current_spindle_rpm = my_spindle.set_rpm(rpm);
|
||||||
|
prep.current_spindle_rpm = rpm;
|
||||||
} else {
|
} else {
|
||||||
sys.spindle_speed = 0.0;
|
sys.spindle_speed = 0.0;
|
||||||
prep.current_spindle_rpm = 0.0;
|
prep.current_spindle_rpm = 0.0;
|
||||||
|
@@ -2,11 +2,15 @@
|
|||||||
SpindleClass.cpp
|
SpindleClass.cpp
|
||||||
|
|
||||||
A Spindle Class
|
A Spindle Class
|
||||||
|
Spindle - A base class. Do not use
|
||||||
|
PWMSpindel - A spindle with a PWM output
|
||||||
|
RelaySpindle - An on/off only spindle
|
||||||
|
Laser - Output is PWM, but the M4 laser power mode can be used
|
||||||
|
DacSpindle - Uses the DAC to output a 0-3.3V output
|
||||||
|
|
||||||
Part of Grbl_ESP32
|
Part of Grbl_ESP32
|
||||||
|
|
||||||
2020 - Bart Dring This file was modified for use on the ESP32
|
2020 - Bart Dring
|
||||||
CPU. Do not use this with Grbl for atMega328P
|
|
||||||
|
|
||||||
Grbl is free software: you can redistribute it and/or modify
|
Grbl is free software: you can redistribute it and/or modify
|
||||||
it under the terms of the GNU General Public License as published by
|
it under the terms of the GNU General Public License as published by
|
||||||
@@ -19,17 +23,6 @@
|
|||||||
You should have received a copy of the GNU General Public License
|
You should have received a copy of the GNU General Public License
|
||||||
along with Grbl. If not, see <http://www.gnu.org/licenses/>.
|
along with Grbl. If not, see <http://www.gnu.org/licenses/>.
|
||||||
|
|
||||||
*/
|
|
||||||
|
|
||||||
/*
|
|
||||||
|
|
||||||
TODO
|
|
||||||
|
|
||||||
|
|
||||||
Testing
|
|
||||||
Should $G show actual speed (Regular Grbl does not)
|
|
||||||
Speed overrides only take place during motion
|
|
||||||
|
|
||||||
*/
|
*/
|
||||||
#include "grbl.h"
|
#include "grbl.h"
|
||||||
#include "SpindleClass.h"
|
#include "SpindleClass.h"
|
||||||
@@ -190,7 +183,7 @@ void PWMSpindle::set_pwm(uint32_t duty) {
|
|||||||
#ifdef INVERT_SPINDLE_PWM
|
#ifdef INVERT_SPINDLE_PWM
|
||||||
duty = (1 << SPINDLE_PWM_BIT_PRECISION) - duty;
|
duty = (1 << SPINDLE_PWM_BIT_PRECISION) - duty;
|
||||||
#endif
|
#endif
|
||||||
grbl_msg_sendf(CLIENT_SERIAL, MSG_LEVEL_INFO, "Set PWM %d of %d", duty, (1 << SPINDLE_PWM_BIT_PRECISION) - 1);
|
//grbl_msg_sendf(CLIENT_SERIAL, MSG_LEVEL_INFO, "Set PWM %d of %d", duty, (1 << SPINDLE_PWM_BIT_PRECISION) - 1);
|
||||||
ledcWrite(_spindle_pwm_chan_num, duty);
|
ledcWrite(_spindle_pwm_chan_num, duty);
|
||||||
}
|
}
|
||||||
|
|
||||||
@@ -239,7 +232,7 @@ void RelaySpindle::set_pwm(uint32_t duty) {
|
|||||||
}
|
}
|
||||||
|
|
||||||
|
|
||||||
// ====================== Laser =============================
|
// ===================================== Laser ==============================================
|
||||||
|
|
||||||
|
|
||||||
bool Laser :: isRateAdjusted() {
|
bool Laser :: isRateAdjusted() {
|
||||||
@@ -247,9 +240,20 @@ bool Laser :: isRateAdjusted() {
|
|||||||
return (settings.flags & BITFLAG_LASER_MODE);
|
return (settings.flags & BITFLAG_LASER_MODE);
|
||||||
}
|
}
|
||||||
|
|
||||||
// ======================= DacSpindle =======================
|
void Laser :: config_message() {
|
||||||
|
grbl_msg_sendf(CLIENT_SERIAL,
|
||||||
|
MSG_LEVEL_INFO,
|
||||||
|
"Laser spindle on GPIO:%d, Freq:%.2fHz, Res:%dbits Laser mode:$32=%d",
|
||||||
|
SPINDLE_PWM_PIN,
|
||||||
|
_pwm_freq,
|
||||||
|
SPINDLE_PWM_BIT_PRECISION,
|
||||||
|
isRateAdjusted()); // the current mode
|
||||||
|
}
|
||||||
|
|
||||||
|
// ======================================== DacSpindle ======================================
|
||||||
void DacSpindle :: init() {
|
void DacSpindle :: init() {
|
||||||
_pwm_period = ((1 << SPINDLE_PWM_BIT_PRECISION) - 1);
|
_pwm_period = ((1 << SPINDLE_PWM_BIT_PRECISION) - 1);
|
||||||
|
_dac_channel_num = (dac_channel_t)0;
|
||||||
_gpio_ok = true;
|
_gpio_ok = true;
|
||||||
switch (SPINDLE_PWM_PIN) {
|
switch (SPINDLE_PWM_PIN) {
|
||||||
case GPIO_NUM_25:
|
case GPIO_NUM_25:
|
||||||
|
@@ -67,7 +67,7 @@ class PWMSpindle : public Spindle {
|
|||||||
|
|
||||||
private:
|
private:
|
||||||
int8_t _spindle_pwm_chan_num;
|
int8_t _spindle_pwm_chan_num;
|
||||||
float _pwm_freq;
|
|
||||||
|
|
||||||
int32_t _current_pwm_duty;
|
int32_t _current_pwm_duty;
|
||||||
|
|
||||||
@@ -83,6 +83,7 @@ class PWMSpindle : public Spindle {
|
|||||||
void set_spindle_dir_pin(bool Clockwise);
|
void set_spindle_dir_pin(bool Clockwise);
|
||||||
|
|
||||||
protected:
|
protected:
|
||||||
|
float _pwm_freq;
|
||||||
uint32_t _pwm_period; // how many counts in 1 period
|
uint32_t _pwm_period; // how many counts in 1 period
|
||||||
};
|
};
|
||||||
|
|
||||||
@@ -100,6 +101,7 @@ class RelaySpindle : public PWMSpindle {
|
|||||||
class Laser : public PWMSpindle {
|
class Laser : public PWMSpindle {
|
||||||
public:
|
public:
|
||||||
bool isRateAdjusted();
|
bool isRateAdjusted();
|
||||||
|
void config_message();
|
||||||
};
|
};
|
||||||
|
|
||||||
// This uses one of the (2) DAC pins on ESP32 to output a voltage
|
// This uses one of the (2) DAC pins on ESP32 to output a voltage
|
||||||
|
Reference in New Issue
Block a user