1
0
mirror of https://github.com/bdring/Grbl_Esp32.git synced 2025-09-01 10:23:19 +02:00

Add Spindle Classes

This commit is contained in:
bdring
2020-05-07 17:48:45 -05:00
parent c6dd494db1
commit 8b44c6f7ce
35 changed files with 140 additions and 491 deletions

View File

@@ -21,6 +21,8 @@
#include "grbl.h"
#include "WiFi.h"
#include "Spindles/SpindleClass.cpp"
// Declare system global variable structure
system_t sys;
int32_t sys_position[N_AXIS]; // Real-time machine (aka home) position vector in steps.
@@ -34,6 +36,8 @@ volatile uint8_t sys_rt_exec_accessory_override; // Global realtime executor bit
volatile uint8_t sys_rt_exec_debug;
#endif
Spindle *spindle;
void setup() {
@@ -52,7 +56,7 @@ void setup() {
#else
#define MACHINE_STRING MACHINE_NAME
#endif
grbl_msg_sendf(CLIENT_SERIAL, MSG_LEVEL_INFO, "Using machine:%s", MACHINE_STRING);
report_machine_type(CLIENT_SERIAL);
#endif
settings_init(); // Load Grbl settings from EEPROM
stepper_init(); // Configure stepper pins and interrupt timers
@@ -113,7 +117,7 @@ void loop() {
// Reset Grbl primary systems.
serial_reset_read_buffer(CLIENT_ALL); // Clear serial read buffer
gc_init(); // Set g-code parser to default state
spindle_init();
spindle_select(SPINDLE_TYPE);
coolant_init();
limits_init();
probe_init();

View File

@@ -41,7 +41,8 @@
#define STEPPERS_DISABLE_PIN GPIO_NUM_13
#define SPINDLE_TYPE SPINDLE_TYPE_PWM
#define SPINDLE_PWM_PIN GPIO_NUM_17 // labeled SpinPWM
#define SPINDLE_OUTPUT_PIN GPIO_NUM_17 // labeled SpinPWM
#define SPINDLE_ENABLE_PIN GPIO_NUM_22 // labeled SpinEnbl
#define COOLANT_MIST_PIN GPIO_NUM_21 // labeled Mist

View File

@@ -33,7 +33,7 @@
#define Y2_DIRECTION_PIN GPIO_NUM_33 /* labeled Z */
#define SPINDLE_TYPE SPINDLE_TYPE_PWM
#define SPINDLE_PWM_PIN GPIO_NUM_2
#define SPINDLE_OUTPUT_PIN GPIO_NUM_2
#define SPINDLE_ENABLE_PIN GPIO_NUM_22
#define LIMIT_MASK B11

View File

@@ -67,10 +67,6 @@
#define REED_SW_PIN GPIO_NUM_17
#define LIMIT_MASK 0
#ifdef IGNORE_CONTROL_PINS // maybe set in config.h
#undef IGNORE_CONTROL_PINS
#endif
#ifndef ENABLE_CONTROL_SW_DEBOUNCE
#define ENABLE_CONTROL_SW_DEBOUNCE
#endif

View File

@@ -40,7 +40,8 @@
#define STEPPERS_DISABLE_PIN GPIO_NUM_12
#define SPINDLE_TYPE SPINDLE_TYPE_PWM
#define SPINDLE_PWM_PIN GPIO_NUM_19
#define SPINDLE_OUTPUT_PIN GPIO_NUM_19
#define SPINDLE_DIR_PIN GPIO_NUM_18
#define COOLANT_FLOOD_PIN GPIO_NUM_34
@@ -53,7 +54,6 @@
#define PROBE_PIN GPIO_NUM_39
// comment out #define IGNORE_CONTROL_PINS in config.h to use control pins
#define CONTROL_RESET_PIN GPIO_NUM_2
#define CONTROL_FEED_HOLD_PIN GPIO_NUM_4
#define CONTROL_CYCLE_START_PIN GPIO_NUM_35 // ESP32 needs external pullup

View File

@@ -50,9 +50,11 @@
//#define USE_SPINDLE_RELAY
#ifdef USE_SPINDLE_RELAY
#define SPINDLE_PWM_PIN GPIO_NUM_2
#define SPINDLE_TYPE SPINDLE_TYPE_PWM
#define SPINDLE_OUTPUT_PIN GPIO_NUM_2
#else
#define SPINDLE_PWM_PIN GPIO_NUM_16
#define SPINDLE_TYPE SPINDLE_TYPE_RELAY
#define SPINDLE_OUTPUT_PIN GPIO_NUM_16
#define SPINDLE_ENABLE_PIN GPIO_NUM_32
#endif
@@ -78,7 +80,6 @@
#define INVERT_CONTROL_PIN_MASK B1110
// Note: check the #define IGNORE_CONTROL_PINS is the way you want in config.h
#define CONTROL_RESET_PIN GPIO_NUM_34 // needs external pullup
#define CONTROL_FEED_HOLD_PIN GPIO_NUM_36 // needs external pullup
#define CONTROL_CYCLE_START_PIN GPIO_NUM_39 // needs external pullup

View File

@@ -51,10 +51,6 @@
#define SERVO_Z_HOME_POS SERVO_Z_RANGE_MAX // move to max during homing
#define SERVO_Z_MPOS false // will not use mpos, uses work coordinates
#ifndef IGNORE_CONTROL_PINS // maybe set in config.h
#define IGNORE_CONTROL_PINS
#endif
// redefine some stuff from config.h
#ifdef HOMING_CYCLE_0
#undef HOMING_CYCLE_0
@@ -74,6 +70,8 @@
#define SERVO_PEN_PIN GPIO_NUM_27
#define SPINDLE_TYPE SPINDLE_TYPE_NONE
// defaults
#define DEFAULT_STEP_PULSE_MICROSECONDS 3
#define DEFAULT_STEPPER_IDLE_LOCK_TIME 255 // stay on

View File

@@ -51,10 +51,11 @@
#ifdef USE_SPINDLE_RELAY
#define SPINDLE_TYPE SPINDLE_TYPE_RELAY
#define SPINDLE_PWM_PIN GPIO_NUM_17
#define SPINDLE_OUTPUT_PIN GPIO_NUM_17
#else
#define SPINDLE_TYPE SPINDLE_TYPE_PWM
#define SPINDLE_PWM_PIN GPIO_NUM_16
#define SPINDLE_OUTPUT_PIN GPIO_NUM_16
#define SPINDLE_ENABLE_PIN GPIO_NUM_32
#endif
@@ -78,15 +79,6 @@
#define INVERT_CONTROL_PIN_MASK B1110
// Note: default is #define IGNORE_CONTROL_PINS in config.h
// uncomment to these lines to use them
/*
#ifdef IGNORE_CONTROL_PINS
#undef IGNORE_CONTROL_PINS
#endif
*/
#define CONTROL_RESET_PIN GPIO_NUM_34 // needs external pullup
#define CONTROL_FEED_HOLD_PIN GPIO_NUM_36 // needs external pullup
#define CONTROL_CYCLE_START_PIN GPIO_NUM_39 // needs external pullup

View File

@@ -52,10 +52,11 @@
#ifdef USE_SPINDLE_RELAY
#define SPINDLE_TYPE SPINDLE_TYPE_RELAY
#define SPINDLE_PWM_PIN GPIO_NUM_2
#define SPINDLE_OUTPUT_PIN GPIO_NUM_2
#else
#define SPINDLE_TYPE SPINDLE_TYPE_PWM
#define SPINDLE_PWM_PIN GPIO_NUM_16
#define SPINDLE_OUTPUT_PIN GPIO_NUM_16
#define SPINDLE_ENABLE_PIN GPIO_NUM_32
#endif
@@ -85,14 +86,6 @@
#define INVERT_CONTROL_PIN_MASK B1110
// Note: default is #define IGNORE_CONTROL_PINS in config.h
// uncomment to these lines to use them
/*
#ifdef IGNORE_CONTROL_PINS
#undef IGNORE_CONTROL_PINS
#endif
*/
#define CONTROL_RESET_PIN GPIO_NUM_34 // needs external pullup
#define CONTROL_FEED_HOLD_PIN GPIO_NUM_36 // needs external pullup

View File

@@ -49,10 +49,6 @@
#define Y_LIMIT_PIN GPIO_NUM_4
#define LIMIT_MASK B11
// If SPINDLE_PWM_PIN is commented out, this frees up the pin, but Grbl will still
// use a virtual spindle. Do not comment out the other parameters for the spindle.
//#define SPINDLE_PWM_PIN GPIO_NUM_17 // Laser PWM
#define USING_SERVO // uncomment to use this feature
//#define USING_SOLENOID // uncomment to use this feature
@@ -68,6 +64,8 @@
#define SOLENOID_PEN_PIN GPIO_NUM_16
#endif
#define SPINDLE_TYPE SPINDLE_TYPE_NONE
// defaults
#define DEFAULT_STEP_PULSE_MICROSECONDS 3
#define DEFAULT_STEPPER_IDLE_LOCK_TIME 250 // stay on

View File

@@ -57,9 +57,7 @@
#define X_LIMIT_PIN GPIO_NUM_4
#define LIMIT_MASK B1
#ifdef IGNORE_CONTROL_PINS // maybe set in config.h
#undef IGNORE_CONTROL_PINS
#endif
#define SPINDLE_TYPE SPINDLE_TYPE_NONE
#ifndef ENABLE_CONTROL_SW_DEBOUNCE
#define ENABLE_CONTROL_SW_DEBOUNCE

View File

@@ -79,7 +79,7 @@
#define COOLANT_MIST_PIN GPIO_NUM_21
#define SPINDLE_TYPE SPINDLE_TYPE_PWM
#define SPINDLE_PWM_PIN GPIO_NUM_25
#define SPINDLE_OUTPUT_PIN GPIO_NUM_25
#define SPINDLE_ENABLE_PIN GPIO_NUM_4
// Relay operation

View File

@@ -64,7 +64,7 @@
#define COOLANT_MIST_PIN GPIO_NUM_21
#define SPINDLE_TYPE SPINDLE_TYPE_PWM
#define SPINDLE_PWM_PIN GPIO_NUM_25
#define SPINDLE_OUTPUT_PIN GPIO_NUM_25
#define SPINDLE_ENABLE_PIN GPIO_NUM_4
// Relay operation

View File

@@ -70,15 +70,20 @@
// Turn on with M7 and off with M9
#define COOLANT_MIST_PIN GPIO_NUM_21
#define SPINDLE_PWM_PIN GPIO_NUM_25
#define SPINDLE_OUTPUT_PIN GPIO_NUM_25
#define SPINDLE_ENABLE_PIN GPIO_NUM_4
// Relay operation
// Install Jumper near relay
// For spindle Use max RPM of 1
// For PWM remove jumper and set MAX RPM to something higher ($30 setting)
// For PWM remove jumper to prevent relay damage
// Interlock jumper along top edge needs to be installed for both versions
#define DEFAULT_SPINDLE_RPM_MAX 1 // Should be 1 for relay operation
#define USE_RELAY // comment out to use PWM
#ifdef USE_RELAY
#define SPINDLE_TYPE SPINDLE_TYPE_RELAY
#else
#define SPINDLE_TYPE SPINDLE_TYPE_PWM
#endif
#define PROBE_PIN GPIO_NUM_22

View File

@@ -102,7 +102,7 @@
// machine does not support one of these features, you can leave
// the corresponding pin undefined.
// #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 COOLANT_MIST_PIN GPIO_NUM_21 // labeled Mist
// #define COOLANT_FLOOD_PIN GPIO_NUM_25 // labeled Flood
@@ -175,11 +175,6 @@
// === Control Pins
// The control pins with names that begin with CONTROL_ are
// ignored by default, to avoid noise problems. To make them
// work, you must undefine IGNORE_CONTROL_PINS
// #undef IGNORE_CONTROL_PINS
// If some of the control pin switches are normally closed
// (the default is normally open), you can invert some of them
// with INVERT_CONTROL_PIN_MASK. The bits in the mask are

View File

@@ -70,8 +70,9 @@
#define SERVO_Z_HOME_POS SERVO_Z_RANGE_MAX // move to max during homing
#define SERVO_Z_MPOS false // will not use mpos, uses work coordinates
#else
#define SPINDLE_TYPE SPINDLE_TYPE_PWM
#define SPINDLE_PWM_PIN GPIO_NUM_27
#define SPINDLE_OUTPUT_PIN GPIO_NUM_27
#endif
// #define X_LIMIT_PIN See version section at beginning of file

View File

@@ -32,8 +32,6 @@
*/
#include "SpindleClass.h"
#include "SpindleClass.h"
// don't change these
#define BESC_PWM_FREQ 50.0f // Hz
#define BESC_PWM_BIT_PRECISION 16 // bits

View File

@@ -76,11 +76,6 @@ Some features should not be changed. See notes below.
// For example B1101 will invert the function of the Reset pin.
#define INVERT_CONTROL_PIN_MASK B1111
// This allows control pins to be ignored.
// Since these are typically used on the pins that don't have pullups, they will float and cause
// problems if not externally pulled up. Ignoring will always return not activated when read.
#define IGNORE_CONTROL_PINS
#define ENABLE_CONTROL_SW_DEBOUNCE // Default disabled. Uncomment to enable.
#define CONTROL_SW_DEBOUNCE_PERIOD 32 // in milliseconds default 32 microseconds
@@ -205,7 +200,7 @@ Some features should not be changed. See notes below.
#define CMD_RAPID_OVR_LOW 0x97
// #define CMD_RAPID_OVR_EXTRA_LOW 0x98 // *NOT SUPPORTED*
#define CMD_SPINDLE_OVR_RESET 0x99 // Restores spindle override value to 100%.
#define CMD_SPINDLE_OVR_COARSE_PLUS 0x9A
#define CMD_SPINDLE_OVR_COARSE_PLUS 0x9A // 154
#define CMD_SPINDLE_OVR_COARSE_MINUS 0x9B
#define CMD_SPINDLE_OVR_FINE_PLUS 0x9C
#define CMD_SPINDLE_OVR_FINE_MINUS 0x9D
@@ -437,12 +432,6 @@ Some features should not be changed. See notes below.
// tool length offset value is subtracted from the current location.
#define TOOL_LENGTH_OFFSET_AXIS Z_AXIS // Default z-axis. Valid values are X_AXIS, Y_AXIS, or Z_AXIS.
// Enables variable spindle output voltage for different RPM values. On the Arduino Uno, the spindle
// enable pin will output 5V for maximum RPM with 256 intermediate levels and 0V when disabled.
// NOTE: IMPORTANT for Arduino Unos! When enabled, the Z-limit pin D11 and spindle enable pin D12 switch!
// The hardware PWM output on pin D11 is required for variable spindle output voltages.
#define VARIABLE_SPINDLE // Default enabled. Comment to disable.
// Alters the behavior of the spindle enable pin. By default Grbl will not disable the enable pin if
// spindle speed is zero and M3/4 is active, but still sets the PWM output to zero. This allows the users
// to know if the spindle is active and use it as an additional control input.

View File

@@ -114,7 +114,18 @@
#define DEFAULT_HOMING_PULLOFF 1.0 // $27 mm
#endif
// ======== sPINDLE STUFF ====================
// ======== SPINDLE STUFF ====================
#ifndef DEFAULT_SPINDLE_RPM_MIN // $31
#define DEFAULT_SPINDLE_RPM_MIN 0.0 // rpm
#endif
#ifndef DEFAULT_LASER_MODE // $32
#define DEFAULT_LASER_MODE 0 // false
#endif
#ifndef DEFAULT_SPINDLE_RPM_MAX // $30
#define DEFAULT_SPINDLE_RPM_MAX 1000.0 // rpm
#endif
#ifndef DEFAULT_SPINDLE_FREQ
#define DEFAULT_SPINDLE_FREQ 5000.0 // $33 Hz (extended set)
@@ -132,20 +143,7 @@
#define DEFAULT_SPINDLE_MAX_VALUE 100.0 // $36 Percent of full period (extended set)
#endif
#ifndef DEFAULT_SPINDLE_RPM_MAX
#define DEFAULT_SPINDLE_RPM_MAX 1000.0 // rpm
#endif
#ifndef DEFAULT_SPINDLE_RPM_MIN
#define DEFAULT_SPINDLE_RPM_MIN 0.0 // rpm
#endif
#ifndef DEFAULT_LASER_MODE
#define DEFAULT_LASER_MODE 0 // false
#endif
// user settings
// ================ user settings =====================
#ifndef DEFAULT_USER_INT_80
#define DEFAULT_USER_INT_80 0 // $80 User integer setting
#endif

View File

@@ -301,14 +301,10 @@ uint8_t gc_execute_line(char* line, uint8_t client) {
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;
@@ -1085,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->spindle_sync(gc_state.modal.spindle, 0);
else
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.
}

View File

@@ -18,9 +18,11 @@
along with Grbl. If not, see <http://www.gnu.org/licenses/>.
*/
#pragma once
// Grbl versioning system
#define GRBL_VERSION "1.1f"
#define GRBL_VERSION_BUILD "20200504"
#define GRBL_VERSION "1.2a"
#define GRBL_VERSION_BUILD "20200428"
//#include <sdkconfig.h>
#include <Arduino.h>
@@ -28,6 +30,7 @@
#include <driver/rmt.h>
#include <esp_task_wdt.h>
#include <freertos/task.h>
#include <Preferences.h>
#include "driver/timer.h"
@@ -51,7 +54,7 @@
#include "protocol.h"
#include "report.h"
#include "serial.h"
#include "spindle_control.h"
#include "Spindles/SpindleClass.h"
#include "stepper.h"
#include "jog.h"
#include "inputbuffer.h"

View File

@@ -16,18 +16,12 @@ PWM
// !!! For initial testing, start with test_drive.h which disables
// all I/O pins
#include "Machines/test_drive.h"
#include "Machines/3axis_v4.h"
// !!! For actual use, change the line above to select a board
// from Machines/, for example:
// #include "Machines/3axis_v4.h"
// Some configurations use two files, the first establishing a base
// configuration and the second providing additional customization,
// for example:
// #include "Machines/3axis_v4.h"
// #include "Machines/add_esc_spindle.h"
// === OEM Single File Configuration Option
// OEMs that wish to publish source code that is configured for a
// specific machine may put all of their configuration definitions
@@ -57,14 +51,6 @@ PWM
#include MACHINE_PATHNAME_QUOTED(MACHINE_FILENAME)
// You can choose two-file configurations by also defining MACHINE_FILENAME2,
// for example:
// $env:PLATFORMIO_BUILD_FLAGS='-DMACHINE_FILENAME=3axis_v4.h -DMACHINE_FILENAME2=add_esc_spindle.h'; platformio run
#ifdef MACHINE_FILENAME2
#include MACHINE_PATHNAME_QUOTED(MACHINE_FILENAME2)
#endif
#endif // MACHINE_FILENAME
#endif // _machine_h

View File

@@ -1,12 +1,10 @@
#ifndef _machine_common_h
#define _machine_common_h
#ifndef SPINDLE_PWM_BIT_PRECISION
#define SPINDLE_PWM_BIT_PRECISION 8
#ifndef SPINDLE_TYPE
#define SPINDLE_TYPE SPINDLE_TYPE_PWM
#endif
#define SPINDLE_PWM_MAX_VALUE ((1<<SPINDLE_PWM_BIT_PRECISION) - 1)
// Grbl setting that are common to all machines
// It should not be necessary to change anything herein

View File

@@ -424,7 +424,7 @@ void mc_reset() {
if (bit_isfalse(sys_rt_exec_state, EXEC_RESET)) {
system_set_exec_state_flag(EXEC_RESET);
// Kill spindle and coolant.
spindle_stop();
spindle->stop();
coolant_stop();
// turn off all digital I/O
sys_io_control(0xFF, false);

View File

@@ -284,9 +284,8 @@ uint8_t plan_buffer_line(float* target, plan_line_data_t* pl_data) {
plan_block_t* block = &block_buffer[block_buffer_head];
memset(block, 0, sizeof(plan_block_t)); // Zero all block values.
block->condition = pl_data->condition;
#ifdef VARIABLE_SPINDLE
block->spindle_speed = pl_data->spindle_speed;
#endif
#ifdef USE_LINE_NUMBERS
block->line_number = pl_data->line_number;
#endif

View File

@@ -81,7 +81,7 @@ typedef struct {
float rapid_rate; // Axis-limit adjusted maximum rate for this block direction in (mm/min)
float programmed_rate; // Programmed rate of this block (mm/min).
//#ifdef VARIABLE_SPINDLE
// Stored spindle speed data used by spindle overrides and resuming methods.
float spindle_speed; // Block spindle speed. Copied from pl_line_data.
//#endif

View File

@@ -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.
@@ -603,16 +599,16 @@ static void protocol_exec_rt_suspend() {
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;
@@ -621,7 +617,6 @@ static void protocol_exec_rt_suspend() {
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); // 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.
@@ -658,7 +653,7 @@ static void protocol_exec_rt_suspend() {
if (bit_isfalse(sys.suspend, SUSPEND_RESTART_RETRACT)) {
if (bit_istrue(settings.flags, BITFLAG_LASER_MODE)) {
// When in laser mode, ignore spindle spin-up delay. Set to turn on laser when cycle starts.
bit_true(sys.step_control, STEP_CONTROL_UPDATE_SPINDLE_PWM);
bit_true(sys.step_control, STEP_CONTROL_UPDATE_SPINDLE_RPM);
} else {
spindle->set_state((restore_condition & (PL_COND_FLAG_SPINDLE_CW | PL_COND_FLAG_SPINDLE_CCW)), (uint32_t)restore_spindle_speed);
delay_sec(SAFETY_DOOR_SPINDLE_DELAY, DELAY_MODE_SYS_SUSPEND);
@@ -707,7 +702,6 @@ static void protocol_exec_rt_suspend() {
if (sys.spindle_stop_ovr & SPINDLE_STOP_OVR_INITIATE) {
if (gc_state.modal.spindle != SPINDLE_DISABLE) {
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
@@ -718,7 +712,7 @@ static void protocol_exec_rt_suspend() {
report_feedback_message(MESSAGE_SPINDLE_RESTORE);
if (bit_istrue(settings.flags, BITFLAG_LASER_MODE)) {
// When in laser mode, ignore spindle spin-up delay. Set to turn on laser when cycle starts.
bit_true(sys.step_control, STEP_CONTROL_UPDATE_SPINDLE_PWM);
bit_true(sys.step_control, STEP_CONTROL_UPDATE_SPINDLE_RPM);
} else
spindle->set_state((restore_condition & (PL_COND_FLAG_SPINDLE_CW | PL_COND_FLAG_SPINDLE_CCW)), (uint32_t)restore_spindle_speed);
}

View File

@@ -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,%d", st_get_realtime_rate()/ MM_PER_INCH, sys.spindle_speed);
else
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:");

View File

@@ -170,6 +170,8 @@ 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);

View File

@@ -40,7 +40,7 @@ void settings_init() {
if (!read_global_settings()) {
report_status_message(STATUS_SETTING_READ_FAIL, CLIENT_SERIAL);
settings_restore(SETTINGS_RESTORE_ALL); // Force restore all EEPROM data.
report_grbl_settings(CLIENT_SERIAL, false); // only the serial could be working at this point
report_grbl_settings(CLIENT_SERIAL, false);
}
}
@@ -64,12 +64,14 @@ void settings_restore(uint8_t restore_flag) {
settings.status_report_mask = DEFAULT_STATUS_REPORT_MASK;
settings.junction_deviation = DEFAULT_JUNCTION_DEVIATION;
settings.arc_tolerance = DEFAULT_ARC_TOLERANCE;
settings.rpm_max = DEFAULT_SPINDLE_RPM_MAX;
settings.rpm_min = DEFAULT_SPINDLE_RPM_MIN;
settings.spindle_pwm_freq = DEFAULT_SPINDLE_FREQ; // $33 Hz (extended set)
settings.spindle_pwm_off_value = DEFAULT_SPINDLE_OFF_VALUE; // $34 Percent (extended set)
settings.spindle_pwm_min_value = DEFAULT_SPINDLE_MIN_VALUE; // $35 Percent (extended set)
settings.spindle_pwm_max_value = DEFAULT_SPINDLE_MAX_VALUE; // $36 Percent (extended set)
settings.rpm_max = DEFAULT_SPINDLE_RPM_MAX;
settings.rpm_min = DEFAULT_SPINDLE_RPM_MIN;
settings.homing_dir_mask = DEFAULT_HOMING_DIR_MASK;
settings.homing_feed_rate = DEFAULT_HOMING_FEED_RATE;
settings.homing_seek_rate = DEFAULT_HOMING_SEEK_RATE;
@@ -366,20 +368,19 @@ uint8_t settings_store_global_setting(uint8_t parameter, float value) {
case 25: settings.homing_seek_rate = value; break;
case 26: settings.homing_debounce_delay = int_value; break;
case 27: settings.homing_pulloff = value; break;
case 30: settings.rpm_max = value; spindle_init(); break; // Re-initialize spindle rpm calibration
case 31: settings.rpm_min = value; spindle_init(); break; // Re-initialize spindle rpm calibration
case 30: settings.rpm_max = std::max(value, 1.0f); spindle->init(); break; // Re-initialize spindle rpm calibration (min of 1)
case 31: settings.rpm_min = value; spindle->init(); break; // Re-initialize spindle rpm calibration
case 32:
#ifdef VARIABLE_SPINDLE
if (int_value) settings.flags |= BITFLAG_LASER_MODE;
else settings.flags &= ~BITFLAG_LASER_MODE;
#else
return (STATUS_SETTING_DISABLED_LASER);
#endif
if (int_value)
settings.flags |= BITFLAG_LASER_MODE;
else
settings.flags &= ~BITFLAG_LASER_MODE;
spindle->init(); // update the spindle class
break;
case 33: settings.spindle_pwm_freq = value; spindle_init(); break; // Re-initialize spindle pwm calibration
case 34: settings.spindle_pwm_off_value = value; spindle_init(); break; // Re-initialize spindle pwm calibration
case 35: settings.spindle_pwm_min_value = value; spindle_init(); break; // Re-initialize spindle pwm calibration
case 36: settings.spindle_pwm_max_value = value; spindle_init(); break; // Re-initialize spindle pwm calibration
case 33: settings.spindle_pwm_freq = value; spindle_select(SPINDLE_TYPE); break; // Re-initialize spindle pwm calibration
case 34: settings.spindle_pwm_off_value = value; spindle_select(SPINDLE_TYPE); break; // Re-initialize spindle pwm calibration
case 35: settings.spindle_pwm_min_value = value; spindle_select(SPINDLE_TYPE); break; // Re-initialize spindle pwm calibration
case 36: settings.spindle_pwm_max_value = value; spindle_select(SPINDLE_TYPE); break; // Re-initialize spindle pwm calibration
case 80:
case 81:
case 82:

View File

@@ -1,226 +0,0 @@
/*
spindle_control.cpp - Header for system level commands and real-time processes
Part of Grbl
Copyright (c) 2014-2016 Sungeun K. Jeon for Gnea Research LLC
2018 - 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/>.
*/
#include "grbl.h"
int8_t spindle_pwm_chan_num;
#ifdef SPINDLE_PWM_PIN
static float pwm_gradient; // Precalulated value to speed up rpm to PWM conversions.
uint32_t spindle_pwm_period; // how many counts in 1 period
uint32_t spindle_pwm_off_value;
uint32_t spindle_pwm_min_value;
uint32_t spindle_pwm_max_value;
#endif
void spindle_init() {
#ifdef SPINDLE_PWM_PIN
#ifdef INVERT_SPINDLE_PWM
grbl_msg_sendf(CLIENT_SERIAL, MSG_LEVEL_INFO, "INVERT_SPINDLE_PWM");
#endif
#ifdef INVERT_SPINDLE_ENABLE_PIN
grbl_msg_sendf(CLIENT_SERIAL, MSG_LEVEL_INFO, "INVERT_SPINDLE_ENABLE_PIN");
#endif
// determine how many PWM counts are in eqach PWM cycle
spindle_pwm_period = ((1 << SPINDLE_PWM_BIT_PRECISION) - 1);
if (settings.spindle_pwm_min_value > settings.spindle_pwm_min_value)
grbl_msg_sendf(CLIENT_SERIAL, MSG_LEVEL_INFO, "Warning spindle min pwm is greater than max. Check $35 and $36");
// pre-caculate some PWM count values
spindle_pwm_off_value = (spindle_pwm_period * settings.spindle_pwm_off_value / 100.0);
spindle_pwm_min_value = (spindle_pwm_period * settings.spindle_pwm_min_value / 100.0);
spindle_pwm_max_value = (spindle_pwm_period * settings.spindle_pwm_max_value / 100.0);
// The pwm_gradient is the pwm duty cycle units per rpm
pwm_gradient = (spindle_pwm_max_value - spindle_pwm_min_value) / (settings.rpm_max - settings.rpm_min);
// Use DIR and Enable if pins are defined
#ifdef SPINDLE_ENABLE_PIN
pinMode(SPINDLE_ENABLE_PIN, OUTPUT);
#endif
#ifdef SPINDLE_DIR_PIN
pinMode(SPINDLE_DIR_PIN, OUTPUT);
#endif
// use the LED control feature to setup PWM https://docs.espressif.com/projects/esp-idf/en/latest/api-reference/peripherals/ledc.html
spindle_pwm_chan_num = 0; // spindle always uses channel 0
ledcSetup(spindle_pwm_chan_num, (double)settings.spindle_pwm_freq, SPINDLE_PWM_BIT_PRECISION); // setup the channel
ledcAttachPin(SPINDLE_PWM_PIN, spindle_pwm_chan_num); // attach the PWM to the pin
// Start with spindle off off
spindle_stop();
#endif
}
void spindle_stop() {
spindle_set_enable(false);
#ifdef SPINDLE_PWM_PIN
#ifndef INVERT_SPINDLE_PWM
grbl_analogWrite(spindle_pwm_chan_num, spindle_pwm_off_value);
#else
grbl_analogWrite(spindle_pwm_chan_num, (1 << SPINDLE_PWM_BIT_PRECISION)); // TO DO...wrong for min_pwm
#endif
#endif
}
uint8_t spindle_get_state() { // returns SPINDLE_STATE_DISABLE, SPINDLE_STATE_CW or SPINDLE_STATE_CCW
// TODO Update this when direction and enable pin are added
#ifndef SPINDLE_PWM_PIN
return (SPINDLE_STATE_DISABLE);
#else
if (ledcRead(spindle_pwm_chan_num) == 0) // Check the PWM value
return (SPINDLE_STATE_DISABLE);
else {
#ifdef SPINDLE_DIR_PIN
if (digitalRead(SPINDLE_DIR_PIN))
return (SPINDLE_STATE_CW);
else
return (SPINDLE_STATE_CCW);
#else
return (SPINDLE_STATE_CW);
#endif
}
#endif
}
void spindle_set_speed(uint32_t pwm_value) {
#ifndef SPINDLE_PWM_PIN
//grbl_sendf(CLIENT_SERIAL, "[MSG: set speed...no pin defined]\r\n");
return;
#else
#ifndef SPINDLE_ENABLE_OFF_WITH_ZERO_SPEED
spindle_set_enable(true);
#else
spindle_set_enable(pwm_value != 0);
#endif
#ifndef INVERT_SPINDLE_PWM
grbl_analogWrite(spindle_pwm_chan_num, pwm_value);
#else
grbl_analogWrite(spindle_pwm_chan_num, (1 << SPINDLE_PWM_BIT_PRECISION) - pwm_value);
#endif
#endif
}
uint32_t spindle_compute_pwm_value(float rpm) {
#ifdef SPINDLE_PWM_PIN
uint32_t pwm_value;
rpm *= (0.010 * sys.spindle_speed_ovr); // Scale by spindle speed override value.
// Calculate PWM register value based on rpm max/min settings and programmed rpm.
if ((settings.rpm_min >= settings.rpm_max) || (rpm >= settings.rpm_max)) {
// No PWM range possible. Set simple on/off spindle control pin state.
sys.spindle_speed = settings.rpm_max;
pwm_value = spindle_pwm_max_value;
} else if (rpm <= settings.rpm_min) {
if (rpm == 0.0) { // S0 disables spindle
sys.spindle_speed = 0.0;
pwm_value = spindle_pwm_off_value;
} else { // Set minimum PWM output
sys.spindle_speed = settings.rpm_min;
pwm_value = spindle_pwm_min_value;
}
} else {
// Compute intermediate PWM value with linear spindle speed model.
// NOTE: A nonlinear model could be installed here, if required, but keep it VERY light-weight.
sys.spindle_speed = rpm;
#ifdef ENABLE_PIECEWISE_LINEAR_SPINDLE
pwm_value = piecewise_linear_fit(rpm);
#else
pwm_value = floor((rpm - settings.rpm_min) * pwm_gradient) + spindle_pwm_min_value;
#endif
}
return (pwm_value);
#else
return (0); // no SPINDLE_PWM_PIN
#endif
}
// Called by spindle_set_state() and step segment generator. Keep routine small and efficient.
void spindle_set_state(uint8_t state, float rpm) {
#ifdef SPINDLE_PWM_PIN
if (sys.abort) return; // Block during abort.
if (state == SPINDLE_DISABLE) { // Halt or set spindle direction and rpm.
sys.spindle_speed = 0.0;
spindle_stop();
} else {
// TODO ESP32 Enable and direction control
#ifdef SPINDLE_DIR_PIN
digitalWrite(SPINDLE_DIR_PIN, state == SPINDLE_ENABLE_CW);
#endif
// NOTE: Assumes all calls to this function is when Grbl is not moving or must remain off.
if (settings.flags & BITFLAG_LASER_MODE) {
if (state == SPINDLE_ENABLE_CCW) rpm = 0.0; // TODO: May need to be rpm_min*(100/MAX_SPINDLE_SPEED_OVERRIDE);
}
spindle_set_speed(spindle_compute_pwm_value(rpm));
}
sys.report_ovr_counter = 0; // Set to report change immediately
#endif
}
void spindle_sync(uint8_t state, float rpm) {
if (sys.state == STATE_CHECK_MODE)
return;
protocol_buffer_synchronize(); // Empty planner buffer to ensure spindle is set when programmed.
spindle_set_state(state, rpm);
}
void grbl_analogWrite(uint8_t chan, uint32_t duty) {
// Remember the old duty cycle in memory instead of reading
// it from the I/O peripheral because I/O reads are quite
// a bit slower than memory reads.
static uint32_t old_duty = 0;
if (old_duty != duty) { // reduce unnecessary calls to ledcWrite()
old_duty = duty;
ledcWrite(chan, duty);
}
}
void spindle_set_enable(bool enable) {
#ifdef SPINDLE_ENABLE_PIN
#ifndef INVERT_SPINDLE_ENABLE_PIN
digitalWrite(SPINDLE_ENABLE_PIN, enable); // turn off (low) with zero speed
#else
digitalWrite(SPINDLE_ENABLE_PIN, !enable); // turn off (high) with zero speed
#endif
#endif
}
uint32_t piecewise_linear_fit(float rpm) {
uint32_t pwm_value;
#if (N_PIECES > 3)
if (rpm > RPM_POINT34)
pwm_value = floor(RPM_LINE_A4 * rpm - RPM_LINE_B4);
else
#endif
#if (N_PIECES > 2)
if (rpm > RPM_POINT23)
pwm_value = floor(RPM_LINE_A3 * rpm - RPM_LINE_B3);
else
#endif
#if (N_PIECES > 1)
if (rpm > RPM_POINT12)
pwm_value = floor(RPM_LINE_A2 * rpm - RPM_LINE_B2);
else
#endif
{
pwm_value = floor(RPM_LINE_A1 * rpm - RPM_LINE_B1);
}
return pwm_value;
}

View File

@@ -1,47 +0,0 @@
/*
spindle.h - Header for system level commands and real-time processes
Part of Grbl
Copyright (c) 2014-2016 Sungeun K. Jeon for Gnea Research LLC
2018 - 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/>.
*/
#ifndef spindle_control_h
#define spindle_control_h
#include "grbl.h"
#define SPINDLE_NO_SYNC false
#define SPINDLE_FORCE_SYNC true
#define SPINDLE_STATE_DISABLE 0 // Must be zero.
#define SPINDLE_STATE_CW bit(0)
#define SPINDLE_STATE_CCW bit(1)
extern uint32_t spindle_pwm_off_value;
void spindle_init();
void spindle_stop();
uint8_t spindle_get_state();
void spindle_set_speed(uint32_t pwm_value);
uint32_t spindle_compute_pwm_value(float rpm);
void spindle_set_state(uint8_t state, float rpm);
void spindle_sync(uint8_t state, float rpm);
void grbl_analogWrite(uint8_t chan, uint32_t duty);
void spindle_set_enable(bool enable);
uint32_t piecewise_linear_fit(float rpm);
#endif

View File

@@ -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;
@@ -294,7 +289,7 @@ void IRAM_ATTR onStepperDriverTimer(void* para) { // ISR It is time to take a st
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.
}
@@ -686,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
}
@@ -1008,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
@@ -1105,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];
@@ -1211,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
@@ -1402,4 +1398,4 @@ bool get_stepper_disable() { // returns true if steppers are disabled
disabled = !disabled; // Apply pin invert.
}
return disabled;
}
}

View File

@@ -26,7 +26,7 @@ bool debouncing = false; // debouncing in process
void system_ini() { // Renamed from system_init() due to conflict with esp32 files
// setup control inputs
#ifndef IGNORE_CONTROL_PINS
#ifdef CONTROL_SAFETY_DOOR_PIN
pinMode(CONTROL_SAFETY_DOOR_PIN, INPUT_PULLUP);
attachInterrupt(digitalPinToInterrupt(CONTROL_SAFETY_DOOR_PIN), isr_control_inputs, CHANGE);
@@ -73,7 +73,7 @@ void system_ini() { // Renamed from system_init() due to conflict with esp32 fil
5, // priority
NULL);
#endif
#endif
//customize pin definition if needed
#if (GRBL_SPI_SS != -1) || (GRBL_SPI_MISO != -1) || (GRBL_SPI_MOSI != -1) || (GRBL_SPI_SCK != -1)
SPI.begin(GRBL_SPI_SCK, GRBL_SPI_MISO, GRBL_SPI_MOSI, GRBL_SPI_SS);
@@ -453,10 +453,8 @@ uint8_t system_check_travel_limits(float* target) {
// defined by the CONTROL_PIN_INDEX in the header file.
uint8_t system_control_get_state() {
uint8_t defined_pin_mask = 0; // a mask of defined pins
#ifdef IGNORE_CONTROL_PINS
return 0;
#endif
uint8_t control_state = 0;
#ifdef CONTROL_SAFETY_DOOR_PIN
defined_pin_mask |= CONTROL_PIN_INDEX_SAFETY_DOOR;
if (digitalRead(CONTROL_SAFETY_DOOR_PIN)) control_state |= CONTROL_PIN_INDEX_SAFETY_DOOR;
@@ -589,11 +587,13 @@ int8_t sys_get_next_RMT_chan_num() {
}
}
/*
This returns an unused pwm channel.
The 8 channels share 4 timers, so pairs 0,1 & 2,3 , etc
have to be the same frequency. The spindle always uses channel 0
so we start counting from 2.
There are still possible issues if requested channels use different frequencies
TODO: Make this more robust.
*/

View File

@@ -74,6 +74,7 @@ extern system_t sys;
#define EXEC_ALARM_HOMING_FAIL_DOOR 7
#define EXEC_ALARM_HOMING_FAIL_PULLOFF 8
#define EXEC_ALARM_HOMING_FAIL_APPROACH 9
#define EXEC_ALARM_SPINDLE_CONTROL 10
// Override bit maps. Realtime bitflags to control feed, rapid, spindle, and coolant overrides.
// Spindle/coolant and feed/rapids are separated into two controlling flag variables.
@@ -125,7 +126,7 @@ extern system_t sys;
#define STEP_CONTROL_END_MOTION bit(0)
#define STEP_CONTROL_EXECUTE_HOLD bit(1)
#define STEP_CONTROL_EXECUTE_SYS_MOTION bit(2)
#define STEP_CONTROL_UPDATE_SPINDLE_PWM bit(3)
#define STEP_CONTROL_UPDATE_SPINDLE_RPM bit(3)
// Define control pin index for Grbl internal use. Pin maps may change, but these values don't.
//#ifdef ENABLE_SAFETY_DOOR_INPUT_PIN
@@ -152,8 +153,7 @@ extern system_t sys;
#define SPINDLE_STOP_OVR_RESTORE bit(2)
#define SPINDLE_STOP_OVR_RESTORE_CYCLE bit(3)
#define UNDEFINED_PIN 255 // Can be used to show a pin has no i/O assigned
// NOTE: These position variables may need to be declared as volatiles, if problems arise.
extern int32_t sys_position[N_AXIS]; // Real-time machine (aka home) position vector in steps.