1
0
mirror of https://github.com/bdring/Grbl_Esp32.git synced 2025-08-27 08:14:31 +02:00

Added support for Spindle Enable and Direction

- Added Spindle Enable Support
- Added Spindle Direction Support
- M7 and M8 are now both optional

See the Wiki on how to setup I/O
This commit is contained in:
bdring
2018-09-10 12:40:45 -05:00
parent 0f98c00efd
commit 62c60b9a76
11 changed files with 167 additions and 89 deletions

View File

@@ -185,7 +185,9 @@ Some features should not be changed. See notes below.
// Enables a second coolant control pin via the mist coolant g-code command M7 on the Arduino Uno
// analog pin 4. Only use this option if you require a second coolant control pin.
// NOTE: The M8 flood coolant control pin on analog pin 3 will still be functional regardless.
//#define ENABLE_M7 // Disabled by default. Uncomment to enable.
// ESP32 NOTE! This is here for reference only. You enable both M7 and M8 by assigning them a GPIO Pin
// in cpu_map.h
//#define ENABLE_M7 // Don't uncomment...see above!
// This option causes the feed hold input to act as a safety door switch. A safety door, when triggered,
// immediately forces a feed hold and then safely de-energizes the machine. Resuming is blocked until

View File

@@ -26,8 +26,12 @@
void coolant_init()
{
#ifdef COOLANT_FLOOD_PIN
pinMode(COOLANT_FLOOD_PIN, OUTPUT);
#ifdef ENABLE_M7
#endif
#ifdef COOLANT_MIST_PIN
pinMode(COOLANT_MIST_PIN, OUTPUT);
#endif
coolant_stop();
@@ -39,6 +43,7 @@ uint8_t coolant_get_state()
{
uint8_t cl_state = COOLANT_STATE_DISABLE;
#ifdef COOLANT_FLOOD_PIN
#ifdef INVERT_COOLANT_FLOOD_PIN
if (! digitalRead(COOLANT_FLOOD_PIN)) {
#else
@@ -46,7 +51,10 @@ uint8_t coolant_get_state()
#endif
cl_state |= COOLANT_STATE_FLOOD;
}
#ifdef ENABLE_M7
#endif
#ifdef COOLANT_MIST_PIN
#ifdef INVERT_COOLANT_MIST_PIN
if (! digitalRead(COOLANT_MIST_PIN)) {
#else
@@ -65,12 +73,15 @@ uint8_t coolant_get_state()
// an interrupt-level. No report flag set, but only called by routines that don't need it.
void coolant_stop()
{
#ifdef COOLANT_FLOOD_PIN
#ifdef INVERT_COOLANT_FLOOD_PIN
digitalWrite(COOLANT_FLOOD_PIN, 1);
#else
digitalWrite(COOLANT_FLOOD_PIN, 0);
#endif
#ifdef ENABLE_M7
#endif
#ifdef COOLANT_MIST_PIN
#ifdef INVERT_COOLANT_MIST_PIN
digitalWrite(COOLANT_MIST_PIN, 1);
#else
@@ -94,6 +105,7 @@ void coolant_set_state(uint8_t mode)
} else {
#ifdef COOLANT_FLOOD_PIN
if (mode & COOLANT_FLOOD_ENABLE) {
#ifdef INVERT_COOLANT_FLOOD_PIN
digitalWrite(COOLANT_FLOOD_PIN, 0);
@@ -101,8 +113,9 @@ void coolant_set_state(uint8_t mode)
digitalWrite(COOLANT_FLOOD_PIN, 1);
#endif
}
#endif
#ifdef ENABLE_M7
#ifdef COOLANT_MIST_PIN
if (mode & COOLANT_MIST_ENABLE) {
#ifdef INVERT_COOLANT_MIST_PIN
digitalWrite(COOLANT_MIST_PIN, 0);

View File

@@ -34,8 +34,6 @@
changed. They are just preserved right now to make it easy to stay in sync
with AVR grbl
*/
// This is the CPU Map for the ESP32 CNC Controller R2
@@ -59,8 +57,11 @@
#define STEPPERS_DISABLE_PIN GPIO_NUM_13
// *** the flood coolant feature code is activated by defining this pins
// *** Comment it out to use the pin for other features
#define COOLANT_FLOOD_PIN GPIO_NUM_16
#define COOLANT_MIST_PIN GPIO_NUM_19
//#define COOLANT_MIST_PIN GPIO_NUM_21
#define SPINDLE_PWM_PIN GPIO_NUM_17
#define SPINDLE_PWM_CHANNEL 0
@@ -70,6 +71,11 @@
#define SPINDLE_PWM_MAX_VALUE 255 // TODO ESP32 Calc from resolution
#define SPINDLE_PWM_RANGE (SPINDLE_PWM_MAX_VALUE-SPINDLE_PWM_MIN_VALUE)
// if these spindle function pins are defined, they will be activated in the code
// comment them out to use the pins for other functions
//#define SPINDLE_ENABLE_PIN GPIO_NUM_16
//#define SPINDLE_DIR_PIN GPIO_NUM_16
#define X_LIMIT_BIT 0
#define Y_LIMIT_BIT 1
#define Z_LIMIT_BIT 2

View File

@@ -255,34 +255,38 @@ uint8_t gc_execute_line(char *line, uint8_t client)
default: gc_block.modal.program_flow = int_value; // Program end and reset
}
break;
#ifndef USE_SPINDLE_DIR_AS_ENABLE_PIN
case 4:
#endif
case 3: case 5:
case 3: case 4: case 5:
word_bit = MODAL_GROUP_M7;
switch(int_value) {
case 3: gc_block.modal.spindle = SPINDLE_ENABLE_CW; break;
#ifndef USE_SPINDLE_DIR_AS_ENABLE_PIN
case 4: gc_block.modal.spindle = SPINDLE_ENABLE_CCW; break;
case 3:
gc_block.modal.spindle = SPINDLE_ENABLE_CW;
break;
case 4:
#ifdef SPINDLE_DIR_PIN
gc_block.modal.spindle = SPINDLE_ENABLE_CCW;
#else
FAIL(STATUS_GCODE_UNSUPPORTED_COMMAND);
#endif
break;
case 5: gc_block.modal.spindle = SPINDLE_DISABLE; break;
}
break;
#ifdef ENABLE_M7
case 7: case 8: case 9:
#else
case 8: case 9:
#endif
word_bit = MODAL_GROUP_M8;
switch(int_value) {
#ifdef ENABLE_M7
#ifdef COOLANT_MIST_PIN
case 7: gc_block.modal.coolant = COOLANT_MIST_ENABLE; break;
#endif
#ifdef COOLANT_FLOOD_PIN
case 8: gc_block.modal.coolant = COOLANT_FLOOD_ENABLE; break;
#endif
case 9: gc_block.modal.coolant = COOLANT_DISABLE; break;
default: FAIL(STATUS_GCODE_UNSUPPORTED_COMMAND); // [Unsupported M command]
}
break;
default: FAIL(STATUS_GCODE_UNSUPPORTED_COMMAND); // [Unsupported M command]
default:
FAIL(STATUS_GCODE_UNSUPPORTED_COMMAND); // [Unsupported M command]
}
// Check for more than one command per modal group violations in the current block

View File

@@ -20,7 +20,7 @@
// Grbl versioning system
#define GRBL_VERSION "1.1f"
#define GRBL_VERSION_BUILD "20180906"
#define GRBL_VERSION_BUILD "20180910"
//#include <sdkconfig.h>
#include <arduino.h>

View File

@@ -511,19 +511,28 @@ void protocol_exec_rt_system()
if (rt_exec & (EXEC_COOLANT_FLOOD_OVR_TOGGLE | EXEC_COOLANT_MIST_OVR_TOGGLE)) {
if ((sys.state == STATE_IDLE) || (sys.state & (STATE_CYCLE | STATE_HOLD))) {
uint8_t coolant_state = gc_state.modal.coolant;
#ifdef ENABLE_M7
if (rt_exec & EXEC_COOLANT_MIST_OVR_TOGGLE) {
if (coolant_state & COOLANT_MIST_ENABLE) { bit_false(coolant_state,COOLANT_MIST_ENABLE); }
else { coolant_state |= COOLANT_MIST_ENABLE; }
#ifdef COOLANT_FLOOD_PIN
if (rt_exec & EXEC_COOLANT_FLOOD_OVR_TOGGLE)
{
if (coolant_state & COOLANT_FLOOD_ENABLE) {
bit_false(coolant_state,COOLANT_FLOOD_ENABLE);
}
else {
coolant_state |= COOLANT_FLOOD_ENABLE;
}
if (rt_exec & EXEC_COOLANT_FLOOD_OVR_TOGGLE) {
if (coolant_state & COOLANT_FLOOD_ENABLE) { bit_false(coolant_state,COOLANT_FLOOD_ENABLE); }
else { coolant_state |= COOLANT_FLOOD_ENABLE; }
}
#else
if (coolant_state & COOLANT_FLOOD_ENABLE) { bit_false(coolant_state,COOLANT_FLOOD_ENABLE); }
else { coolant_state |= COOLANT_FLOOD_ENABLE; }
#endif
#ifdef COOLANT_MIST_PIN
if (rt_exec & EXEC_COOLANT_MIST_OVR_TOGGLE) {
if (coolant_state & COOLANT_MIST_ENABLE) {
bit_false(coolant_state,COOLANT_MIST_ENABLE);
}
else {
coolant_state |= COOLANT_MIST_ENABLE;
}
}
#endif
coolant_set_state(coolant_state); // Report counter set in coolant_set_state().
gc_state.modal.coolant = coolant_state;
}

View File

@@ -403,16 +403,14 @@ void report_gcode_modes(uint8_t client)
case SPINDLE_DISABLE : strcat(modes_rpt, " M5"); break;
}
//report_util_gcode_modes_M();
#ifdef ENABLE_M7
//report_util_gcode_modes_M(); // optional M7 and M8 should have been dealt with by here
if (gc_state.modal.coolant) { // Note: Multiple coolant states may be active at the same time.
if (gc_state.modal.coolant & PL_COND_FLAG_COOLANT_MIST) { strcat(modes_rpt, " M7"); }
if (gc_state.modal.coolant & PL_COND_FLAG_COOLANT_FLOOD) { strcat(modes_rpt, " M8"); }
} else { strcat(modes_rpt, " M9"); }
#else
if (gc_state.modal.coolant) { strcat(modes_rpt, " M8"); }
else { strcat(modes_rpt, " M9"); }
#endif
}
else {
strcat(modes_rpt, " M9");
}
sprintf(temp, " T%d", gc_state.tool);
strcat(modes_rpt, temp);
@@ -459,8 +457,8 @@ void report_build_info(char *line, uint8_t client)
#ifdef USE_LINE_NUMBERS
strcat(build_info,"N");
#endif
#ifdef ENABLE_M7
strcat(build_info,"M");
#ifdef COOLANT_MIST_PIN
strcat(build_info,"M"); // TODO Need to deal with M8...it could be disabled
#endif
#ifdef COREXY
strcat(build_info,"C");
@@ -703,7 +701,7 @@ void report_realtime_status(uint8_t client)
#endif
}
if (cl_state & COOLANT_STATE_FLOOD) { strcat(status, "F"); }
#ifdef ENABLE_M7
#ifdef COOLANT_MIST_PIN // TODO Deal with M8 - Flood
if (cl_state & COOLANT_STATE_MIST) { strcat(status, "M"); }
#endif
}

View File

@@ -141,8 +141,10 @@ void serialCheckTask(void *pvParameters)
case CMD_SPINDLE_OVR_FINE_PLUS: system_set_exec_accessory_override_flag(EXEC_SPINDLE_OVR_FINE_PLUS); break;
case CMD_SPINDLE_OVR_FINE_MINUS: system_set_exec_accessory_override_flag(EXEC_SPINDLE_OVR_FINE_MINUS); break;
case CMD_SPINDLE_OVR_STOP: system_set_exec_accessory_override_flag(EXEC_SPINDLE_OVR_STOP); break;
#ifdef COOLANT_FLOOD_PIN
case CMD_COOLANT_FLOOD_OVR_TOGGLE: system_set_exec_accessory_override_flag(EXEC_COOLANT_FLOOD_OVR_TOGGLE); break;
#ifdef ENABLE_M7
#endif
#ifdef COOLANT_MIST_PIN
case CMD_COOLANT_MIST_OVR_TOGGLE: system_set_exec_accessory_override_flag(EXEC_COOLANT_MIST_OVR_TOGGLE); break;
#endif
}
@@ -246,8 +248,10 @@ void serialCheck()
case CMD_SPINDLE_OVR_FINE_PLUS: system_set_exec_accessory_override_flag(EXEC_SPINDLE_OVR_FINE_PLUS); break;
case CMD_SPINDLE_OVR_FINE_MINUS: system_set_exec_accessory_override_flag(EXEC_SPINDLE_OVR_FINE_MINUS); break;
case CMD_SPINDLE_OVR_STOP: system_set_exec_accessory_override_flag(EXEC_SPINDLE_OVR_STOP); break;
#ifdef COOLANT_FLOOD_PIN
case CMD_COOLANT_FLOOD_OVR_TOGGLE: system_set_exec_accessory_override_flag(EXEC_COOLANT_FLOOD_OVR_TOGGLE); break;
#ifdef ENABLE_M7
#endif
#ifdef COOLANT_MIST_PIN
case CMD_COOLANT_MIST_OVR_TOGGLE: system_set_exec_accessory_override_flag(EXEC_COOLANT_MIST_OVR_TOGGLE); break;
#endif
}
@@ -274,7 +278,7 @@ void serial_reset_read_buffer(uint8_t client)
{
if (client == client_num || client == CLIENT_ALL)
{
serial_rx_buffer_tail[client_num] = serial_rx_buffer_head[client_num];
serial_rx_buffer_tail[client_num-1] = serial_rx_buffer_head[client_num-1];
}
}
}

View File

@@ -3,7 +3,7 @@
Part of Grbl
Copyright (c) 2014-2016 Sungeun K. Jeon for Gnea Research LLC
2018 - Bart Dring This file was modifed for use on the ESP32
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
@@ -23,30 +23,54 @@
void spindle_init()
{
// 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://esp-idf.readthedocs.io/en/v1.0/api/ledc.html
ledcSetup(SPINDLE_PWM_CHANNEL, SPINDLE_PWM_BASE_FREQ, SPINDLE_PWM_BIT_PRECISION); // setup the channel
ledcAttachPin(SPINDLE_PWM_PIN, SPINDLE_PWM_CHANNEL); // attach the PWM to the pin
// Start with PWM off
// Start with spindle off off
spindle_stop();
}
void spindle_stop()
{
spindle_set_enable(false);
grbl_analogWrite(SPINDLE_PWM_CHANNEL, 0);
}
uint8_t spindle_get_state()
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
if (ledcRead(SPINDLE_PWM_CHANNEL) == 0) // Check the PWM value
return(SPINDLE_STATE_DISABLE);
else
return(SPINDLE_STATE_CW); // only CW is supported right now.
{
#ifdef SPINDLE_DIR_PIN
if (digitalRead(SPINDLE_DIR_PIN))
return (SPINDLE_STATE_CW);
else
return(SPINDLE_STATE_CCW);
#else
return(SPINDLE_STATE_CW);
#endif
}
}
void spindle_set_speed(uint8_t pwm_value)
{
#ifndef SPINDLE_ENABLE_OFF_WITH_ZERO_SPEED
spindle_set_enable(true);
#else
spindle_set_enable(pwm_value != 0);
#endif
grbl_analogWrite(SPINDLE_PWM_CHANNEL, pwm_value);
}
@@ -70,12 +94,22 @@ void spindle_set_state(uint8_t state, float rpm)
} else {
// TODO ESP32 Enable and direction control
#ifdef SPINDLE_DIR_PIN
if (state == SPINDLE_ENABLE_CW) {
digitalWrite(SPINDLE_DIR_PIN, 1);
}
else
{
digitalWrite(SPINDLE_DIR_PIN, 0);
}
#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
@@ -98,4 +132,14 @@ void grbl_analogWrite(uint8_t chan, uint32_t 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
}

View File

@@ -30,7 +30,6 @@
#define SPINDLE_STATE_CW bit(0)
#define SPINDLE_STATE_CCW bit(1)
void spindle_init();
void spindle_stop();
uint8_t spindle_get_state();
@@ -38,7 +37,7 @@
uint8_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);
#endif

View File

@@ -49,7 +49,6 @@ Using SD Card
### Roadmap
- Add Wifi support and a web page interface
- Add spindle enable and direction.
### Credits