mirror of
https://github.com/bdring/Grbl_Esp32.git
synced 2025-08-30 09:39:49 +02:00
Merge pull request #388 from MitchBradley/Devt
Fix #386 - Arduino compiling problem
This commit is contained in:
@@ -21,7 +21,7 @@
|
|||||||
#include "grbl.h"
|
#include "grbl.h"
|
||||||
#include "WiFi.h"
|
#include "WiFi.h"
|
||||||
|
|
||||||
#include "tools/SpindleClass.cpp"
|
#include "Spindles/SpindleClass.cpp"
|
||||||
|
|
||||||
// Declare system global variable structure
|
// Declare system global variable structure
|
||||||
system_t sys;
|
system_t sys;
|
||||||
|
@@ -1,7 +1,7 @@
|
|||||||
/*
|
/*
|
||||||
BESCSpindle.cpp
|
BESCSpindle.cpp
|
||||||
|
|
||||||
This a special type of PWM spindle for RC type Brushless DC Speed
|
This a special type of PWM spindle for RC type Brushless DC Speed
|
||||||
controllers.
|
controllers.
|
||||||
|
|
||||||
Part of Grbl_ESP32
|
Part of Grbl_ESP32
|
||||||
@@ -38,11 +38,8 @@
|
|||||||
|
|
||||||
*/
|
*/
|
||||||
|
|
||||||
#include "grbl.h"
|
|
||||||
#include "SpindleClass.h"
|
|
||||||
|
|
||||||
// don't change these
|
// don't change these
|
||||||
#define BESC_PWM_FREQ 50.0f // Hz
|
#define BESC_PWM_FREQ 50.0f // Hz
|
||||||
#define BESC_PWM_BIT_PRECISION 16 // bits
|
#define BESC_PWM_BIT_PRECISION 16 // bits
|
||||||
#define BESC_PULSE_PERIOD (1.0 / BESC_PWM_FREQ)
|
#define BESC_PULSE_PERIOD (1.0 / BESC_PWM_FREQ)
|
||||||
// ok to tweak
|
// ok to tweak
|
||||||
@@ -94,17 +91,17 @@ float BESCSpindle::set_rpm(float rpm) {
|
|||||||
return rpm;
|
return rpm;
|
||||||
|
|
||||||
// apply speed overrides
|
// apply speed overrides
|
||||||
rpm *= (0.010 * sys.spindle_speed_ovr); // Scale by spindle speed override value (percent)
|
rpm *= (0.010 * sys.spindle_speed_ovr); // Scale by spindle speed override value (percent)
|
||||||
|
|
||||||
// apply limits limits
|
// apply limits limits
|
||||||
if ((_min_rpm >= _max_rpm) || (rpm >= _max_rpm)) {
|
if ((_min_rpm >= _max_rpm) || (rpm >= _max_rpm)) {
|
||||||
rpm = _max_rpm;
|
rpm = _max_rpm;
|
||||||
} else if (rpm != 0.0 && rpm <= _min_rpm) {
|
} else if (rpm != 0.0 && rpm <= _min_rpm) {
|
||||||
rpm = _min_rpm;
|
rpm = _min_rpm;
|
||||||
}
|
}
|
||||||
|
|
||||||
sys.spindle_speed = rpm;
|
sys.spindle_speed = rpm;
|
||||||
|
|
||||||
// determine the pwm value
|
// determine the pwm value
|
||||||
if (rpm == 0.0) {
|
if (rpm == 0.0) {
|
||||||
pwm_value = _pwm_off_value;
|
pwm_value = _pwm_off_value;
|
||||||
@@ -118,4 +115,4 @@ float BESCSpindle::set_rpm(float rpm) {
|
|||||||
|
|
||||||
set_output(pwm_value);
|
set_output(pwm_value);
|
||||||
return rpm;
|
return rpm;
|
||||||
}
|
}
|
@@ -3,7 +3,7 @@
|
|||||||
|
|
||||||
This uses the Analog DAC in the ESP32 to generate a voltage
|
This uses the Analog DAC in the ESP32 to generate a voltage
|
||||||
proportional to the GCode S value desired. Some spindle uses
|
proportional to the GCode S value desired. Some spindle uses
|
||||||
a 0-5V or 0-10V value to control the spindle. You would use
|
a 0-5V or 0-10V value to control the spindle. You would use
|
||||||
an Op Amp type circuit to get from the 0.3.3V of the ESP32 to that voltage.
|
an Op Amp type circuit to get from the 0.3.3V of the ESP32 to that voltage.
|
||||||
|
|
||||||
Part of Grbl_ESP32
|
Part of Grbl_ESP32
|
||||||
@@ -19,29 +19,26 @@
|
|||||||
GNU General Public License for more details.
|
GNU General Public License for more details.
|
||||||
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/>.
|
||||||
|
|
||||||
*/
|
|
||||||
|
|
||||||
#include "grbl.h"
|
*/
|
||||||
#include "SpindleClass.h"
|
|
||||||
|
|
||||||
// ======================================== DacSpindle ======================================
|
// ======================================== DacSpindle ======================================
|
||||||
void DacSpindle :: init() {
|
void DacSpindle :: init() {
|
||||||
get_pins_and_settings();
|
get_pins_and_settings();
|
||||||
if (_output_pin == UNDEFINED_PIN)
|
if (_output_pin == UNDEFINED_PIN)
|
||||||
return;
|
return;
|
||||||
|
|
||||||
_min_rpm = settings.rpm_min;
|
_min_rpm = settings.rpm_min;
|
||||||
_max_rpm = settings.rpm_max;
|
_max_rpm = settings.rpm_max;
|
||||||
_pwm_min_value = 0; // not actually PWM...DAC counts
|
_pwm_min_value = 0; // not actually PWM...DAC counts
|
||||||
_pwm_max_value = 255; // not actually PWM...DAC counts
|
_pwm_max_value = 255; // not actually PWM...DAC counts
|
||||||
_gpio_ok = true;
|
_gpio_ok = true;
|
||||||
|
|
||||||
if (_output_pin != GPIO_NUM_25 && _output_pin != GPIO_NUM_26) { // DAC can only be used on these pins
|
if (_output_pin != GPIO_NUM_25 && _output_pin != GPIO_NUM_26) { // DAC can only be used on these pins
|
||||||
_gpio_ok = false;
|
_gpio_ok = false;
|
||||||
grbl_msg_sendf(CLIENT_SERIAL, MSG_LEVEL_INFO, "DAC spindle pin invalid GPIO_NUM_%d (pin 25 or 26 only)", _output_pin);
|
grbl_msg_sendf(CLIENT_SERIAL, MSG_LEVEL_INFO, "DAC spindle pin invalid GPIO_NUM_%d (pin 25 or 26 only)", _output_pin);
|
||||||
return;
|
return;
|
||||||
}
|
}
|
||||||
|
|
||||||
if (_enable_pin != UNDEFINED_PIN)
|
if (_enable_pin != UNDEFINED_PIN)
|
||||||
pinMode(_enable_pin, OUTPUT);
|
pinMode(_enable_pin, OUTPUT);
|
||||||
@@ -50,7 +47,7 @@ void DacSpindle :: init() {
|
|||||||
pinMode(_direction_pin, OUTPUT);
|
pinMode(_direction_pin, OUTPUT);
|
||||||
}
|
}
|
||||||
is_reversable = (_direction_pin != UNDEFINED_PIN);
|
is_reversable = (_direction_pin != UNDEFINED_PIN);
|
||||||
|
|
||||||
|
|
||||||
config_message();
|
config_message();
|
||||||
}
|
}
|
||||||
@@ -89,7 +86,7 @@ float DacSpindle::set_rpm(float rpm) {
|
|||||||
// Compute intermediate PWM value with linear spindle speed model.
|
// 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.
|
// NOTE: A nonlinear model could be installed here, if required, but keep it VERY light-weight.
|
||||||
sys.spindle_speed = rpm;
|
sys.spindle_speed = rpm;
|
||||||
|
|
||||||
pwm_value = (uint32_t)map_float(rpm, _min_rpm, _max_rpm, _pwm_min_value, _pwm_max_value);
|
pwm_value = (uint32_t)map_float(rpm, _min_rpm, _max_rpm, _pwm_min_value, _pwm_max_value);
|
||||||
}
|
}
|
||||||
|
|
||||||
@@ -106,5 +103,5 @@ void DacSpindle :: set_output(uint32_t duty) {
|
|||||||
if (_gpio_ok) {
|
if (_gpio_ok) {
|
||||||
dacWrite(_output_pin, (uint8_t)duty);
|
dacWrite(_output_pin, (uint8_t)duty);
|
||||||
}
|
}
|
||||||
|
|
||||||
}
|
}
|
@@ -44,8 +44,6 @@
|
|||||||
Add periodic pinging of VFD in run mode to see if it is still at correct RPM
|
Add periodic pinging of VFD in run mode to see if it is still at correct RPM
|
||||||
*/
|
*/
|
||||||
|
|
||||||
#include "grbl.h"
|
|
||||||
#include "SpindleClass.h"
|
|
||||||
#include "driver/uart.h"
|
#include "driver/uart.h"
|
||||||
|
|
||||||
#define HUANYANG_ADDR 0x01
|
#define HUANYANG_ADDR 0x01
|
||||||
@@ -62,7 +60,7 @@ void HuanyangSpindle :: init() {
|
|||||||
grbl_msg_sendf(CLIENT_SERIAL, MSG_LEVEL_INFO, "Huanyang spindle errors");
|
grbl_msg_sendf(CLIENT_SERIAL, MSG_LEVEL_INFO, "Huanyang spindle errors");
|
||||||
return;
|
return;
|
||||||
}
|
}
|
||||||
|
|
||||||
uart_driver_delete(HUANYANG_UART_PORT); // this allows us to init() more than once if settings have changed.
|
uart_driver_delete(HUANYANG_UART_PORT); // this allows us to init() more than once if settings have changed.
|
||||||
|
|
||||||
uart_config_t uart_config = {
|
uart_config_t uart_config = {
|
||||||
@@ -71,9 +69,9 @@ void HuanyangSpindle :: init() {
|
|||||||
.parity = UART_PARITY_DISABLE,
|
.parity = UART_PARITY_DISABLE,
|
||||||
.stop_bits = UART_STOP_BITS_1,
|
.stop_bits = UART_STOP_BITS_1,
|
||||||
.flow_ctrl = UART_HW_FLOWCTRL_DISABLE,
|
.flow_ctrl = UART_HW_FLOWCTRL_DISABLE,
|
||||||
.rx_flow_ctrl_thresh = 122,
|
.rx_flow_ctrl_thresh = 122,
|
||||||
};
|
};
|
||||||
|
|
||||||
uart_param_config(HUANYANG_UART_PORT, &uart_config);
|
uart_param_config(HUANYANG_UART_PORT, &uart_config);
|
||||||
|
|
||||||
uart_set_pin(HUANYANG_UART_PORT,
|
uart_set_pin(HUANYANG_UART_PORT,
|
||||||
@@ -153,7 +151,7 @@ void HuanyangSpindle :: set_state(uint8_t state, float rpm) {
|
|||||||
}
|
}
|
||||||
|
|
||||||
set_rpm(rpm);
|
set_rpm(rpm);
|
||||||
sys.report_ovr_counter = 0; // Set to report change immediately
|
sys.report_ovr_counter = 0; // Set to report change immediately
|
||||||
}
|
}
|
||||||
|
|
||||||
bool HuanyangSpindle :: set_mode(uint8_t mode) {
|
bool HuanyangSpindle :: set_mode(uint8_t mode) {
|
||||||
@@ -167,7 +165,7 @@ bool HuanyangSpindle :: set_mode(uint8_t mode) {
|
|||||||
msg[3] = 0x08;
|
msg[3] = 0x08;
|
||||||
|
|
||||||
add_ModRTU_CRC(msg, sizeof(msg));
|
add_ModRTU_CRC(msg, sizeof(msg));
|
||||||
|
|
||||||
//report_hex_msg(msg, "To VFD:", sizeof(msg)); // TODO for debugging comment out
|
//report_hex_msg(msg, "To VFD:", sizeof(msg)); // TODO for debugging comment out
|
||||||
|
|
||||||
uart_write_bytes(HUANYANG_UART_PORT, msg, sizeof(msg));
|
uart_write_bytes(HUANYANG_UART_PORT, msg, sizeof(msg));
|
||||||
@@ -185,7 +183,7 @@ bool HuanyangSpindle :: get_response(uint16_t length) {
|
|||||||
return false;
|
return false;
|
||||||
}
|
}
|
||||||
// check CRC?
|
// check CRC?
|
||||||
// Check address?
|
// Check address?
|
||||||
|
|
||||||
return true;
|
return true;
|
||||||
}
|
}
|
||||||
@@ -205,8 +203,8 @@ float HuanyangSpindle :: set_rpm(float rpm) {
|
|||||||
msg[3] = (data & 0xFF00) >> 8;
|
msg[3] = (data & 0xFF00) >> 8;
|
||||||
msg[4] = (data & 0xFF);
|
msg[4] = (data & 0xFF);
|
||||||
|
|
||||||
add_ModRTU_CRC(msg, sizeof(msg));
|
add_ModRTU_CRC(msg, sizeof(msg));
|
||||||
|
|
||||||
//report_hex_msg(msg, "To VFD:", sizeof(msg)); // TODO for debugging comment out
|
//report_hex_msg(msg, "To VFD:", sizeof(msg)); // TODO for debugging comment out
|
||||||
|
|
||||||
uart_write_bytes(HUANYANG_UART_PORT, msg, sizeof(msg));
|
uart_write_bytes(HUANYANG_UART_PORT, msg, sizeof(msg));
|
@@ -1,7 +1,7 @@
|
|||||||
/*
|
/*
|
||||||
Laser.cpp
|
Laser.cpp
|
||||||
|
|
||||||
This is similar the the PWM Spindle except that it allows the
|
This is similar the the PWM Spindle except that it allows the
|
||||||
M4 speed vs. power copensation.
|
M4 speed vs. power copensation.
|
||||||
|
|
||||||
Part of Grbl_ESP32
|
Part of Grbl_ESP32
|
||||||
@@ -17,11 +17,8 @@
|
|||||||
GNU General Public License for more details.
|
GNU General Public License for more details.
|
||||||
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/>.
|
||||||
|
|
||||||
*/
|
|
||||||
|
|
||||||
#include "grbl.h"
|
*/
|
||||||
#include "SpindleClass.h"
|
|
||||||
|
|
||||||
// ===================================== Laser ==============================================
|
// ===================================== Laser ==============================================
|
||||||
|
|
||||||
@@ -38,4 +35,4 @@ void Laser :: config_message() {
|
|||||||
_pwm_freq,
|
_pwm_freq,
|
||||||
_pwm_precision,
|
_pwm_precision,
|
||||||
isRateAdjusted()); // the current mode
|
isRateAdjusted()); // the current mode
|
||||||
}
|
}
|
@@ -17,10 +17,8 @@
|
|||||||
GNU General Public License for more details.
|
GNU General Public License for more details.
|
||||||
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/>.
|
||||||
|
|
||||||
*/
|
*/
|
||||||
#include "grbl.h"
|
|
||||||
#include "SpindleClass.h"
|
|
||||||
|
|
||||||
// ======================= NullSpindle ==============================
|
// ======================= NullSpindle ==============================
|
||||||
// NullSpindle is just bunch of do nothing (ignore) methods to be used when you don't want a spindle
|
// NullSpindle is just bunch of do nothing (ignore) methods to be used when you don't want a spindle
|
||||||
@@ -38,4 +36,4 @@ uint8_t NullSpindle :: get_state() {
|
|||||||
void NullSpindle :: stop() {}
|
void NullSpindle :: stop() {}
|
||||||
void NullSpindle :: config_message() {
|
void NullSpindle :: config_message() {
|
||||||
grbl_msg_sendf(CLIENT_SERIAL, MSG_LEVEL_INFO, "No spindle");
|
grbl_msg_sendf(CLIENT_SERIAL, MSG_LEVEL_INFO, "No spindle");
|
||||||
}
|
}
|
@@ -19,8 +19,6 @@
|
|||||||
along with Grbl. If not, see <http://www.gnu.org/licenses/>.
|
along with Grbl. If not, see <http://www.gnu.org/licenses/>.
|
||||||
|
|
||||||
*/
|
*/
|
||||||
#include "grbl.h"
|
|
||||||
#include "SpindleClass.h"
|
|
||||||
|
|
||||||
// ======================= PWMSpindle ==============================
|
// ======================= PWMSpindle ==============================
|
||||||
/*
|
/*
|
||||||
@@ -110,7 +108,7 @@ float PWMSpindle::set_rpm(float rpm) {
|
|||||||
// apply limits
|
// apply limits
|
||||||
if ((_min_rpm >= _max_rpm) || (rpm >= _max_rpm)) {
|
if ((_min_rpm >= _max_rpm) || (rpm >= _max_rpm)) {
|
||||||
rpm = _max_rpm;
|
rpm = _max_rpm;
|
||||||
} else if (rpm != 0.0 && rpm <= _min_rpm) {
|
} else if (rpm != 0.0 && rpm <= _min_rpm) {
|
||||||
rpm = _min_rpm;
|
rpm = _min_rpm;
|
||||||
}
|
}
|
||||||
|
|
||||||
@@ -124,13 +122,13 @@ float PWMSpindle::set_rpm(float rpm) {
|
|||||||
pwm_value = _pwm_off_value;
|
pwm_value = _pwm_off_value;
|
||||||
} else {
|
} else {
|
||||||
pwm_value = (uint16_t)map_float(rpm, _min_rpm, _max_rpm, _pwm_min_value, _pwm_max_value);
|
pwm_value = (uint16_t)map_float(rpm, _min_rpm, _max_rpm, _pwm_min_value, _pwm_max_value);
|
||||||
}
|
}
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#ifdef SPINDLE_ENABLE_OFF_WITH_ZERO_SPEED
|
#ifdef SPINDLE_ENABLE_OFF_WITH_ZERO_SPEED
|
||||||
set_enable_pin(rpm != 0);
|
set_enable_pin(rpm != 0);
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
set_output(pwm_value);
|
set_output(pwm_value);
|
||||||
|
|
||||||
return rpm;
|
return rpm;
|
||||||
@@ -179,7 +177,7 @@ void PWMSpindle :: config_message() {
|
|||||||
}
|
}
|
||||||
|
|
||||||
|
|
||||||
void PWMSpindle::set_output(uint32_t duty) {
|
void PWMSpindle::set_output(uint32_t duty) {
|
||||||
|
|
||||||
if (_output_pin == UNDEFINED_PIN)
|
if (_output_pin == UNDEFINED_PIN)
|
||||||
return;
|
return;
|
@@ -19,8 +19,6 @@
|
|||||||
along with Grbl. If not, see <http://www.gnu.org/licenses/>.
|
along with Grbl. If not, see <http://www.gnu.org/licenses/>.
|
||||||
|
|
||||||
*/
|
*/
|
||||||
#include "grbl.h"
|
|
||||||
#include "SpindleClass.h"
|
|
||||||
|
|
||||||
// ========================= RelaySpindle ==================================
|
// ========================= RelaySpindle ==================================
|
||||||
/*
|
/*
|
||||||
@@ -72,4 +70,4 @@ void RelaySpindle::set_output(uint32_t duty) {
|
|||||||
duty = (duty == 0); // flip duty
|
duty = (duty == 0); // flip duty
|
||||||
#endif
|
#endif
|
||||||
digitalWrite(_output_pin, duty > 0); // anything greater
|
digitalWrite(_output_pin, duty > 0); // anything greater
|
||||||
}
|
}
|
@@ -32,8 +32,6 @@
|
|||||||
SPINDLE_DIR_PIN
|
SPINDLE_DIR_PIN
|
||||||
|
|
||||||
*/
|
*/
|
||||||
#include "grbl.h"
|
|
||||||
#include "SpindleClass.h"
|
|
||||||
#include "NullSpindle.cpp"
|
#include "NullSpindle.cpp"
|
||||||
#include "PWMSpindle.cpp"
|
#include "PWMSpindle.cpp"
|
||||||
#include "DacSpindle.cpp"
|
#include "DacSpindle.cpp"
|
||||||
@@ -95,5 +93,3 @@ void Spindle :: spindle_sync(uint8_t state, float rpm) {
|
|||||||
protocol_buffer_synchronize(); // Empty planner buffer to ensure spindle is set when programmed.
|
protocol_buffer_synchronize(); // Empty planner buffer to ensure spindle is set when programmed.
|
||||||
set_state(state, rpm);
|
set_state(state, rpm);
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
@@ -38,7 +38,7 @@
|
|||||||
#ifndef SPINDLE_CLASS_H
|
#ifndef SPINDLE_CLASS_H
|
||||||
#define SPINDLE_CLASS_H
|
#define SPINDLE_CLASS_H
|
||||||
|
|
||||||
#include "grbl.h"
|
#include "../grbl.h"
|
||||||
#include <driver/dac.h>
|
#include <driver/dac.h>
|
||||||
#include "driver/uart.h"
|
#include "driver/uart.h"
|
||||||
|
|
||||||
@@ -82,7 +82,7 @@ class PWMSpindle : public Spindle {
|
|||||||
void config_message();
|
void config_message();
|
||||||
|
|
||||||
private:
|
private:
|
||||||
|
|
||||||
int32_t _current_pwm_duty;
|
int32_t _current_pwm_duty;
|
||||||
void set_spindle_dir_pin(bool Clockwise);
|
void set_spindle_dir_pin(bool Clockwise);
|
||||||
|
|
||||||
@@ -104,7 +104,7 @@ class PWMSpindle : public Spindle {
|
|||||||
virtual void set_output(uint32_t duty);
|
virtual void set_output(uint32_t duty);
|
||||||
void set_enable_pin(bool enable_pin);
|
void set_enable_pin(bool enable_pin);
|
||||||
void get_pins_and_settings();
|
void get_pins_and_settings();
|
||||||
uint8_t calc_pwm_precision(float freq);
|
uint8_t calc_pwm_precision(float freq);
|
||||||
};
|
};
|
||||||
|
|
||||||
// This is for an on/off spindle all RPMs above 0 are on
|
// This is for an on/off spindle all RPMs above 0 are on
|
@@ -18,10 +18,11 @@
|
|||||||
along with Grbl. If not, see <http://www.gnu.org/licenses/>.
|
along with Grbl. If not, see <http://www.gnu.org/licenses/>.
|
||||||
*/
|
*/
|
||||||
|
|
||||||
|
#pragma once
|
||||||
// Grbl versioning system
|
// Grbl versioning system
|
||||||
|
|
||||||
#define GRBL_VERSION "1.2a"
|
#define GRBL_VERSION "1.2a"
|
||||||
#define GRBL_VERSION_BUILD "20200423"
|
#define GRBL_VERSION_BUILD "20200428"
|
||||||
|
|
||||||
//#include <sdkconfig.h>
|
//#include <sdkconfig.h>
|
||||||
#include <Arduino.h>
|
#include <Arduino.h>
|
||||||
@@ -53,7 +54,7 @@
|
|||||||
#include "protocol.h"
|
#include "protocol.h"
|
||||||
#include "report.h"
|
#include "report.h"
|
||||||
#include "serial.h"
|
#include "serial.h"
|
||||||
#include "tools/SpindleClass.h"
|
#include "Spindles/SpindleClass.h"
|
||||||
#include "stepper.h"
|
#include "stepper.h"
|
||||||
#include "jog.h"
|
#include "jog.h"
|
||||||
#include "inputbuffer.h"
|
#include "inputbuffer.h"
|
||||||
|
@@ -1,5 +1,3 @@
|
|||||||
#include "grbl.h"
|
|
||||||
|
|
||||||
/*
|
/*
|
||||||
stepper.c - stepper motor driver: executes motion plans using stepper motors
|
stepper.c - stepper motor driver: executes motion plans using stepper motors
|
||||||
Part of Grbl
|
Part of Grbl
|
||||||
@@ -54,7 +52,7 @@ typedef struct {
|
|||||||
#else
|
#else
|
||||||
uint8_t prescaler; // Without AMASS, a prescaler is required to adjust for slow timing.
|
uint8_t prescaler; // Without AMASS, a prescaler is required to adjust for slow timing.
|
||||||
#endif
|
#endif
|
||||||
uint16_t spindle_rpm; // TODO get rid of this.
|
uint16_t spindle_rpm; // TODO get rid of this.
|
||||||
} segment_t;
|
} segment_t;
|
||||||
static segment_t segment_buffer[SEGMENT_BUFFER_SIZE];
|
static segment_t segment_buffer[SEGMENT_BUFFER_SIZE];
|
||||||
|
|
||||||
@@ -285,7 +283,7 @@ void IRAM_ATTR onStepperDriverTimer(void* para) { // ISR It is time to take a st
|
|||||||
//spindle_set_speed(st.exec_segment->spindle_rpm);
|
//spindle_set_speed(st.exec_segment->spindle_rpm);
|
||||||
//grbl_send(CLIENT_SERIAL, "A_");
|
//grbl_send(CLIENT_SERIAL, "A_");
|
||||||
spindle->set_rpm(prep.current_spindle_rpm);
|
spindle->set_rpm(prep.current_spindle_rpm);
|
||||||
|
|
||||||
|
|
||||||
} else {
|
} else {
|
||||||
// Segment buffer empty. Shutdown.
|
// Segment buffer empty. Shutdown.
|
||||||
@@ -1014,7 +1012,7 @@ void st_prep_buffer() {
|
|||||||
} else
|
} else
|
||||||
prep.current_speed = sqrt(pl_block->entry_speed_sqr);
|
prep.current_speed = sqrt(pl_block->entry_speed_sqr);
|
||||||
|
|
||||||
|
|
||||||
if (spindle->isRateAdjusted() ){ // settings.flags & BITFLAG_LASER_MODE) {
|
if (spindle->isRateAdjusted() ){ // settings.flags & BITFLAG_LASER_MODE) {
|
||||||
if (pl_block->condition & PL_COND_FLAG_SPINDLE_CCW) {
|
if (pl_block->condition & PL_COND_FLAG_SPINDLE_CCW) {
|
||||||
// Pre-compute inverse programmed rate to speed up PWM updating per step segment.
|
// Pre-compute inverse programmed rate to speed up PWM updating per step segment.
|
||||||
@@ -1222,14 +1220,14 @@ 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, "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);
|
//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 = rpm;
|
prep.current_spindle_rpm = rpm;
|
||||||
} else {
|
} else {
|
||||||
sys.spindle_speed = 0.0;
|
sys.spindle_speed = 0.0;
|
||||||
@@ -1408,4 +1406,4 @@ bool get_stepper_disable() { // returns true if steppers are disabled
|
|||||||
disabled = !disabled; // Apply pin invert.
|
disabled = !disabled; // Apply pin invert.
|
||||||
}
|
}
|
||||||
return disabled;
|
return disabled;
|
||||||
}
|
}
|
||||||
|
Reference in New Issue
Block a user