mirror of
https://github.com/bdring/Grbl_Esp32.git
synced 2025-09-03 03:13:25 +02:00
Merge pull request #400 from MitchBradley/bmaster
Restored Spindle files
This commit is contained in:
@@ -37,11 +37,25 @@
|
||||
#define Y_LIMIT_PIN GPIO_NUM_4
|
||||
#define Z_LIMIT_PIN GPIO_NUM_16
|
||||
|
||||
#ifdef HOMING_CYCLE_0
|
||||
#undef HOMING_CYCLE_0
|
||||
#endif
|
||||
#define HOMING_CYCLE_0 (1<<Z_AXIS) // Z first
|
||||
|
||||
#ifdef HOMING_CYCLE_1
|
||||
#undef HOMING_CYCLE_1
|
||||
#endif
|
||||
#define HOMING_CYCLE_1 ((1<<X_AXIS)|(1<<Y_AXIS))
|
||||
|
||||
#ifdef HOMING_CYCLE_2
|
||||
#undef HOMING_CYCLE_2
|
||||
#endif
|
||||
|
||||
// OK to comment out to use pin for other features
|
||||
#define STEPPERS_DISABLE_PIN GPIO_NUM_13
|
||||
|
||||
#define SPINDLE_TYPE SPINDLE_TYPE_PWM
|
||||
#define SPINDLE_PWM_PIN GPIO_NUM_2 // labeled SpinPWM
|
||||
#define SPINDLE_OUTPUT_PIN GPIO_NUM_2 // labeled SpinPWM
|
||||
#define SPINDLE_ENABLE_PIN GPIO_NUM_22 // labeled SpinEnbl
|
||||
|
||||
#define MIST_PIN GPIO_NUM_21 // labeled Mist
|
||||
@@ -52,3 +66,5 @@
|
||||
#define CONTROL_RESET_PIN GPIO_NUM_34 // labeled Reset, needs external pullup
|
||||
#define CONTROL_FEED_HOLD_PIN GPIO_NUM_36 // labeled Hold, needs external pullup
|
||||
#define CONTROL_CYCLE_START_PIN GPIO_NUM_39 // labeled Start, needs external pullup
|
||||
|
||||
|
||||
|
@@ -22,7 +22,7 @@
|
||||
along with Grbl_ESP32. If not, see <http://www.gnu.org/licenses/>.
|
||||
*/
|
||||
|
||||
#define MACHINE_NAME "External 4 Axis Driver Board"
|
||||
#define MACHINE_NAME "External 4 Axis Driver Board V2"
|
||||
|
||||
#ifdef N_AXIS
|
||||
#undef N_AXIS
|
||||
@@ -35,20 +35,22 @@
|
||||
#define Y_DIRECTION_PIN GPIO_NUM_15
|
||||
#define Z_STEP_PIN GPIO_NUM_27
|
||||
#define Z_DIRECTION_PIN GPIO_NUM_33
|
||||
#define A_STEP_PIN GPIO_NUM_14
|
||||
#define A_DIRECTION_PIN GPIO_NUM_12
|
||||
#define A_STEP_PIN GPIO_NUM_12
|
||||
#define A_DIRECTION_PIN GPIO_NUM_14
|
||||
#define STEPPERS_DISABLE_PIN GPIO_NUM_13
|
||||
|
||||
/*
|
||||
#define SPINDLE_TYPE SPINDLE_TYPE_PWM
|
||||
#define SPINDLE_PWM_PIN GPIO_NUM_25
|
||||
#define SPINDLE_ENABLE_PIN GPIO_NUM_22
|
||||
#define SPINDLE_TYPE SPINDLE_TYPE_PWM // only one spindle at a time
|
||||
*/
|
||||
|
||||
#define SPINDLE_TYPE SPINDLE_TYPE_HUANYANG
|
||||
#define MODBUS_TX GPIO_NUM_17
|
||||
#define MODBUS_RX GPIO_NUM_4
|
||||
#define MODBUS_CTRL GPIO_NUM_16
|
||||
#define SPINDLE_OUTPUT_PIN GPIO_NUM_25
|
||||
#define SPINDLE_ENABLE_PIN GPIO_NUM_22
|
||||
|
||||
|
||||
#define SPINDLE_TYPE SPINDLE_TYPE_HUANYANG // only one spindle at a time
|
||||
#define HUANYANG_TXD_PIN GPIO_NUM_17
|
||||
#define HUANYANG_RXD_PIN GPIO_NUM_4
|
||||
#define HUANYANG_RTS_PIN GPIO_NUM_16
|
||||
|
||||
#define X_LIMIT_PIN GPIO_NUM_34
|
||||
#define Y_LIMIT_PIN GPIO_NUM_35
|
||||
|
122
Grbl_Esp32/Spindles/BESCSpindle.cpp
Normal file
122
Grbl_Esp32/Spindles/BESCSpindle.cpp
Normal file
@@ -0,0 +1,122 @@
|
||||
/*
|
||||
BESCSpindle.cpp
|
||||
|
||||
This a special type of PWM spindle for RC type Brushless DC Speed
|
||||
controllers. They use a short pulse for off and a longer pulse for
|
||||
full on. The pulse is always a small portion of the full cycle.
|
||||
Some BESCs have a special turn on procedure. This may be a one time
|
||||
procedure or must be done every time. The user must do that via gcode.
|
||||
|
||||
Part of Grbl_ESP32
|
||||
2020 - Bart Dring
|
||||
|
||||
Grbl is free software: you can redistribute it and/or modify
|
||||
it under the terms of the GNU General Public License as published by
|
||||
the Free Software Foundation, either version 3 of the License, or
|
||||
(at your option) any later version.
|
||||
Grbl is distributed in the hope that it will be useful,
|
||||
but WITHOUT ANY WARRANTY; without even the implied warranty of
|
||||
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
|
||||
GNU General Public License for more details.
|
||||
You should have received a copy of the GNU General Public License
|
||||
along with Grbl. If not, see <http://www.gnu.org/licenses/>.
|
||||
|
||||
Important ESC Settings
|
||||
50 Hz this is a typical frequency for an ESC
|
||||
Some ESCs can handle higher frequencies, but there is no advantage to changing it.
|
||||
|
||||
Determine the typical min and max pulse length of your ESC
|
||||
BESC_MIN_PULSE_SECS is typically 1ms (0.001 sec) or less
|
||||
BESC_MAX_PULSE_SECS is typically 2ms (0.002 sec) or more
|
||||
|
||||
*/
|
||||
#include "SpindleClass.h"
|
||||
|
||||
#include "SpindleClass.h"
|
||||
|
||||
// don't change these
|
||||
#define BESC_PWM_FREQ 50.0f // Hz
|
||||
#define BESC_PWM_BIT_PRECISION 16 // bits
|
||||
#define BESC_PULSE_PERIOD (1.0 / BESC_PWM_FREQ)
|
||||
|
||||
// Ok to tweak. These are the pulse lengths in seconds
|
||||
// #define them in your machine definition file if you want different values
|
||||
#ifndef BESC_MIN_PULSE_SECS
|
||||
#define BESC_MIN_PULSE_SECS 0.0009f // in seconds
|
||||
#endif
|
||||
|
||||
#ifndef BESC_MAX_PULSE_SECS
|
||||
#define BESC_MAX_PULSE_SECS 0.0022f // in seconds
|
||||
#endif
|
||||
|
||||
//calculations...don't change
|
||||
#define BESC_MIN_PULSE_CNT (uint16_t)(BESC_MIN_PULSE_SECS / BESC_PULSE_PERIOD * 65535.0)
|
||||
#define BESC_MAX_PULSE_CNT (uint16_t)(BESC_MAX_PULSE_SECS / BESC_PULSE_PERIOD * 65535.0)
|
||||
|
||||
void BESCSpindle :: init() {
|
||||
|
||||
get_pins_and_settings(); // these gets the standard PWM settings, but many need to be changed for BESC
|
||||
|
||||
if (_output_pin == UNDEFINED_PIN) {
|
||||
grbl_msg_sendf(CLIENT_SERIAL, MSG_LEVEL_INFO, "Warning: BESC output pin not defined");
|
||||
return; // We cannot continue without the output pin
|
||||
}
|
||||
|
||||
// override some settings to what is required for a BESC
|
||||
_pwm_freq = (uint32_t)BESC_PWM_FREQ;
|
||||
_pwm_precision = 16;
|
||||
|
||||
// override these settings
|
||||
_pwm_off_value = BESC_MIN_PULSE_CNT;
|
||||
_pwm_min_value = _pwm_off_value;
|
||||
_pwm_max_value = BESC_MAX_PULSE_CNT;
|
||||
|
||||
ledcSetup(_spindle_pwm_chan_num, (double)_pwm_freq, _pwm_precision); // setup the channel
|
||||
ledcAttachPin(_output_pin, _spindle_pwm_chan_num); // attach the PWM to the pin
|
||||
|
||||
if (_enable_pin != UNDEFINED_PIN)
|
||||
pinMode(_enable_pin, OUTPUT);
|
||||
|
||||
set_rpm(0);
|
||||
|
||||
config_message();
|
||||
}
|
||||
|
||||
// prints the startup message of the spindle config
|
||||
void BESCSpindle :: config_message() {
|
||||
grbl_msg_sendf(CLIENT_SERIAL,
|
||||
MSG_LEVEL_INFO,
|
||||
"BESC spindle on Pin:%d Min:%0.2fms Max:%0.2fms Freq:%dHz Res:%dbits",
|
||||
report_pin_number(_output_pin),
|
||||
BESC_MIN_PULSE_SECS * 1000.0, // convert to milliseconds
|
||||
BESC_MAX_PULSE_SECS * 1000.0, // convert to milliseconds
|
||||
report_pin_number(_pwm_freq),
|
||||
report_pin_number(_pwm_precision));
|
||||
}
|
||||
|
||||
uint32_t BESCSpindle::set_rpm(uint32_t rpm) {
|
||||
uint32_t pwm_value;
|
||||
|
||||
if (_output_pin == UNDEFINED_PIN)
|
||||
return rpm;
|
||||
|
||||
// apply speed overrides
|
||||
rpm = rpm * sys.spindle_speed_ovr / 100; // Scale by spindle speed override value (percent)
|
||||
|
||||
// apply limits limits
|
||||
if ((_min_rpm >= _max_rpm) || (rpm >= _max_rpm))
|
||||
rpm = _max_rpm;
|
||||
else if (rpm != 0 && rpm <= _min_rpm)
|
||||
rpm = _min_rpm;
|
||||
sys.spindle_speed = rpm;
|
||||
|
||||
// determine the pwm value
|
||||
if (rpm == 0) {
|
||||
pwm_value = _pwm_off_value;
|
||||
} else {
|
||||
pwm_value = map_uint32_t(rpm, _min_rpm, _max_rpm, _pwm_min_value, _pwm_max_value);
|
||||
}
|
||||
|
||||
set_output(pwm_value);
|
||||
return rpm;
|
||||
}
|
111
Grbl_Esp32/Spindles/DacSpindle.cpp
Normal file
111
Grbl_Esp32/Spindles/DacSpindle.cpp
Normal file
@@ -0,0 +1,111 @@
|
||||
/*
|
||||
DacSpindle.cpp
|
||||
|
||||
This uses the Analog DAC in the ESP32 to generate a voltage
|
||||
proportional to the GCode S value desired. Some spindle uses
|
||||
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.
|
||||
|
||||
Part of Grbl_ESP32
|
||||
2020 - Bart Dring
|
||||
|
||||
Grbl is free software: you can redistribute it and/or modify
|
||||
it under the terms of the GNU General Public License as published by
|
||||
the Free Software Foundation, either version 3 of the License, or
|
||||
(at your option) any later version.
|
||||
Grbl is distributed in the hope that it will be useful,
|
||||
but WITHOUT ANY WARRANTY; without even the implied warranty of
|
||||
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
|
||||
GNU General Public License for more details.
|
||||
You should have received a copy of the GNU General Public License
|
||||
along with Grbl. If not, see <http://www.gnu.org/licenses/>.
|
||||
|
||||
*/
|
||||
#include "SpindleClass.h"
|
||||
|
||||
// ======================================== DacSpindle ======================================
|
||||
void DacSpindle :: init() {
|
||||
get_pins_and_settings();
|
||||
|
||||
if (_output_pin == UNDEFINED_PIN)
|
||||
return;
|
||||
|
||||
_min_rpm = settings.rpm_min;
|
||||
_max_rpm = settings.rpm_max;
|
||||
_pwm_min_value = 0; // not actually PWM...DAC counts
|
||||
_pwm_max_value = 255; // not actually PWM...DAC counts
|
||||
_gpio_ok = true;
|
||||
|
||||
if (_output_pin != GPIO_NUM_25 && _output_pin != GPIO_NUM_26) { // DAC can only be used on these pins
|
||||
_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);
|
||||
return;
|
||||
}
|
||||
|
||||
if (_enable_pin != UNDEFINED_PIN)
|
||||
pinMode(_enable_pin, OUTPUT);
|
||||
|
||||
if (_direction_pin != UNDEFINED_PIN) {
|
||||
pinMode(_direction_pin, OUTPUT);
|
||||
}
|
||||
|
||||
is_reversable = (_direction_pin != UNDEFINED_PIN);
|
||||
|
||||
config_message();
|
||||
}
|
||||
|
||||
void DacSpindle :: config_message() {
|
||||
grbl_msg_sendf(CLIENT_SERIAL,
|
||||
MSG_LEVEL_INFO,
|
||||
"DAC spindle Output:%d, Enbl:%d, Dir:%d, Res:8bits",
|
||||
report_pin_number(_output_pin),
|
||||
report_pin_number(_enable_pin), // 255 means pin not defined
|
||||
report_pin_number(_direction_pin)); // 255 means pin not defined
|
||||
}
|
||||
|
||||
uint32_t DacSpindle::set_rpm(uint32_t rpm) {
|
||||
if (_output_pin == UNDEFINED_PIN)
|
||||
return rpm;
|
||||
|
||||
uint32_t pwm_value;
|
||||
|
||||
// apply overrides and limits
|
||||
rpm = rpm * sys.spindle_speed_ovr / 100; // Scale by spindle speed override value (percent)
|
||||
|
||||
// Calculate PWM register value based on rpm max/min settings and programmed rpm.
|
||||
if ((_min_rpm >= _max_rpm) || (rpm >= _max_rpm)) {
|
||||
// No PWM range possible. Set simple on/off spindle control pin state.
|
||||
sys.spindle_speed = _max_rpm;
|
||||
pwm_value = _pwm_max_value;
|
||||
} else if (rpm <= _min_rpm) {
|
||||
if (rpm == 0) { // S0 disables spindle
|
||||
sys.spindle_speed = 0;
|
||||
pwm_value = 0;
|
||||
} else { // Set minimum PWM output
|
||||
rpm = _min_rpm;
|
||||
sys.spindle_speed = rpm;
|
||||
pwm_value = 0;
|
||||
grbl_msg_sendf(CLIENT_SERIAL, MSG_LEVEL_INFO, "Spindle RPM less than min RPM:%5.2f %d", rpm, pwm_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 = map_uint32_t(rpm, _min_rpm, _max_rpm, _pwm_min_value, _pwm_max_value);
|
||||
}
|
||||
|
||||
if (_off_with_zero_speed) {
|
||||
set_enable_pin(rpm != 0);
|
||||
}
|
||||
|
||||
set_output(pwm_value);
|
||||
|
||||
return rpm;
|
||||
}
|
||||
|
||||
void DacSpindle :: set_output(uint32_t duty) {
|
||||
if (_gpio_ok) {
|
||||
dacWrite(_output_pin, (uint8_t)duty);
|
||||
}
|
||||
}
|
321
Grbl_Esp32/Spindles/HuanyangSpindle.cpp
Normal file
321
Grbl_Esp32/Spindles/HuanyangSpindle.cpp
Normal file
@@ -0,0 +1,321 @@
|
||||
/*
|
||||
HuanyangSpindle.cpp
|
||||
|
||||
This is for a Huanyang VFD based spindle via RS485 Modbus.
|
||||
|
||||
Part of Grbl_ESP32
|
||||
2020 - Bart Dring
|
||||
|
||||
Grbl is free software: you can redistribute it and/or modify
|
||||
it under the terms of the GNU General Public License as published by
|
||||
the Free Software Foundation, either version 3 of the License, or
|
||||
(at your option) any later version.
|
||||
Grbl is distributed in the hope that it will be useful,
|
||||
but WITHOUT ANY WARRANTY; without even the implied warranty of
|
||||
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
|
||||
GNU General Public License for more details.
|
||||
You should have received a copy of the GNU General Public License
|
||||
along with Grbl. If not, see <http://www.gnu.org/licenses/>.
|
||||
|
||||
WARNING!!!!
|
||||
VFDs are very dangerous. They have high voltages and are very powerful
|
||||
Remove power before changing bits.
|
||||
|
||||
VFD frequencies are in Hz. Multiply by 60 for RPM
|
||||
|
||||
before using spindle, VFD must be setup for RS485 and match your spindle
|
||||
PD001 2 RS485 Control of run commands
|
||||
PD002 2 RS485 Control of operating frequency
|
||||
PD005 400 Maximum frequency Hz (Typical for spindles)
|
||||
PD011 120 Min Speed (Recommend Aircooled=120 Water=100)
|
||||
PD014 10 Acceleration time (Test to optimize)
|
||||
PD015 10 Deceleration time (Test to optimize)
|
||||
PD023 1 Reverse run enabled
|
||||
PD142 3.7 Max current Amps (0.8kw=3.7 1.5kw=7.0, 2.2kw=??)
|
||||
PD163 1 RS485 Address: 1 (Typical. OK to change...see below)
|
||||
PD164 1 RS485 Baud rate: 9600 (Typical. OK to change...see below)
|
||||
PD165 3 RS485 Mode: RTU, 8N1
|
||||
|
||||
Some references....
|
||||
Manual: http://www.hy-electrical.com/bf/inverter.pdf
|
||||
Reference: https://github.com/Smoothieware/Smoothieware/blob/edge/src/modules/tools/spindle/HuanyangSpindleControl.cpp
|
||||
Refernece: https://gist.github.com/Bouni/803492ed0aab3f944066
|
||||
VFD settings: https://www.hobbytronics.co.za/Content/external/1159/Spindle_Settings.pdf
|
||||
|
||||
TODO
|
||||
Returning errors to Grbl and handling them in Grbl.
|
||||
What happens if the VFD does not respond
|
||||
Add periodic pinging of VFD in run mode to see if it is still at correct RPM
|
||||
*/
|
||||
#include "SpindleClass.h"
|
||||
|
||||
#include "driver/uart.h"
|
||||
|
||||
#define HUANYANG_UART_PORT UART_NUM_2 // hard coded for this port right now
|
||||
#define ECHO_TEST_CTS UART_PIN_NO_CHANGE // CTS pin is not used
|
||||
#define HUANYANG_BUF_SIZE 127
|
||||
#define RESPONSE_WAIT_TICKS 50 // how long to wait for a response
|
||||
#define HUANYANG_MAX_MSG_SIZE 10 // more than enough for a modbus message
|
||||
|
||||
// OK to change these
|
||||
// #define them in your machine definition file if you want different values
|
||||
#ifndef HUANYANG_ADDR
|
||||
#define HUANYANG_ADDR 0x01
|
||||
#endif
|
||||
|
||||
#ifndef HUANYANG_BAUD_RATE
|
||||
#define HUANYANG_BAUD_RATE 9600 // PD164 setting
|
||||
#endif
|
||||
|
||||
// communication task and queue stuff
|
||||
typedef struct {
|
||||
uint8_t tx_length;
|
||||
uint8_t rx_length;
|
||||
char msg[HUANYANG_MAX_MSG_SIZE];
|
||||
} hy_command_t;
|
||||
|
||||
QueueHandle_t hy_cmd_queue;
|
||||
|
||||
static TaskHandle_t vfd_cmdTaskHandle = 0;
|
||||
|
||||
// The communications task
|
||||
void vfd_cmd_task(void* pvParameters) {
|
||||
hy_command_t next_cmd;
|
||||
uint8_t rx_message[HUANYANG_MAX_MSG_SIZE];
|
||||
|
||||
while (true) {
|
||||
if (xQueueReceive(hy_cmd_queue, &next_cmd, 0) == pdTRUE) {
|
||||
//grbl_msg_sendf(CLIENT_SERIAL, MSG_LEVEL_INFO, "queue send %d !!!", next_cmd.tx_length);
|
||||
//report_hex_msg(next_cmd.msg, "To VFD:", next_cmd.tx_length); // TODO for debugging comment out
|
||||
uart_write_bytes(HUANYANG_UART_PORT, next_cmd.msg, next_cmd.tx_length);
|
||||
|
||||
uint16_t read_length = uart_read_bytes(HUANYANG_UART_PORT, rx_message, next_cmd.rx_length, RESPONSE_WAIT_TICKS);
|
||||
|
||||
if (read_length < next_cmd.rx_length) {
|
||||
grbl_msg_sendf(CLIENT_SERIAL, MSG_LEVEL_INFO, "Spindle RS485 Unresponsive");
|
||||
// TODO Do something with this error
|
||||
// system_set_exec_alarm(EXEC_ALARM_SPINDLE_CONTROL);
|
||||
}
|
||||
} else {
|
||||
// TODO: Should we ping the spindle here to make sure it does not go off line?
|
||||
}
|
||||
vTaskDelay(500); // TODO: What is the best value here?
|
||||
}
|
||||
}
|
||||
|
||||
// ================== Class methods ==================================
|
||||
|
||||
void HuanyangSpindle :: init() {
|
||||
|
||||
if (! _task_running) { // init can happen many times, we only want to start one task
|
||||
xTaskCreatePinnedToCore(vfd_cmd_task, // task
|
||||
"vfd_cmdTaskHandle", // name for task
|
||||
2048, // size of task stack
|
||||
NULL, // parameters
|
||||
1, // priority
|
||||
&vfd_cmdTaskHandle,
|
||||
0 // core
|
||||
);
|
||||
hy_cmd_queue = xQueueCreate(5, sizeof(hy_command_t));
|
||||
_task_running = true;
|
||||
}
|
||||
|
||||
// fail if required items are not defined
|
||||
if (!get_pins_and_settings()) {
|
||||
grbl_msg_sendf(CLIENT_SERIAL, MSG_LEVEL_INFO, "Huanyang spindle errors");
|
||||
return;
|
||||
}
|
||||
|
||||
// this allows us to init() again later.
|
||||
// If you change certain settings, init() gets called agian
|
||||
uart_driver_delete(HUANYANG_UART_PORT);
|
||||
|
||||
uart_config_t uart_config = {
|
||||
.baud_rate = HUANYANG_BAUD_RATE,
|
||||
.data_bits = UART_DATA_8_BITS,
|
||||
.parity = UART_PARITY_DISABLE,
|
||||
.stop_bits = UART_STOP_BITS_1,
|
||||
.flow_ctrl = UART_HW_FLOWCTRL_DISABLE,
|
||||
.rx_flow_ctrl_thresh = 122,
|
||||
};
|
||||
|
||||
uart_param_config(HUANYANG_UART_PORT, &uart_config);
|
||||
|
||||
uart_set_pin(HUANYANG_UART_PORT,
|
||||
_txd_pin,
|
||||
_rxd_pin,
|
||||
_rts_pin,
|
||||
UART_PIN_NO_CHANGE);
|
||||
|
||||
uart_driver_install(HUANYANG_UART_PORT,
|
||||
HUANYANG_BUF_SIZE * 2,
|
||||
0,
|
||||
0,
|
||||
NULL,
|
||||
0);
|
||||
|
||||
uart_set_mode(HUANYANG_UART_PORT, UART_MODE_RS485_HALF_DUPLEX);
|
||||
|
||||
is_reversable = true; // these VFDs are always reversable
|
||||
|
||||
//
|
||||
_current_pwm_rpm = 0;
|
||||
_state = SPINDLE_DISABLE;
|
||||
|
||||
config_message();
|
||||
}
|
||||
|
||||
// Checks for all the required pin definitions
|
||||
// It returns a message for each missing pin
|
||||
// Returns true if all pins are defined.
|
||||
bool HuanyangSpindle :: get_pins_and_settings() {
|
||||
bool pins_ok = true;
|
||||
|
||||
#ifdef HUANYANG_TXD_PIN
|
||||
_txd_pin = HUANYANG_TXD_PIN;
|
||||
#else
|
||||
grbl_msg_sendf(CLIENT_SERIAL, MSG_LEVEL_INFO, "Missing HUANYANG_TXD_PIN");
|
||||
pins_ok = false;
|
||||
#endif
|
||||
|
||||
#ifdef HUANYANG_RXD_PIN
|
||||
_rxd_pin = HUANYANG_RXD_PIN;
|
||||
#else
|
||||
grbl_msg_sendf(CLIENT_SERIAL, MSG_LEVEL_INFO, "No HUANYANG_RXD_PIN");
|
||||
pins_ok = false;
|
||||
#endif
|
||||
|
||||
#ifdef HUANYANG_RTS_PIN
|
||||
_rts_pin = HUANYANG_RTS_PIN;
|
||||
#else
|
||||
grbl_msg_sendf(CLIENT_SERIAL, MSG_LEVEL_INFO, "No HUANYANG_RTS_PIN");
|
||||
pins_ok = false;
|
||||
#endif
|
||||
|
||||
return pins_ok;
|
||||
}
|
||||
|
||||
void HuanyangSpindle :: config_message() {
|
||||
grbl_msg_sendf(CLIENT_SERIAL,
|
||||
MSG_LEVEL_INFO,
|
||||
"Huanyang Spindle Tx:%d Rx:%d RTS:%d",
|
||||
report_pin_number(_txd_pin),
|
||||
report_pin_number(_rxd_pin),
|
||||
report_pin_number(_rts_pin));
|
||||
}
|
||||
|
||||
/*
|
||||
ADDR CMD LEN DATA CRC
|
||||
0x01 0x03 0x01 0x01 0x31 0x88 Start spindle clockwise
|
||||
0x01 0x03 0x01 0x08 0xF1 0x8E Stop spindle
|
||||
0x01 0x03 0x01 0x11 0x30 0x44 Start spindle counter-clockwise
|
||||
*/
|
||||
void HuanyangSpindle :: set_state(uint8_t state, uint32_t rpm) {
|
||||
grbl_msg_sendf(CLIENT_SERIAL, MSG_LEVEL_INFO, "VFD Set state");
|
||||
|
||||
if (sys.abort)
|
||||
return; // Block during abort.
|
||||
|
||||
if (state != _state) { // already at the desired state. This function gets called a lot.
|
||||
_state = state; // store locally for faster get_state()
|
||||
set_mode(state);
|
||||
if (state == SPINDLE_DISABLE) {
|
||||
sys.spindle_speed = 0;
|
||||
return;
|
||||
}
|
||||
}
|
||||
|
||||
set_rpm(rpm);
|
||||
sys.report_ovr_counter = 0; // Set to report change immediately
|
||||
|
||||
return;
|
||||
}
|
||||
|
||||
bool HuanyangSpindle :: set_mode(uint8_t mode) {
|
||||
hy_command_t mode_cmd;
|
||||
|
||||
mode_cmd.tx_length = 6;
|
||||
mode_cmd.rx_length = 6;
|
||||
|
||||
mode_cmd.msg[0] = HUANYANG_ADDR;
|
||||
mode_cmd.msg[1] = 0x03;
|
||||
mode_cmd.msg[2] = 0x01;
|
||||
|
||||
if (mode == SPINDLE_ENABLE_CW)
|
||||
mode_cmd.msg[3] = 0x01;
|
||||
else if (mode == SPINDLE_ENABLE_CCW)
|
||||
mode_cmd.msg[3] = 0x11;
|
||||
else //SPINDLE_DISABLE
|
||||
mode_cmd.msg[3] = 0x08;
|
||||
|
||||
add_ModRTU_CRC(mode_cmd.msg, mode_cmd.rx_length);
|
||||
|
||||
if (xQueueSend(hy_cmd_queue, &mode_cmd, 0) != pdTRUE)
|
||||
grbl_msg_sendf(CLIENT_SERIAL, MSG_LEVEL_INFO, "VFD Queue Full");
|
||||
|
||||
return true;
|
||||
}
|
||||
|
||||
/*
|
||||
ADDR CMD LEN DATA CRC
|
||||
0x01 0x05 0x02 0x09 0xC4 0xBF 0x0F Write Frequency (0x9C4 = 2500 = 25.00HZ)
|
||||
*/
|
||||
uint32_t HuanyangSpindle :: set_rpm(uint32_t rpm) {
|
||||
hy_command_t rpm_cmd;
|
||||
|
||||
if (rpm == _current_pwm_rpm) // prevent setting same RPM twice
|
||||
return rpm;
|
||||
|
||||
_current_pwm_rpm = rpm;
|
||||
|
||||
// TODO add the speed modifiers override, linearization, etc.
|
||||
|
||||
rpm_cmd.tx_length = 7;
|
||||
rpm_cmd.rx_length = 6;
|
||||
|
||||
rpm_cmd.msg[0] = HUANYANG_ADDR;
|
||||
rpm_cmd.msg[1] = 0x05;
|
||||
rpm_cmd.msg[2] = 0x02;
|
||||
|
||||
uint16_t data = (uint16_t)(rpm * 100 / 60); // send Hz * 10 (Ex:1500 RPM = 25Hz .... Send 2500)
|
||||
|
||||
rpm_cmd.msg[3] = (data & 0xFF00) >> 8;
|
||||
rpm_cmd.msg[4] = (data & 0xFF);
|
||||
|
||||
add_ModRTU_CRC(rpm_cmd.msg, rpm_cmd.tx_length);
|
||||
|
||||
if (xQueueSend(hy_cmd_queue, &rpm_cmd, 0) != pdTRUE)
|
||||
grbl_msg_sendf(CLIENT_SERIAL, MSG_LEVEL_INFO, "VFD Queue Full");
|
||||
|
||||
return rpm;
|
||||
}
|
||||
|
||||
void HuanyangSpindle ::stop() {
|
||||
set_mode(SPINDLE_DISABLE);
|
||||
}
|
||||
|
||||
// state is cached rather than read right now to prevent delays
|
||||
uint8_t HuanyangSpindle :: get_state() {
|
||||
return _state;
|
||||
}
|
||||
|
||||
// Calculate the CRC on all of the byte except the last 2
|
||||
// It then added the CRC to those last 2 bytes
|
||||
// full_msg_len This is the length of the message including the 2 crc bytes
|
||||
// Source: https://ctlsys.com/support/how_to_compute_the_modbus_rtu_message_crc/
|
||||
void HuanyangSpindle :: add_ModRTU_CRC(char* buf, int full_msg_len) {
|
||||
uint16_t crc = 0xFFFF;
|
||||
for (int pos = 0; pos < full_msg_len - 2; pos++) {
|
||||
crc ^= (uint16_t)buf[pos]; // XOR byte into least sig. byte of crc
|
||||
for (int i = 8; i != 0; i--) { // Loop over each bit
|
||||
if ((crc & 0x0001) != 0) { // If the LSB is set
|
||||
crc >>= 1; // Shift right and XOR 0xA001
|
||||
crc ^= 0xA001;
|
||||
} else // Else LSB is not set
|
||||
crc >>= 1; // Just shift right
|
||||
}
|
||||
}
|
||||
// add the calculated Crc to the message
|
||||
buf[full_msg_len - 1] = (crc & 0xFF00) >> 8;
|
||||
buf[full_msg_len - 2] = (crc & 0xFF);
|
||||
}
|
39
Grbl_Esp32/Spindles/Laser.cpp
Normal file
39
Grbl_Esp32/Spindles/Laser.cpp
Normal file
@@ -0,0 +1,39 @@
|
||||
/*
|
||||
Laser.cpp
|
||||
|
||||
This is similar the the PWM Spindle except that it allows the
|
||||
M4 speed vs. power copensation.
|
||||
|
||||
Part of Grbl_ESP32
|
||||
2020 - Bart Dring
|
||||
|
||||
Grbl is free software: you can redistribute it and/or modify
|
||||
it under the terms of the GNU General Public License as published by
|
||||
the Free Software Foundation, either version 3 of the License, or
|
||||
(at your option) any later version.
|
||||
Grbl is distributed in the hope that it will be useful,
|
||||
but WITHOUT ANY WARRANTY; without even the implied warranty of
|
||||
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
|
||||
GNU General Public License for more details.
|
||||
You should have received a copy of the GNU General Public License
|
||||
along with Grbl. If not, see <http://www.gnu.org/licenses/>.
|
||||
|
||||
*/
|
||||
#include "SpindleClass.h"
|
||||
|
||||
// ===================================== Laser ==============================================
|
||||
|
||||
|
||||
bool Laser :: isRateAdjusted() {
|
||||
return true; // can use M4 (CCW) laser mode.
|
||||
}
|
||||
|
||||
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",
|
||||
report_pin_number(_output_pin),
|
||||
_pwm_freq,
|
||||
_pwm_precision,
|
||||
isRateAdjusted()); // the current mode
|
||||
}
|
41
Grbl_Esp32/Spindles/NullSpindle.cpp
Normal file
41
Grbl_Esp32/Spindles/NullSpindle.cpp
Normal file
@@ -0,0 +1,41 @@
|
||||
/*
|
||||
NullSpindle.cpp
|
||||
|
||||
This is used when you don't want to use a spindle No I/O will be used
|
||||
and most methods don't do anything
|
||||
|
||||
Part of Grbl_ESP32
|
||||
2020 - Bart Dring
|
||||
|
||||
Grbl is free software: you can redistribute it and/or modify
|
||||
it under the terms of the GNU General Public License as published by
|
||||
the Free Software Foundation, either version 3 of the License, or
|
||||
(at your option) any later version.
|
||||
Grbl is distributed in the hope that it will be useful,
|
||||
but WITHOUT ANY WARRANTY; without even the implied warranty of
|
||||
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
|
||||
GNU General Public License for more details.
|
||||
You should have received a copy of the GNU General Public License
|
||||
along with Grbl. If not, see <http://www.gnu.org/licenses/>.
|
||||
|
||||
*/
|
||||
#include "SpindleClass.h"
|
||||
|
||||
// ======================= NullSpindle ==============================
|
||||
// NullSpindle is just bunch of do nothing (ignore) methods to be used when you don't want a spindle
|
||||
|
||||
void NullSpindle :: init() {
|
||||
is_reversable = false;
|
||||
config_message();
|
||||
}
|
||||
uint32_t NullSpindle :: set_rpm(uint32_t rpm) {
|
||||
return rpm;
|
||||
}
|
||||
void NullSpindle :: set_state(uint8_t state, uint32_t rpm) {}
|
||||
uint8_t NullSpindle :: get_state() {
|
||||
return (SPINDLE_STATE_DISABLE);
|
||||
}
|
||||
void NullSpindle :: stop() {}
|
||||
void NullSpindle :: config_message() {
|
||||
grbl_msg_sendf(CLIENT_SERIAL, MSG_LEVEL_INFO, "No spindle");
|
||||
}
|
257
Grbl_Esp32/Spindles/PWMSpindle.cpp
Normal file
257
Grbl_Esp32/Spindles/PWMSpindle.cpp
Normal file
@@ -0,0 +1,257 @@
|
||||
/*
|
||||
PWMSpindle.cpp
|
||||
|
||||
This is a full featured TTL PWM spindle This does not include speed/power
|
||||
compensation. Use the Laser class for that.
|
||||
|
||||
Part of Grbl_ESP32
|
||||
2020 - Bart Dring
|
||||
|
||||
Grbl is free software: you can redistribute it and/or modify
|
||||
it under the terms of the GNU General Public License as published by
|
||||
the Free Software Foundation, either version 3 of the License, or
|
||||
(at your option) any later version.
|
||||
Grbl is distributed in the hope that it will be useful,
|
||||
but WITHOUT ANY WARRANTY; without even the implied warranty of
|
||||
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
|
||||
GNU General Public License for more details.
|
||||
You should have received a copy of the GNU General Public License
|
||||
along with Grbl. If not, see <http://www.gnu.org/licenses/>.
|
||||
|
||||
*/
|
||||
#include "SpindleClass.h"
|
||||
|
||||
// ======================= PWMSpindle ==============================
|
||||
/*
|
||||
This gets called at startup or whenever a spindle setting changes
|
||||
If the spindle is running it will stop and need to be restarted with M3Snnnn
|
||||
*/
|
||||
|
||||
//#include "grbl.h"
|
||||
|
||||
void PWMSpindle :: init() {
|
||||
|
||||
get_pins_and_settings();
|
||||
|
||||
if (_output_pin == UNDEFINED_PIN) {
|
||||
grbl_msg_sendf(CLIENT_SERIAL, MSG_LEVEL_INFO, "Warning: Spindle output pin not defined");
|
||||
return; // We cannot continue without the output pin
|
||||
}
|
||||
|
||||
ledcSetup(_spindle_pwm_chan_num, (double)_pwm_freq, _pwm_precision); // setup the channel
|
||||
ledcAttachPin(_output_pin, _spindle_pwm_chan_num); // attach the PWM to the pin
|
||||
|
||||
if (_enable_pin != UNDEFINED_PIN)
|
||||
pinMode(_enable_pin, OUTPUT);
|
||||
|
||||
if (_direction_pin != UNDEFINED_PIN)
|
||||
pinMode(_direction_pin, OUTPUT);
|
||||
|
||||
config_message();
|
||||
}
|
||||
|
||||
// Get the GPIO from the machine definition
|
||||
void PWMSpindle :: get_pins_and_settings() {
|
||||
// setup all the pins
|
||||
|
||||
#ifdef SPINDLE_OUTPUT_PIN
|
||||
_output_pin = SPINDLE_OUTPUT_PIN;
|
||||
#else
|
||||
_output_pin = UNDEFINED_PIN;
|
||||
#endif
|
||||
|
||||
#ifdef INVERT_SPINDLE_ENABLE_PIN
|
||||
_invert_pwm = true;
|
||||
#else
|
||||
_invert_pwm = false;
|
||||
#endif
|
||||
|
||||
#ifdef SPINDLE_ENABLE_PIN
|
||||
_enable_pin = SPINDLE_ENABLE_PIN;
|
||||
#ifdef SPINDLE_ENABLE_OFF_WITH_ZERO_SPEED
|
||||
_off_with_zero_speed = true;
|
||||
#endif
|
||||
#else
|
||||
_enable_pin = UNDEFINED_PIN;
|
||||
_off_with_zero_speed = false;
|
||||
#endif
|
||||
|
||||
|
||||
#ifdef SPINDLE_DIR_PIN
|
||||
_direction_pin = SPINDLE_DIR_PIN;
|
||||
#else
|
||||
_direction_pin = UNDEFINED_PIN;
|
||||
#endif
|
||||
|
||||
is_reversable = (_direction_pin != UNDEFINED_PIN);
|
||||
|
||||
_pwm_freq = (uint32_t)settings.spindle_pwm_freq;
|
||||
_pwm_precision = calc_pwm_precision(_pwm_freq); // detewrmine the best precision
|
||||
_pwm_period = (1 << _pwm_precision);
|
||||
|
||||
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 * (uint32_t)settings.spindle_pwm_off_value / 100.0);
|
||||
_pwm_min_value = (_pwm_period * (uint32_t)settings.spindle_pwm_min_value / 100.0);
|
||||
_pwm_max_value = (_pwm_period * (uint32_t)settings.spindle_pwm_max_value / 100.0);
|
||||
|
||||
#ifdef ENABLE_PIECEWISE_LINEAR_SPINDLE
|
||||
_min_rpm = RPM_MIN;
|
||||
_max_rpm = RPM_MAX;
|
||||
_piecewide_linear = true;
|
||||
#else
|
||||
_min_rpm = (uint32_t)settings.rpm_min;
|
||||
_max_rpm = (uint32_t)settings.rpm_max;
|
||||
_piecewide_linear = false;
|
||||
#endif
|
||||
// The pwm_gradient is the pwm duty cycle units per rpm
|
||||
// _pwm_gradient = (_pwm_max_value - _pwm_min_value) / (_max_rpm - _min_rpm);
|
||||
|
||||
_spindle_pwm_chan_num = 0; // Channel 0 is reserved for spindle use
|
||||
|
||||
|
||||
}
|
||||
|
||||
uint32_t PWMSpindle::set_rpm(uint32_t rpm) {
|
||||
uint32_t pwm_value;
|
||||
|
||||
if (_output_pin == UNDEFINED_PIN)
|
||||
return rpm;
|
||||
|
||||
//grbl_msg_sendf(CLIENT_SERIAL, MSG_LEVEL_INFO, "Set rpm %d", rpm);
|
||||
|
||||
// apply override
|
||||
rpm = rpm * sys.spindle_speed_ovr / 100; // Scale by spindle speed override value (uint8_t percent)
|
||||
|
||||
// apply limits
|
||||
if ((_min_rpm >= _max_rpm) || (rpm >= _max_rpm))
|
||||
rpm = _max_rpm;
|
||||
else if (rpm != 0 && rpm <= _min_rpm)
|
||||
rpm = _min_rpm;
|
||||
|
||||
sys.spindle_speed = rpm;
|
||||
|
||||
if (_piecewide_linear) {
|
||||
//pwm_value = piecewise_linear_fit(rpm); TODO
|
||||
pwm_value = 0;
|
||||
grbl_msg_sendf(CLIENT_SERIAL, MSG_LEVEL_INFO, "Warning: Linear fit not implemented yet.");
|
||||
|
||||
} else {
|
||||
if (rpm == 0)
|
||||
pwm_value = _pwm_off_value;
|
||||
else
|
||||
pwm_value = map_uint32_t(rpm, _min_rpm, _max_rpm, _pwm_min_value, _pwm_max_value);
|
||||
}
|
||||
|
||||
if (_off_with_zero_speed)
|
||||
set_enable_pin(rpm != 0);
|
||||
|
||||
set_output(pwm_value);
|
||||
|
||||
return 0;
|
||||
}
|
||||
|
||||
void PWMSpindle::set_state(uint8_t state, uint32_t rpm) {
|
||||
if (sys.abort)
|
||||
return; // Block during abort.
|
||||
|
||||
if (state == SPINDLE_DISABLE) { // Halt or set spindle direction and rpm.
|
||||
sys.spindle_speed = 0;
|
||||
stop();
|
||||
} else {
|
||||
set_spindle_dir_pin(state == SPINDLE_ENABLE_CW);
|
||||
set_rpm(rpm);
|
||||
}
|
||||
|
||||
set_enable_pin(state == SPINDLE_DISABLE);
|
||||
|
||||
sys.report_ovr_counter = 0; // Set to report change immediately
|
||||
}
|
||||
|
||||
uint8_t PWMSpindle::get_state() {
|
||||
|
||||
|
||||
if (_current_pwm_duty == 0 || _output_pin == UNDEFINED_PIN)
|
||||
return (SPINDLE_STATE_DISABLE);
|
||||
else {
|
||||
if (_direction_pin != UNDEFINED_PIN) {
|
||||
if (digitalRead(_direction_pin))
|
||||
return (SPINDLE_STATE_CW);
|
||||
else
|
||||
return (SPINDLE_STATE_CCW);
|
||||
} else
|
||||
return (SPINDLE_STATE_CW);
|
||||
}
|
||||
}
|
||||
|
||||
void PWMSpindle::stop() {
|
||||
// inverts are delt with in methods
|
||||
set_enable_pin(false);
|
||||
set_output(_pwm_off_value);
|
||||
}
|
||||
|
||||
// prints the startup message of the spindle config
|
||||
void PWMSpindle :: config_message() {
|
||||
grbl_msg_sendf(CLIENT_SERIAL,
|
||||
MSG_LEVEL_INFO,
|
||||
"PWM spindle Output:%d, Enbl:%d, Dir:%d, Freq:%dHz, Res:%dbits",
|
||||
report_pin_number(_output_pin),
|
||||
report_pin_number(_enable_pin), // 255 means pin not defined
|
||||
report_pin_number(_direction_pin), // 255 means pin not defined
|
||||
_pwm_freq,
|
||||
_pwm_precision);
|
||||
}
|
||||
|
||||
|
||||
void PWMSpindle::set_output(uint32_t duty) {
|
||||
if (_output_pin == UNDEFINED_PIN)
|
||||
return;
|
||||
|
||||
//grbl_msg_sendf(CLIENT_SERIAL, MSG_LEVEL_INFO, "Set output %d", duty);
|
||||
|
||||
// to prevent excessive calls to ledcWrite, make sure duty hass changed
|
||||
if (duty == _current_pwm_duty)
|
||||
return;
|
||||
|
||||
_current_pwm_duty = duty;
|
||||
|
||||
if (_invert_pwm)
|
||||
duty = (1 << _pwm_precision) - duty;
|
||||
|
||||
ledcWrite(_spindle_pwm_chan_num, duty);
|
||||
|
||||
}
|
||||
|
||||
void PWMSpindle::set_enable_pin(bool enable) {
|
||||
if (_enable_pin == UNDEFINED_PIN)
|
||||
return;
|
||||
#ifndef INVERT_SPINDLE_ENABLE_PIN
|
||||
digitalWrite(_enable_pin, enable);
|
||||
#else
|
||||
digitalWrite(_enable_pin, !enable);
|
||||
#endif
|
||||
}
|
||||
|
||||
void PWMSpindle::set_spindle_dir_pin(bool Clockwise) {
|
||||
if (_direction_pin != UNDEFINED_PIN)
|
||||
digitalWrite(_direction_pin, Clockwise);
|
||||
}
|
||||
|
||||
|
||||
/*
|
||||
Calculate the highest precision of a PWM based on the frequency in bits
|
||||
|
||||
80,000,000 / freq = period
|
||||
determine the highest precision where (1 << precision) < period
|
||||
*/
|
||||
uint8_t PWMSpindle :: calc_pwm_precision(uint32_t freq) {
|
||||
uint8_t precision = 0;
|
||||
|
||||
// increase the precision (bits) until it exceeds allow by frequency the max or is 16
|
||||
while ((1 << precision) < (uint32_t)(80000000 / freq) && precision <= 16)
|
||||
precision++;
|
||||
|
||||
return precision - 1;
|
||||
}
|
80
Grbl_Esp32/Spindles/RelaySpindle.cpp
Normal file
80
Grbl_Esp32/Spindles/RelaySpindle.cpp
Normal file
@@ -0,0 +1,80 @@
|
||||
/*
|
||||
RelaySpindle.cpp
|
||||
|
||||
This is used for a basic on/off spindle All S Values above 0
|
||||
will turn the spindle on.
|
||||
|
||||
Part of Grbl_ESP32
|
||||
2020 - Bart Dring
|
||||
|
||||
Grbl is free software: you can redistribute it and/or modify
|
||||
it under the terms of the GNU General Public License as published by
|
||||
the Free Software Foundation, either version 3 of the License, or
|
||||
(at your option) any later version.
|
||||
Grbl is distributed in the hope that it will be useful,
|
||||
but WITHOUT ANY WARRANTY; without even the implied warranty of
|
||||
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
|
||||
GNU General Public License for more details.
|
||||
You should have received a copy of the GNU General Public License
|
||||
along with Grbl. If not, see <http://www.gnu.org/licenses/>.
|
||||
|
||||
*/
|
||||
#include "SpindleClass.h"
|
||||
|
||||
// ========================= RelaySpindle ==================================
|
||||
/*
|
||||
This is a sub class of PWMSpindle but is a digital rather than PWM output
|
||||
*/
|
||||
void RelaySpindle::init() {
|
||||
get_pins_and_settings();
|
||||
|
||||
if (_output_pin == UNDEFINED_PIN)
|
||||
return;
|
||||
|
||||
pinMode(_output_pin, OUTPUT);
|
||||
|
||||
if (_enable_pin != UNDEFINED_PIN)
|
||||
pinMode(_enable_pin, OUTPUT);
|
||||
|
||||
if (_direction_pin != UNDEFINED_PIN)
|
||||
pinMode(_direction_pin, OUTPUT);
|
||||
|
||||
is_reversable = (_direction_pin != UNDEFINED_PIN);
|
||||
|
||||
config_message();
|
||||
}
|
||||
|
||||
// prints the startup message of the spindle config
|
||||
void RelaySpindle :: config_message() {
|
||||
grbl_msg_sendf(CLIENT_SERIAL,
|
||||
MSG_LEVEL_INFO,
|
||||
"Relay spindle Output:%d, Enbl:%d, Dir:%d",
|
||||
report_pin_number(_output_pin),
|
||||
report_pin_number(_enable_pin), // 255 means pin not defined
|
||||
report_pin_number(_direction_pin)); // 255 means pin not defined
|
||||
}
|
||||
|
||||
uint32_t RelaySpindle::set_rpm(uint32_t rpm) {
|
||||
if (_output_pin == UNDEFINED_PIN)
|
||||
return rpm;
|
||||
|
||||
sys.spindle_speed = rpm;
|
||||
|
||||
if (rpm == 0) {
|
||||
set_output(0);
|
||||
} else {
|
||||
set_output(1);
|
||||
}
|
||||
|
||||
if (_off_with_zero_speed)
|
||||
set_enable_pin(rpm != 0);
|
||||
|
||||
return rpm;
|
||||
}
|
||||
|
||||
void RelaySpindle::set_output(uint32_t duty) {
|
||||
#ifdef INVERT_SPINDLE_PWM
|
||||
duty = (duty == 0); // flip duty
|
||||
#endif
|
||||
digitalWrite(_output_pin, duty > 0); // anything greater
|
||||
}
|
91
Grbl_Esp32/Spindles/SpindleClass.cpp
Normal file
91
Grbl_Esp32/Spindles/SpindleClass.cpp
Normal file
@@ -0,0 +1,91 @@
|
||||
/*
|
||||
SpindleClass.cpp
|
||||
|
||||
A Base class for spindles and spinsle like things such as lasers
|
||||
|
||||
Part of Grbl_ESP32
|
||||
|
||||
2020 - Bart Dring
|
||||
|
||||
Grbl is free software: you can redistribute it and/or modify
|
||||
it under the terms of the GNU General Public License as published by
|
||||
the Free Software Foundation, either version 3 of the License, or
|
||||
(at your option) any later version.
|
||||
Grbl is distributed in the hope that it will be useful,
|
||||
but WITHOUT ANY WARRANTY; without even the implied warranty of
|
||||
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
|
||||
GNU General Public License for more details.
|
||||
You should have received a copy of the GNU General Public License
|
||||
along with Grbl. If not, see <http://www.gnu.org/licenses/>.
|
||||
|
||||
TODO
|
||||
Add Spindle spin up/down delays
|
||||
|
||||
Get rid of dependance on machine definition #defines
|
||||
SPINDLE_OUTPUT_PIN
|
||||
SPINDLE_ENABLE_PIN
|
||||
SPINDLE_DIR_PIN
|
||||
|
||||
*/
|
||||
#include "NullSpindle.cpp"
|
||||
#include "PWMSpindle.cpp"
|
||||
#include "DacSpindle.cpp"
|
||||
#include "RelaySpindle.cpp"
|
||||
#include "Laser.cpp"
|
||||
#include "HuanyangSpindle.cpp"
|
||||
#include "BESCSpindle.cpp"
|
||||
|
||||
|
||||
// An instance of each type of spindle is created here.
|
||||
// This allows the spindle to be dynamicly switched
|
||||
NullSpindle null_spindle;
|
||||
PWMSpindle pwm_spindle;
|
||||
RelaySpindle relay_spindle;
|
||||
Laser laser;
|
||||
DacSpindle dac_spindle;
|
||||
HuanyangSpindle huanyang_spindle;
|
||||
BESCSpindle besc_spindle;
|
||||
|
||||
|
||||
void spindle_select(uint8_t spindle_type) {
|
||||
|
||||
switch (spindle_type) {
|
||||
case SPINDLE_TYPE_PWM:
|
||||
spindle = &pwm_spindle;
|
||||
break;
|
||||
case SPINDLE_TYPE_RELAY:
|
||||
spindle = &relay_spindle;
|
||||
break;
|
||||
case SPINDLE_TYPE_LASER:
|
||||
spindle = &laser;
|
||||
break;
|
||||
case SPINDLE_TYPE_DAC:
|
||||
spindle = &dac_spindle;
|
||||
break;
|
||||
case SPINDLE_TYPE_HUANYANG:
|
||||
spindle = &huanyang_spindle;
|
||||
break;
|
||||
case SPINDLE_TYPE_BESC:
|
||||
spindle = &besc_spindle;
|
||||
break;
|
||||
case SPINDLE_TYPE_NONE:
|
||||
default:
|
||||
spindle = &null_spindle;
|
||||
break;
|
||||
}
|
||||
|
||||
spindle->init();
|
||||
}
|
||||
|
||||
// ========================= Spindle ==================================
|
||||
|
||||
bool Spindle::isRateAdjusted() {
|
||||
return false; // default for basic spindle is false
|
||||
}
|
||||
|
||||
void Spindle :: spindle_sync(uint8_t state, uint32_t rpm) {
|
||||
if (sys.state == STATE_CHECK_MODE)
|
||||
return;
|
||||
protocol_buffer_synchronize(); // Empty planner buffer to ensure spindle is set when programmed.
|
||||
set_state(state, rpm);
|
||||
}
|
197
Grbl_Esp32/Spindles/SpindleClass.h
Normal file
197
Grbl_Esp32/Spindles/SpindleClass.h
Normal file
@@ -0,0 +1,197 @@
|
||||
/*
|
||||
SpindleClass.h
|
||||
|
||||
Header file for a Spindle Class
|
||||
See SpindleClass.cpp for more details
|
||||
|
||||
Part of Grbl_ESP32
|
||||
|
||||
2020 - Bart Dring This file was modified for use on the ESP32
|
||||
CPU. Do not use this with Grbl for atMega328P
|
||||
|
||||
Grbl is free software: you can redistribute it and/or modify
|
||||
it under the terms of the GNU General Public License as published by
|
||||
the Free Software Foundation, either version 3 of the License, or
|
||||
(at your option) any later version.
|
||||
Grbl is distributed in the hope that it will be useful,
|
||||
but WITHOUT ANY WARRANTY; without even the implied warranty of
|
||||
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
|
||||
GNU General Public License for more details.
|
||||
You should have received a copy of the GNU General Public License
|
||||
along with Grbl. If not, see <http://www.gnu.org/licenses/>.
|
||||
|
||||
See SpindleClass.cpp for more info and references
|
||||
|
||||
*/
|
||||
|
||||
#define SPINDLE_STATE_DISABLE 0 // Must be zero.
|
||||
#define SPINDLE_STATE_CW bit(0)
|
||||
#define SPINDLE_STATE_CCW bit(1)
|
||||
|
||||
|
||||
#define SPINDLE_TYPE_NONE 0
|
||||
#define SPINDLE_TYPE_PWM 1
|
||||
#define SPINDLE_TYPE_RELAY 2
|
||||
#define SPINDLE_TYPE_LASER 3
|
||||
#define SPINDLE_TYPE_DAC 4
|
||||
#define SPINDLE_TYPE_HUANYANG 5
|
||||
#define SPINDLE_TYPE_BESC 6
|
||||
|
||||
#ifndef SPINDLE_CLASS_H
|
||||
#define SPINDLE_CLASS_H
|
||||
|
||||
#include "../grbl.h"
|
||||
#include <driver/dac.h>
|
||||
#include "driver/uart.h"
|
||||
|
||||
|
||||
// =============== No floats! ===========================
|
||||
// ================ NO FLOATS! ==========================
|
||||
|
||||
// This is the base class. Do not use this as your spindle
|
||||
class Spindle {
|
||||
public:
|
||||
virtual void init(); // not in constructor because this also gets called when $$ settings change
|
||||
virtual uint32_t set_rpm(uint32_t rpm);
|
||||
virtual void set_state(uint8_t state, uint32_t rpm);
|
||||
virtual uint8_t get_state();
|
||||
virtual void stop();
|
||||
virtual void config_message();
|
||||
virtual bool isRateAdjusted();
|
||||
virtual void spindle_sync(uint8_t state, uint32_t rpm);
|
||||
|
||||
bool is_reversable;
|
||||
};
|
||||
|
||||
// This is a dummy spindle that has no I/O.
|
||||
// It is used to ignore spindle commands when no spinde is desired
|
||||
class NullSpindle : public Spindle {
|
||||
public:
|
||||
void init();
|
||||
uint32_t set_rpm(uint32_t rpm);
|
||||
void set_state(uint8_t state, uint32_t rpm);
|
||||
uint8_t get_state();
|
||||
void stop();
|
||||
void config_message();
|
||||
};
|
||||
|
||||
// This adds support for PWM
|
||||
class PWMSpindle : public Spindle {
|
||||
public:
|
||||
void init();
|
||||
virtual uint32_t set_rpm(uint32_t rpm);
|
||||
void set_state(uint8_t state, uint32_t rpm);
|
||||
uint8_t get_state();
|
||||
void stop();
|
||||
void config_message();
|
||||
|
||||
private:
|
||||
|
||||
int32_t _current_pwm_duty;
|
||||
void set_spindle_dir_pin(bool Clockwise);
|
||||
|
||||
protected:
|
||||
uint32_t _min_rpm;
|
||||
uint32_t _max_rpm;
|
||||
uint32_t _pwm_off_value;
|
||||
uint32_t _pwm_min_value;
|
||||
uint32_t _pwm_max_value;
|
||||
uint8_t _output_pin;
|
||||
uint8_t _enable_pin;
|
||||
uint8_t _direction_pin;
|
||||
uint8_t _spindle_pwm_chan_num;
|
||||
uint32_t _pwm_freq;
|
||||
uint32_t _pwm_period; // how many counts in 1 period
|
||||
uint8_t _pwm_precision;
|
||||
bool _piecewide_linear;
|
||||
bool _off_with_zero_speed;
|
||||
bool _invert_pwm;
|
||||
//uint32_t _pwm_gradient; // Precalulated value to speed up rpm to PWM conversions.
|
||||
|
||||
virtual void set_output(uint32_t duty);
|
||||
void set_enable_pin(bool enable_pin);
|
||||
void get_pins_and_settings();
|
||||
uint8_t calc_pwm_precision(uint32_t freq);
|
||||
};
|
||||
|
||||
// This is for an on/off spindle all RPMs above 0 are on
|
||||
class RelaySpindle : public PWMSpindle {
|
||||
public:
|
||||
void init();
|
||||
void config_message();
|
||||
uint32_t set_rpm(uint32_t rpm);
|
||||
protected:
|
||||
void set_output(uint32_t duty);
|
||||
};
|
||||
|
||||
// this is the same as a PWM spindle but the M4 compensation is supported.
|
||||
class Laser : public PWMSpindle {
|
||||
public:
|
||||
bool isRateAdjusted();
|
||||
void config_message();
|
||||
};
|
||||
|
||||
// This uses one of the (2) DAC pins on ESP32 to output a voltage
|
||||
class DacSpindle : public PWMSpindle {
|
||||
public:
|
||||
void init();
|
||||
void config_message();
|
||||
uint32_t set_rpm(uint32_t rpm);
|
||||
private:
|
||||
bool _gpio_ok; // DAC is on a valid pin
|
||||
protected:
|
||||
void set_output(uint32_t duty); // sets DAC instead of PWM
|
||||
};
|
||||
|
||||
class HuanyangSpindle : public Spindle {
|
||||
private:
|
||||
uint16_t ModRTU_CRC(char* buf, int len);
|
||||
void add_ModRTU_CRC(char* buf, int full_msg_len);
|
||||
bool set_mode(uint8_t mode);
|
||||
bool get_pins_and_settings();
|
||||
|
||||
uint32_t _current_pwm_rpm;
|
||||
uint8_t _txd_pin;
|
||||
uint8_t _rxd_pin;
|
||||
uint8_t _rts_pin;
|
||||
uint8_t _state;
|
||||
bool _task_running;
|
||||
|
||||
public:
|
||||
HuanyangSpindle() {
|
||||
_task_running = false;
|
||||
}
|
||||
void init();
|
||||
void config_message();
|
||||
void set_state(uint8_t state, uint32_t rpm);
|
||||
uint8_t get_state();
|
||||
uint32_t set_rpm(uint32_t rpm);
|
||||
void stop();
|
||||
|
||||
|
||||
};
|
||||
|
||||
class BESCSpindle : public PWMSpindle {
|
||||
public:
|
||||
void init();
|
||||
void config_message();
|
||||
uint32_t set_rpm(uint32_t rpm);
|
||||
};
|
||||
|
||||
extern Spindle* spindle;
|
||||
|
||||
|
||||
extern NullSpindle null_spindle;
|
||||
extern PWMSpindle pwm_spindle;
|
||||
extern RelaySpindle relay_spindle;
|
||||
extern Laser laser;
|
||||
extern DacSpindle dac_spindle;
|
||||
extern HuanyangSpindle huanyang_spindle;
|
||||
extern BESCSpindle besc_spindle;
|
||||
|
||||
void spindle_select(uint8_t spindletype);
|
||||
|
||||
// in HuanyangSpindle.cpp
|
||||
void vfd_cmd_task(void* pvParameters);
|
||||
|
||||
#endif
|
@@ -295,23 +295,16 @@ uint8_t gc_execute_line(char* line, uint8_t client) {
|
||||
case 3:
|
||||
case 4:
|
||||
case 5:
|
||||
#ifndef SPINDLE_PWM_PIN
|
||||
grbl_msg_sendf(CLIENT_SERIAL, MSG_LEVEL_INFO, "No spindle pin defined");
|
||||
#endif
|
||||
word_bit = MODAL_GROUP_M7;
|
||||
switch (int_value) {
|
||||
case 3:
|
||||
gc_block.modal.spindle = SPINDLE_ENABLE_CW;
|
||||
break;
|
||||
case 4: // Supported if SPINDLE_DIR_PIN is defined or laser mode is on.
|
||||
#ifndef SPINDLE_DIR_PIN
|
||||
// if laser mode is not on then this is an unsupported command
|
||||
if bit_isfalse(settings.flags, BITFLAG_LASER_MODE) {
|
||||
if (spindle->is_reversable || bit_istrue(settings.flags, BITFLAG_LASER_MODE))
|
||||
gc_block.modal.spindle = SPINDLE_ENABLE_CCW;
|
||||
else
|
||||
FAIL(STATUS_GCODE_UNSUPPORTED_COMMAND);
|
||||
break;
|
||||
}
|
||||
#endif
|
||||
gc_block.modal.spindle = SPINDLE_ENABLE_CCW;
|
||||
break;
|
||||
case 5:
|
||||
gc_block.modal.spindle = SPINDLE_DISABLE;
|
||||
@@ -1088,16 +1081,12 @@ uint8_t gc_execute_line(char* line, uint8_t client) {
|
||||
// [4. Set spindle speed ]:
|
||||
if ((gc_state.spindle_speed != gc_block.values.s) || bit_istrue(gc_parser_flags, GC_PARSER_LASER_FORCE_SYNC)) {
|
||||
if (gc_state.modal.spindle != SPINDLE_DISABLE) {
|
||||
#ifdef VARIABLE_SPINDLE
|
||||
if (bit_isfalse(gc_parser_flags, GC_PARSER_LASER_ISMOTION)) {
|
||||
if (bit_istrue(gc_parser_flags, GC_PARSER_LASER_DISABLE))
|
||||
spindle_sync(gc_state.modal.spindle, 0.0);
|
||||
spindle->spindle_sync(gc_state.modal.spindle, 0);
|
||||
else
|
||||
spindle_sync(gc_state.modal.spindle, gc_block.values.s);
|
||||
spindle->spindle_sync(gc_state.modal.spindle, (uint32_t)gc_block.values.s);
|
||||
}
|
||||
#else
|
||||
spindle_sync(gc_state.modal.spindle, 0.0);
|
||||
#endif
|
||||
}
|
||||
gc_state.spindle_speed = gc_block.values.s; // Update spindle speed state.
|
||||
}
|
||||
@@ -1118,7 +1107,7 @@ uint8_t gc_execute_line(char* line, uint8_t client) {
|
||||
// Update spindle control and apply spindle speed when enabling it in this block.
|
||||
// NOTE: All spindle state changes are synced, even in laser mode. Also, pl_data,
|
||||
// rather than gc_state, is used to manage laser state for non-laser motions.
|
||||
spindle_sync(gc_block.modal.spindle, pl_data->spindle_speed);
|
||||
spindle->spindle_sync(gc_block.modal.spindle, (uint32_t)pl_data->spindle_speed);
|
||||
gc_state.modal.spindle = gc_block.modal.spindle;
|
||||
}
|
||||
pl_data->condition |= gc_state.modal.spindle; // Set condition flag for planner use.
|
||||
@@ -1294,7 +1283,7 @@ uint8_t gc_execute_line(char* line, uint8_t client) {
|
||||
if (!(settings_read_coord_data(gc_state.modal.coord_select, gc_state.coord_system)))
|
||||
FAIL(STATUS_SETTING_READ_FAIL);
|
||||
system_flag_wco_change(); // Set to refresh immediately just in case something altered.
|
||||
spindle_set_state(SPINDLE_DISABLE, 0.0);
|
||||
spindle->set_state(SPINDLE_DISABLE, 0);
|
||||
coolant_set_state(COOLANT_DISABLE);
|
||||
}
|
||||
report_feedback_message(MESSAGE_PROGRAM_END);
|
||||
|
@@ -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
|
||||
}
|
||||
@@ -535,7 +535,6 @@ static void protocol_exec_rt_suspend() {
|
||||
#endif
|
||||
plan_block_t* block = plan_get_current_block();
|
||||
uint8_t restore_condition;
|
||||
#ifdef VARIABLE_SPINDLE
|
||||
float restore_spindle_speed;
|
||||
if (block == NULL) {
|
||||
restore_condition = (gc_state.modal.spindle | gc_state.modal.coolant);
|
||||
@@ -548,10 +547,7 @@ static void protocol_exec_rt_suspend() {
|
||||
if (bit_istrue(settings.flags, BITFLAG_LASER_MODE))
|
||||
system_set_exec_accessory_override_flag(EXEC_SPINDLE_OVR_STOP);
|
||||
#endif
|
||||
#else
|
||||
if (block == NULL) restore_condition = (gc_state.modal.spindle | gc_state.modal.coolant);
|
||||
else restore_condition = block->condition;
|
||||
#endif
|
||||
|
||||
while (sys.suspend) {
|
||||
if (sys.abort) return;
|
||||
// Block until initial hold is complete and the machine has stopped motion.
|
||||
@@ -564,7 +560,7 @@ static void protocol_exec_rt_suspend() {
|
||||
// Ensure any prior spindle stop override is disabled at start of safety door routine.
|
||||
sys.spindle_stop_ovr = SPINDLE_STOP_OVR_DISABLED;
|
||||
#ifndef PARKING_ENABLE
|
||||
spindle_set_state(SPINDLE_DISABLE, 0.0); // De-energize
|
||||
spindle->set_state(SPINDLE_DISABLE, 0); // De-energize
|
||||
coolant_set_state(COOLANT_DISABLE); // De-energize
|
||||
#else
|
||||
// Get current position and store restore location and spindle retract waypoint.
|
||||
@@ -599,20 +595,20 @@ static void protocol_exec_rt_suspend() {
|
||||
// NOTE: Clear accessory state after retract and after an aborted restore motion.
|
||||
pl_data->condition = (PL_COND_FLAG_SYSTEM_MOTION | PL_COND_FLAG_NO_FEED_OVERRIDE);
|
||||
pl_data->spindle_speed = 0.0;
|
||||
spindle_set_state(SPINDLE_DISABLE, 0.0); // De-energize
|
||||
coolant_set_state(COOLANT_DISABLE); // De-energize
|
||||
// Execute fast parking retract motion to parking target location.
|
||||
spindle->set_state((SPINDLE_DISABLE, 0); // De-energize
|
||||
coolant_set_state(COOLANT_DISABLE); // De-energize
|
||||
// Execute fast parking retract motion to parking target location.
|
||||
if (parking_target[PARKING_AXIS] < PARKING_TARGET) {
|
||||
parking_target[PARKING_AXIS] = PARKING_TARGET;
|
||||
parking_target[PARKING_AXIS] = PARKING_TARGET;
|
||||
pl_data->feed_rate = PARKING_RATE;
|
||||
mc_parking_motion(parking_target, pl_data);
|
||||
}
|
||||
} else {
|
||||
// Parking motion not possible. Just disable the spindle and coolant.
|
||||
// NOTE: Laser mode does not start a parking motion to ensure the laser stops immediately.
|
||||
spindle_set_state(SPINDLE_DISABLE, 0.0); // De-energize
|
||||
coolant_set_state(COOLANT_DISABLE); // De-energize
|
||||
}
|
||||
->set_state((SPINDLE_DISABLE, 0.0); // De-energize
|
||||
coolant_set_state(COOLANT_DISABLE); // De-energize
|
||||
}
|
||||
#endif
|
||||
sys.suspend &= ~(SUSPEND_RESTART_RETRACT);
|
||||
sys.suspend |= SUSPEND_RETRACT_COMPLETE;
|
||||
@@ -620,7 +616,7 @@ static void protocol_exec_rt_suspend() {
|
||||
if (sys.state == STATE_SLEEP) {
|
||||
report_feedback_message(MESSAGE_SLEEP_MODE);
|
||||
// Spindle and coolant should already be stopped, but do it again just to be sure.
|
||||
spindle_set_state(SPINDLE_DISABLE, 0.0); // De-energize
|
||||
spindle->set_state(SPINDLE_DISABLE, 0); // De-energize
|
||||
coolant_set_state(COOLANT_DISABLE); // De-energize
|
||||
st_go_idle(); // Disable steppers
|
||||
while (!(sys.abort)) protocol_exec_rt_system(); // Do nothing until reset.
|
||||
@@ -657,9 +653,9 @@ 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);
|
||||
spindle->set_state((restore_condition & (PL_COND_FLAG_SPINDLE_CW | PL_COND_FLAG_SPINDLE_CCW)), (uint32_t)restore_spindle_speed);
|
||||
delay_sec(SAFETY_DOOR_SPINDLE_DELAY, DELAY_MODE_SYS_SUSPEND);
|
||||
}
|
||||
}
|
||||
@@ -705,7 +701,7 @@ static void protocol_exec_rt_suspend() {
|
||||
// Handles beginning of spindle stop
|
||||
if (sys.spindle_stop_ovr & SPINDLE_STOP_OVR_INITIATE) {
|
||||
if (gc_state.modal.spindle != SPINDLE_DISABLE) {
|
||||
spindle_set_state(SPINDLE_DISABLE, 0.0); // De-energize
|
||||
spindle->set_state(SPINDLE_DISABLE, 0); // De-energize
|
||||
sys.spindle_stop_ovr = SPINDLE_STOP_OVR_ENABLED; // Set stop override state to enabled, if de-energized.
|
||||
} else {
|
||||
sys.spindle_stop_ovr = SPINDLE_STOP_OVR_DISABLED; // Clear stop override state
|
||||
@@ -716,9 +712,9 @@ 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);
|
||||
spindle->set_state((restore_condition & (PL_COND_FLAG_SPINDLE_CW | PL_COND_FLAG_SPINDLE_CCW)), (uint32_t)restore_spindle_speed);
|
||||
}
|
||||
if (sys.spindle_stop_ovr & SPINDLE_STOP_OVR_RESTORE_CYCLE) {
|
||||
system_set_exec_state_flag(EXEC_CYCLE_START); // Set to resume program.
|
||||
@@ -727,10 +723,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)) {
|
||||
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);
|
||||
// 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)), (uint32_t)restore_spindle_speed);
|
||||
bit_false(sys.step_control, STEP_CONTROL_UPDATE_SPINDLE_RPM);
|
||||
}
|
||||
}
|
||||
}
|
||||
|
@@ -97,7 +97,7 @@ void grbl_sendf(uint8_t client, const char* format, ...) {
|
||||
void grbl_msg_sendf(uint8_t client, uint8_t level, const char* format, ...) {
|
||||
if (client == CLIENT_INPUT) return;
|
||||
if (level > GRBL_MSG_LEVEL) return;
|
||||
char loc_buf[64];
|
||||
char loc_buf[100];
|
||||
char* temp = loc_buf;
|
||||
va_list arg;
|
||||
va_list copy;
|
||||
@@ -113,7 +113,7 @@ void grbl_msg_sendf(uint8_t client, uint8_t level, const char* format, ...) {
|
||||
len = vsnprintf(temp, len + 1, format, arg);
|
||||
grbl_sendf(client, "[MSG:%s]\r\n", temp);
|
||||
va_end(arg);
|
||||
if (len > 64)
|
||||
if (len > 100)
|
||||
delete[] temp;
|
||||
}
|
||||
|
||||
@@ -308,11 +308,8 @@ void report_grbl_settings(uint8_t client, uint8_t show_extended) {
|
||||
sprintf(setting, "$27=%4.3f\r\n", settings.homing_pulloff); strcat(rpt, setting);
|
||||
sprintf(setting, "$30=%4.3f\r\n", settings.rpm_max); strcat(rpt, setting);
|
||||
sprintf(setting, "$31=%4.3f\r\n", settings.rpm_min); strcat(rpt, setting);
|
||||
#ifdef VARIABLE_SPINDLE
|
||||
sprintf(setting, "$32=%d\r\n", bit_istrue(settings.flags, BITFLAG_LASER_MODE)); strcat(rpt, setting);
|
||||
#else
|
||||
strcat(rpt, "$32=0\r\n");
|
||||
#endif
|
||||
|
||||
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);
|
||||
@@ -471,10 +468,8 @@ void report_gcode_modes(uint8_t client) {
|
||||
else
|
||||
sprintf(temp, " F%.0f", gc_state.feed_rate);
|
||||
strcat(modes_rpt, temp);
|
||||
#ifdef VARIABLE_SPINDLE
|
||||
sprintf(temp, " S%4.3f", gc_state.spindle_speed);
|
||||
strcat(modes_rpt, temp);
|
||||
#endif
|
||||
strcat(modes_rpt, "]\r\n");
|
||||
grbl_send(client, modes_rpt);
|
||||
}
|
||||
@@ -497,12 +492,8 @@ void report_build_info(char* line, uint8_t client) {
|
||||
strcpy(build_info, "[VER:" GRBL_VERSION "." GRBL_VERSION_BUILD ":");
|
||||
strcat(build_info, line);
|
||||
strcat(build_info, "]\r\n[OPT:");
|
||||
#ifdef VARIABLE_SPINDLE
|
||||
strcat(build_info, "V");
|
||||
#endif
|
||||
#ifdef USE_LINE_NUMBERS
|
||||
strcat(build_info, "V"); // variable spindle..always on now
|
||||
strcat(build_info, "N");
|
||||
#endif
|
||||
#ifdef COOLANT_MIST_PIN
|
||||
strcat(build_info, "M"); // TODO Need to deal with M8...it could be disabled
|
||||
#endif
|
||||
@@ -558,6 +549,7 @@ void report_build_info(char* line, uint8_t client) {
|
||||
// These will likely have a comma delimiter to separate them.
|
||||
strcat(build_info, "]\r\n");
|
||||
grbl_send(client, build_info); // ok to send to all
|
||||
report_machine_type(client);
|
||||
#if defined (ENABLE_WIFI)
|
||||
grbl_send(client, (char*)wifi_config.info());
|
||||
#endif
|
||||
@@ -679,19 +671,11 @@ void report_realtime_status(uint8_t client) {
|
||||
#endif
|
||||
// Report realtime feed speed
|
||||
#ifdef REPORT_FIELD_CURRENT_FEED_SPEED
|
||||
#ifdef VARIABLE_SPINDLE
|
||||
if (bit_istrue(settings.flags, BITFLAG_REPORT_INCHES))
|
||||
sprintf(temp, "|FS:%.1f,%.0f", st_get_realtime_rate(), sys.spindle_speed / MM_PER_INCH);
|
||||
sprintf(temp, "|FS:%.1f,%d", st_get_realtime_rate()/ MM_PER_INCH, sys.spindle_speed);
|
||||
else
|
||||
sprintf(temp, "|FS:%.0f,%.0f", st_get_realtime_rate(), sys.spindle_speed);
|
||||
sprintf(temp, "|FS:%.0f,%d", st_get_realtime_rate(), sys.spindle_speed);
|
||||
strcat(status, temp);
|
||||
#else
|
||||
if (bit_istrue(settings.flags, BITFLAG_REPORT_INCHES))
|
||||
sprintf(temp, "|F:%.1f", st_get_realtime_rate() / MM_PER_INCH);
|
||||
else
|
||||
sprintf(temp, "|F:%.0f", st_get_realtime_rate());
|
||||
strcat(status, temp);
|
||||
#endif
|
||||
#endif
|
||||
#ifdef REPORT_FIELD_PIN_STATE
|
||||
uint8_t lim_pin_state = limits_get_state();
|
||||
@@ -744,7 +728,7 @@ void report_realtime_status(uint8_t client) {
|
||||
} else sys.report_ovr_counter = (REPORT_OVR_REFRESH_IDLE_COUNT - 1);
|
||||
sprintf(temp, "|Ov:%d,%d,%d", sys.f_override, sys.r_override, sys.spindle_speed_ovr);
|
||||
strcat(status, temp);
|
||||
uint8_t sp_state = spindle_get_state();
|
||||
uint8_t sp_state = spindle->get_state();
|
||||
uint8_t cl_state = coolant_get_state();
|
||||
if (sp_state || cl_state) {
|
||||
strcat(status, "|A:");
|
||||
@@ -790,4 +774,54 @@ void report_gcode_comment(char* comment) {
|
||||
msg[index - offset] = 0; // null terminate
|
||||
grbl_msg_sendf(CLIENT_SERIAL, MSG_LEVEL_INFO, "GCode Comment...%s", msg);
|
||||
}
|
||||
}
|
||||
|
||||
void report_machine_type(uint8_t client) {
|
||||
grbl_msg_sendf(client, MSG_LEVEL_INFO, "Using machine:%s", MACHINE_NAME);
|
||||
}
|
||||
|
||||
|
||||
/*
|
||||
Print a message in hex format
|
||||
Ex: report_hex_msg(msg, "Rx:", 6);
|
||||
Would would print something like ... [MSG Rx: 0x01 0x03 0x01 0x08 0x31 0xbf]
|
||||
*/
|
||||
void report_hex_msg(char* buf, const char* prefix, int len) {
|
||||
char report[200];
|
||||
char temp[20];
|
||||
sprintf(report, "%s", prefix);
|
||||
for (int i = 0; i < len; i++) {
|
||||
sprintf(temp, " 0x%02X", buf[i]);
|
||||
strcat(report, temp);
|
||||
}
|
||||
|
||||
grbl_msg_sendf(CLIENT_SERIAL, MSG_LEVEL_INFO, "%s", report);
|
||||
|
||||
}
|
||||
|
||||
char report_get_axis_letter(uint8_t axis) {
|
||||
switch (axis) {
|
||||
case X_AXIS:
|
||||
return 'X';
|
||||
case Y_AXIS:
|
||||
return 'Y';
|
||||
case Z_AXIS:
|
||||
return 'Z';
|
||||
case A_AXIS:
|
||||
return 'A';
|
||||
case B_AXIS:
|
||||
return 'B';
|
||||
case C_AXIS:
|
||||
return 'C';
|
||||
default:
|
||||
return '?';
|
||||
}
|
||||
}
|
||||
|
||||
// used to report the pin nhumber or -1 for undefined.
|
||||
int16_t report_pin_number(uint8_t pin_number) {
|
||||
if (pin_number == UNDEFINED_PIN)
|
||||
return -1;
|
||||
else
|
||||
return (int16_t)pin_number;
|
||||
}
|
@@ -170,6 +170,11 @@ void report_gcode_comment(char* comment);
|
||||
void report_realtime_debug();
|
||||
#endif
|
||||
|
||||
void report_machine_type(uint8_t client);
|
||||
|
||||
void report_hex_msg(char* buf, const char *prefix, int len);
|
||||
|
||||
char report_get_axis_letter(uint8_t axis);
|
||||
int16_t report_pin_number(uint8_t pin_number);
|
||||
|
||||
#endif
|
||||
|
@@ -1,5 +1,3 @@
|
||||
#include "grbl.h"
|
||||
|
||||
/*
|
||||
stepper.c - stepper motor driver: executes motion plans using stepper motors
|
||||
Part of Grbl
|
||||
@@ -37,9 +35,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 +52,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 +139,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 +278,18 @@ 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_rpm(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);
|
||||
if (st.exec_block->is_pwm_rate_adjusted) {
|
||||
spindle->set_rpm(0);
|
||||
}
|
||||
}
|
||||
#endif
|
||||
|
||||
system_set_exec_state_flag(EXEC_CYCLE_STOP); // Flag main program for cycle end
|
||||
return; // Nothing to do but exit.
|
||||
}
|
||||
@@ -688,37 +681,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
|
||||
}
|
||||
@@ -1010,18 +1003,16 @@ 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 (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;
|
||||
}
|
||||
}
|
||||
#endif
|
||||
|
||||
}
|
||||
/* ---------------------------------------------------------------------------------
|
||||
Compute the velocity profile of a new planner block based on its entry and exit
|
||||
@@ -1107,9 +1098,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];
|
||||
@@ -1213,29 +1204,32 @@ 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.
|
||||
if (st_prep_block->is_pwm_rate_adjusted)
|
||||
if (st_prep_block->is_pwm_rate_adjusted) {
|
||||
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)
|
||||
// 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 = 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
|
||||
@@ -1404,4 +1398,4 @@ bool get_stepper_disable() { // returns true if steppers are disabled
|
||||
disabled = !disabled; // Apply pin invert.
|
||||
}
|
||||
return disabled;
|
||||
}
|
||||
}
|
||||
|
Reference in New Issue
Block a user