mirror of
https://github.com/bdring/Grbl_Esp32.git
synced 2025-01-16 21:58:13 +01:00
M67 (#592)
* Implemented gcode parsing. No action yet. * Added iImmediate version of commands. * Analog I/O working - don't merge yet. * Ready for review * Fixing issues and mask variable size
This commit is contained in:
parent
3ca84db178
commit
50bae92bfb
@ -179,7 +179,7 @@ void atari_home_task(void* pvParameters) {
|
||||
void calc_solenoid(float penZ) {
|
||||
bool isPenUp;
|
||||
static bool previousPenState = false;
|
||||
uint32_t solenoid_pen_pulse_len; // duty cycle of solenoid
|
||||
uint32_t solenoid_pen_pulse_len; // duty cycle of solenoid
|
||||
isPenUp = ((penZ > 0) || (sys.state == State::Alarm)); // is pen above Z0 or is there an alarm
|
||||
// if the state has not change, we only count down to the pull time
|
||||
if (previousPenState == isPenUp) {
|
||||
|
@ -538,3 +538,16 @@
|
||||
#ifndef DYNAMIXEL_RTS
|
||||
# define DYNAMIXEL_RTS UNDEFINED_PIN
|
||||
#endif
|
||||
|
||||
#ifndef USER_ANALOG_PIN_0_FREQ
|
||||
# define USER_ANALOG_PIN_0_FREQ 5000
|
||||
#endif
|
||||
#ifndef USER_ANALOG_PIN_1_FREQ
|
||||
# define USER_ANALOG_PIN_1_FREQ 5000
|
||||
#endif
|
||||
#ifndef USER_ANALOG_PIN_2_FREQ
|
||||
# define USER_ANALOG_PIN_2_FREQ 5000
|
||||
#endif
|
||||
#ifndef USER_ANALOG_PIN_3_FREQ
|
||||
# define USER_ANALOG_PIN_3_FREQ 5000
|
||||
#endif
|
||||
|
@ -137,8 +137,8 @@ Error gc_execute_line(char* line, uint8_t client) {
|
||||
uint8_t axis_words = 0; // XYZ tracking
|
||||
uint8_t ijk_words = 0; // IJK tracking
|
||||
// Initialize command and value words and parser flags variables.
|
||||
uint16_t command_words = 0; // Tracks G and M command words. Also used for modal group violations.
|
||||
uint16_t value_words = 0; // Tracks value words.
|
||||
uint32_t command_words = 0; // Tracks G and M command words. Also used for modal group violations.
|
||||
uint32_t value_words = 0; // Tracks value words.
|
||||
uint8_t gc_parser_flags = GCParserNone;
|
||||
// Determine if the line is a jogging motion or a normal g-code block.
|
||||
if (line[0] == '$') { // NOTE: `$J=` already parsed when passed to this function.
|
||||
@ -156,7 +156,7 @@ Error gc_execute_line(char* line, uint8_t client) {
|
||||
perform initial error-checks for command word modal group violations, for any repeated
|
||||
words, and for negative values set for the value words F, N, P, T, and S. */
|
||||
ModalGroup mg_word_bit; // Bit-value for assigning tracking variables
|
||||
uint8_t bitmask = 0;
|
||||
uint32_t bitmask = 0;
|
||||
uint8_t char_counter;
|
||||
char letter;
|
||||
float value;
|
||||
@ -498,11 +498,27 @@ Error gc_execute_line(char* line, uint8_t client) {
|
||||
break;
|
||||
#endif
|
||||
case 62:
|
||||
gc_block.modal.io_control = IoControl::Enable;
|
||||
gc_block.modal.io_control = IoControl::DigitalOnSync;
|
||||
mg_word_bit = ModalGroup::MM10;
|
||||
break;
|
||||
case 63:
|
||||
gc_block.modal.io_control = IoControl::Disable;
|
||||
gc_block.modal.io_control = IoControl::DigitalOffSync;
|
||||
mg_word_bit = ModalGroup::MM10;
|
||||
break;
|
||||
case 64:
|
||||
gc_block.modal.io_control = IoControl::DigitalOnImmediate;
|
||||
mg_word_bit = ModalGroup::MM10;
|
||||
break;
|
||||
case 65:
|
||||
gc_block.modal.io_control = IoControl::DigitalOffImmediate;
|
||||
mg_word_bit = ModalGroup::MM10;
|
||||
break;
|
||||
case 67:
|
||||
gc_block.modal.io_control = IoControl::SetAnalogSync;
|
||||
mg_word_bit = ModalGroup::MM10;
|
||||
break;
|
||||
case 68:
|
||||
gc_block.modal.io_control = IoControl::SetAnalogImmediate;
|
||||
mg_word_bit = ModalGroup::MM10;
|
||||
break;
|
||||
default:
|
||||
@ -545,6 +561,11 @@ Error gc_execute_line(char* line, uint8_t client) {
|
||||
break;
|
||||
#endif
|
||||
// case 'D': // Not supported
|
||||
case 'E':
|
||||
axis_word_bit = GCodeWord::E;
|
||||
gc_block.values.e = int_value;
|
||||
//grbl_msg_sendf(CLIENT_SERIAL, MSG_LEVEL_INFO, "E %d", gc_block.values.e);
|
||||
break;
|
||||
case 'F':
|
||||
axis_word_bit = GCodeWord::F;
|
||||
gc_block.values.f = value;
|
||||
@ -577,8 +598,11 @@ Error gc_execute_line(char* line, uint8_t client) {
|
||||
axis_word_bit = GCodeWord::P;
|
||||
gc_block.values.p = value;
|
||||
break;
|
||||
// NOTE: For certain commands, P value must be an integer, but none of these commands are supported.
|
||||
// case 'Q': // Not supported
|
||||
case 'Q':
|
||||
axis_word_bit = GCodeWord::Q;
|
||||
gc_block.values.q = value;
|
||||
//grbl_msg_sendf(CLIENT_SERIAL, MSG_LEVEL_INFO, "Q %2.2f", value);
|
||||
break;
|
||||
case 'R':
|
||||
axis_word_bit = GCodeWord::R;
|
||||
gc_block.values.r = value;
|
||||
@ -614,7 +638,7 @@ Error gc_execute_line(char* line, uint8_t client) {
|
||||
FAIL(Error::GcodeUnsupportedCommand);
|
||||
}
|
||||
// NOTE: Variable 'axis_word_bit' is always assigned, if the non-command letter is valid.
|
||||
bitmask = bit(axis_word_bit);
|
||||
uint32_t bitmask = bit(axis_word_bit);
|
||||
if (bit_istrue(value_words, bitmask)) {
|
||||
FAIL(Error::GcodeWordRepeated); // [Word repeated]
|
||||
}
|
||||
@ -749,12 +773,20 @@ Error gc_execute_line(char* line, uint8_t client) {
|
||||
}
|
||||
bit_false(value_words, bit(GCodeWord::P));
|
||||
}
|
||||
if ((gc_block.modal.io_control == IoControl::Enable) || (gc_block.modal.io_control == IoControl::Disable)) {
|
||||
if ((gc_block.modal.io_control == IoControl::DigitalOnSync) || (gc_block.modal.io_control == IoControl::DigitalOffSync) ||
|
||||
(gc_block.modal.io_control == IoControl::DigitalOnImmediate) || (gc_block.modal.io_control == IoControl::DigitalOffImmediate)) {
|
||||
if (bit_isfalse(value_words, bit(GCodeWord::P))) {
|
||||
FAIL(Error::GcodeValueWordMissing); // [P word missing]
|
||||
}
|
||||
bit_false(value_words, bit(GCodeWord::P));
|
||||
}
|
||||
if ((gc_block.modal.io_control == IoControl::SetAnalogSync) || (gc_block.modal.io_control == IoControl::SetAnalogImmediate)) {
|
||||
if (bit_isfalse(value_words, bit(GCodeWord::E)) || bit_isfalse(value_words, bit(GCodeWord::Q))) {
|
||||
FAIL(Error::GcodeValueWordMissing);
|
||||
}
|
||||
bit_false(value_words, bit(GCodeWord::E));
|
||||
bit_false(value_words, bit(GCodeWord::Q));
|
||||
}
|
||||
// [11. Set active plane ]: N/A
|
||||
switch (gc_block.modal.plane_select) {
|
||||
case Plane::XY:
|
||||
@ -1323,13 +1355,29 @@ Error gc_execute_line(char* line, uint8_t client) {
|
||||
}
|
||||
pl_data->coolant = gc_state.modal.coolant; // Set state for planner use.
|
||||
// turn on/off an i/o pin
|
||||
if ((gc_block.modal.io_control == IoControl::Enable) || (gc_block.modal.io_control == IoControl::Disable)) {
|
||||
if (gc_block.values.p <= MaxUserDigitalPin) {
|
||||
sys_io_control(bit((int)gc_block.values.p), (gc_block.modal.io_control == IoControl::Enable));
|
||||
if ((gc_block.modal.io_control == IoControl::DigitalOnSync) || (gc_block.modal.io_control == IoControl::DigitalOffSync) ||
|
||||
(gc_block.modal.io_control == IoControl::DigitalOnImmediate) || (gc_block.modal.io_control == IoControl::DigitalOffImmediate)) {
|
||||
if (gc_block.values.p < MaxUserDigitalPin) {
|
||||
if (!sys_io_control(
|
||||
bit((int)gc_block.values.p),
|
||||
(gc_block.modal.io_control == IoControl::DigitalOnSync) || (gc_block.modal.io_control == IoControl::DigitalOnImmediate),
|
||||
(gc_block.modal.io_control == IoControl::DigitalOnSync) || (gc_block.modal.io_control == IoControl::DigitalOffSync))) {
|
||||
FAIL(Error::PParamMaxExceeded);
|
||||
}
|
||||
} else {
|
||||
FAIL(Error::PParamMaxExceeded);
|
||||
}
|
||||
}
|
||||
if ((gc_block.modal.io_control == IoControl::SetAnalogSync) || (gc_block.modal.io_control == IoControl::SetAnalogImmediate)) {
|
||||
if (gc_block.values.e < MaxUserDigitalPin) {
|
||||
gc_block.values.q = constrain(gc_block.values.q, 0.0, 100.0); // force into valid range
|
||||
if (!sys_pwm_control(bit((int)gc_block.values.e), gc_block.values.q, (gc_block.modal.io_control == IoControl::SetAnalogSync)))
|
||||
FAIL(Error::PParamMaxExceeded);
|
||||
} else {
|
||||
FAIL(Error::PParamMaxExceeded);
|
||||
}
|
||||
}
|
||||
|
||||
// [9. Override control ]: NOT SUPPORTED. Always enabled. Except for a Grbl-only parking control.
|
||||
#ifdef ENABLE_PARKING_OVERRIDE_CONTROL
|
||||
if (gc_state.modal.override != gc_block.modal.override) {
|
||||
|
@ -48,7 +48,7 @@ enum class ModalGroup : uint8_t {
|
||||
MM7 = 12, // [M3,M4,M5] Spindle turning
|
||||
MM8 = 13, // [M7,M8,M9] Coolant control
|
||||
MM9 = 14, // [M56] Override control
|
||||
MM10 = 15, // [M62, M63] User Defined http://linuxcnc.org/docs/html/gcode/overview.html#_modal_groups
|
||||
MM10 = 15, // [M62, M63, M64, M65, M67, M68] User Defined http://linuxcnc.org/docs/html/gcode/overview.html#_modal_groups
|
||||
};
|
||||
|
||||
// Command actions for within execution-type modal groups (motion, stopping, non-modal). Used
|
||||
@ -175,8 +175,12 @@ enum class Override : uint8_t {
|
||||
|
||||
// Modal Group M10: User I/O control
|
||||
enum class IoControl : uint8_t {
|
||||
Enable = 1,
|
||||
Disable = 2,
|
||||
DigitalOnSync = 1, // M62
|
||||
DigitalOffSync = 2, // M63
|
||||
DigitalOnImmediate = 3, // M64
|
||||
DigitalOffImmediate = 4, // M65
|
||||
SetAnalogSync = 5, // M67
|
||||
SetAnalogImmediate = 6, // M68
|
||||
};
|
||||
|
||||
static const int MaxUserDigitalPin = 4;
|
||||
@ -197,22 +201,24 @@ enum class ToolChange : uint8_t {
|
||||
|
||||
// Parameter word mapping.
|
||||
enum class GCodeWord : uint8_t {
|
||||
F = 0,
|
||||
I = 1,
|
||||
J = 2,
|
||||
K = 3,
|
||||
L = 4,
|
||||
N = 5,
|
||||
P = 6,
|
||||
R = 7,
|
||||
S = 8,
|
||||
T = 9,
|
||||
X = 10,
|
||||
Y = 11,
|
||||
Z = 12,
|
||||
A = 13,
|
||||
B = 14,
|
||||
C = 15,
|
||||
E = 0,
|
||||
F = 1,
|
||||
I = 2,
|
||||
J = 3,
|
||||
K = 4,
|
||||
L = 5,
|
||||
N = 6,
|
||||
P = 7,
|
||||
Q = 8,
|
||||
R = 9,
|
||||
S = 10,
|
||||
T = 11,
|
||||
X = 12,
|
||||
Y = 13,
|
||||
Z = 14,
|
||||
A = 15,
|
||||
B = 16,
|
||||
C = 17,
|
||||
};
|
||||
|
||||
// GCode parser position updating flags
|
||||
@ -251,17 +257,18 @@ typedef struct {
|
||||
CoolantState coolant; // {M7,M8,M9}
|
||||
SpindleState spindle; // {M3,M4,M5}
|
||||
ToolChange tool_change; // {M6}
|
||||
IoControl io_control; // {M62, M63}
|
||||
IoControl io_control; // {M62, M63, M67}
|
||||
Override override; // {M56}
|
||||
} gc_modal_t;
|
||||
|
||||
typedef struct {
|
||||
uint8_t e; // M67
|
||||
float f; // Feed
|
||||
float ijk[N_AXIS]; // I,J,K Axis arc offsets
|
||||
uint8_t l; // G10 or canned cycles parameters
|
||||
int32_t n; // Line number
|
||||
float p; // G10 or dwell parameters
|
||||
// float q; // G82 peck drilling
|
||||
float q; // M67
|
||||
float r; // Arc radius
|
||||
float s; // Spindle speed
|
||||
uint8_t t; // Tool selection
|
||||
|
@ -66,6 +66,8 @@ const char* const GRBL_VERSION_BUILD = "20200910";
|
||||
#include "SettingsDefinitions.h"
|
||||
#include "WebUI/WebSettings.h"
|
||||
|
||||
#include "UserOutput.h"
|
||||
|
||||
// Do not guard this because it is needed for local files too
|
||||
#include "SDCard.h"
|
||||
|
||||
|
@ -77,7 +77,7 @@
|
||||
*/
|
||||
|
||||
// Socket #3 5V Output
|
||||
#define USER_DIGITAL_PIN_1 GPIO_NUM_14
|
||||
#define USER_DIGITAL_PIN_2 GPIO_NUM_13
|
||||
#define USER_DIGITAL_PIN_3 GPIO_NUM_15
|
||||
#define USER_DIGITAL_PIN_4 GPIO_NUM_12
|
||||
#define USER_DIGITAL_PIN_0 GPIO_NUM_14
|
||||
#define USER_DIGITAL_PIN_1 GPIO_NUM_13
|
||||
#define USER_DIGITAL_PIN_2 GPIO_NUM_15
|
||||
#define USER_DIGITAL_PIN_3 GPIO_NUM_12
|
||||
|
140
Grbl_Esp32/src/Machines/6_pack_stepstick_XYZ_3_5V_IO_v1.h
Normal file
140
Grbl_Esp32/src/Machines/6_pack_stepstick_XYZ_3_5V_IO_v1.h
Normal file
@ -0,0 +1,140 @@
|
||||
#pragma once
|
||||
// clang-format off
|
||||
|
||||
/*
|
||||
6_pack_stepstick_XYZ_3_5V_IO_v1.h
|
||||
|
||||
Covers all V1 versions V1p0, V1p1, etc
|
||||
|
||||
Part of Grbl_ESP32
|
||||
Pin assignments for the ESP32 I2S 6-axis board
|
||||
2018 - Bart Dring
|
||||
2020 - Mitch Bradley
|
||||
2020 - Michiyasu Odaki
|
||||
Grbl_ESP32 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_ESP32. If not, see <http://www.gnu.org/licenses/>.
|
||||
*/
|
||||
#define MACHINE_NAME "6 Pack Controller StepStick XYZ"
|
||||
|
||||
#ifdef N_AXIS
|
||||
#undef N_AXIS
|
||||
#endif
|
||||
|
||||
#ifdef ENABLE_SD_CARD
|
||||
#undef ENABLE_SD_CARD
|
||||
#endif
|
||||
|
||||
#ifdef HOMING_CYCLE_0
|
||||
#undef HOMING_CYCLE_0
|
||||
#endif
|
||||
#define HOMING_CYCLE_0 bit(Z_AXIS) // Z first
|
||||
|
||||
#ifdef HOMING_CYCLE_1
|
||||
#undef HOMING_CYCLE_1
|
||||
#endif
|
||||
#define HOMING_CYCLE_1 (bit(X_AXIS)|bit(Y_AXIS))
|
||||
|
||||
// === Special Features
|
||||
|
||||
// I2S (steppers & other output-only pins)
|
||||
#define USE_I2S_OUT
|
||||
#define USE_I2S_STEPS
|
||||
//#define DEFAULT_STEPPER ST_I2S_STATIC
|
||||
// === Default settings
|
||||
#define DEFAULT_STEP_PULSE_MICROSECONDS I2S_OUT_USEC_PER_PULSE
|
||||
|
||||
#define USE_STEPSTICK // makes sure MS1,2,3 !reset and !sleep are set
|
||||
|
||||
#define I2S_OUT_BCK GPIO_NUM_22
|
||||
#define I2S_OUT_WS GPIO_NUM_17
|
||||
#define I2S_OUT_DATA GPIO_NUM_21
|
||||
|
||||
#define X_STEPPER_MS3 I2SO(3) // X_CS
|
||||
#define Y_STEPPER_MS3 I2SO(6) // Y_CS
|
||||
#define Z_STEPPER_MS3 I2SO(11) // Z_CS
|
||||
#define A_STEPPER_MS3 I2SO(14) // A_CS
|
||||
#define B_STEPPER_MS3 I2SO(19) // B_CS
|
||||
#define C_STEPPER_MS3 I2SO(22) // C_CS
|
||||
|
||||
#define STEPPER_RESET GPIO_NUM_19
|
||||
|
||||
#define X_DISABLE_PIN I2SO(0)
|
||||
#define X_DIRECTION_PIN I2SO(1)
|
||||
#define X_STEP_PIN I2SO(2)
|
||||
|
||||
#define Y_DIRECTION_PIN I2SO(4)
|
||||
#define Y_STEP_PIN I2SO(5)
|
||||
#define Y_DISABLE_PIN I2SO(7)
|
||||
|
||||
#define Z_DISABLE_PIN I2SO(8)
|
||||
#define Z_DIRECTION_PIN I2SO(9)
|
||||
#define Z_STEP_PIN I2SO(10)
|
||||
|
||||
/*
|
||||
Socket I/O reference
|
||||
The list of modules is here...
|
||||
https://github.com/bdring/6-Pack_CNC_Controller/wiki/CNC-I-O-Module-List
|
||||
Click on each module to get example for using the modules in the sockets
|
||||
*/
|
||||
|
||||
|
||||
// Socket #1
|
||||
// #1 GPIO_NUM_33
|
||||
// #2 GPIO_NUM_32
|
||||
// #3 GPIO_NUM_35 (input only)
|
||||
// #4 GPIO_NUM_34 (input only)
|
||||
|
||||
|
||||
// Socket #2
|
||||
// #1 GPIO_NUM_2
|
||||
// #2 GPIO_NUM_25
|
||||
// #3 GPIO_NUM_39 (input only)
|
||||
// #4 GPIO_NUM_36 (input only)
|
||||
|
||||
// Socket #3
|
||||
// #1 GPIO_NUM_26
|
||||
// #2 GPIO_NUM_4
|
||||
// #3 GPIO_NUM_16
|
||||
// #4 GPIO_NUM_27
|
||||
|
||||
|
||||
// Socket #4
|
||||
// #1 GPIO_NUM_14
|
||||
// #2 GPIO_NUM_13
|
||||
// #3 GPIO_NUM_15
|
||||
// #4 GPIO_NUM_12
|
||||
|
||||
|
||||
// Socket #5
|
||||
// #1 GPIO_NUM_24 (output only)
|
||||
// #2 GPIO_NUM_25 (output only)
|
||||
// #3 GPIO_NUM_26 (output only)
|
||||
// #4 GPIO_NUM_27 (output only)
|
||||
|
||||
// 5V Output Module in Socket #4
|
||||
#define USER_DIGITAL_PIN_0 GPIO_NUM_14
|
||||
#define USER_DIGITAL_PIN_1 GPIO_NUM_13
|
||||
#define USER_ANALOG_PIN_0 GPIO_NUM_15
|
||||
#define USER_ANALOG_PIN_1 GPIO_NUM_12
|
||||
|
||||
#define USER_ANALOG_PIN_0_FREQ 5000
|
||||
#define USER_ANALOG_PIN_1_FREQ 5000
|
||||
|
||||
#define X_LIMIT_PIN GPIO_NUM_33
|
||||
#define Y_LIMIT_PIN GPIO_NUM_32
|
||||
#define Z_LIMIT_PIN GPIO_NUM_35
|
||||
|
||||
#define DEFAULT_X_STEPS_PER_MM 800
|
||||
#define DEFAULT_Y_STEPS_PER_MM 800
|
||||
#define DEFAULT_Z_STEPS_PER_MM 800
|
||||
|
||||
#define REPORT_SEMICOLON_COMMENTS
|
||||
|
@ -503,11 +503,12 @@ void mc_reset() {
|
||||
spindle->stop();
|
||||
coolant_stop();
|
||||
|
||||
// turn off all digital I/O immediately
|
||||
fast_sys_io_control(0xFF, false);
|
||||
// turn off all User I/O immediately
|
||||
sys_io_control(0xFF, LOW, false);
|
||||
sys_pwm_control(0xFF, 0, false);
|
||||
#ifdef ENABLE_SD_CARD
|
||||
// do we need to stop a running SD job?
|
||||
if (get_sd_state(false) == SDCARD_BUSY_PRINTING) {
|
||||
// do we need to stop a running SD job?
|
||||
if (get_sd_state(false) == SDCARD_BUSY_PRINTING) {
|
||||
//Report print stopped
|
||||
report_feedback_message(Message::SdFileQuit);
|
||||
closeFile();
|
||||
|
@ -34,6 +34,9 @@ volatile uint8_t sys_rt_exec_accessory_override; // Global realtime executor
|
||||
volatile uint8_t sys_rt_exec_debug;
|
||||
#endif
|
||||
|
||||
UserOutput::AnalogOutput* myAnalogOutputs[MaxUserDigitalPin];
|
||||
UserOutput::DigitalOutput* myDigitalOutputs[MaxUserDigitalPin];
|
||||
|
||||
xQueueHandle control_sw_queue; // used by control switch debouncing
|
||||
bool debouncing = false; // debouncing in process
|
||||
|
||||
@ -91,23 +94,54 @@ void system_ini() { // Renamed from system_init() due to conflict with esp32 fi
|
||||
#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);
|
||||
#endif
|
||||
// Setup USER_DIGITAL_PINs controlled by M62 and M63
|
||||
|
||||
|
||||
// Setup USER_DIGITAL_PINs controlled by M62, M63, M64, & M65
|
||||
#ifdef USER_DIGITAL_PIN_0
|
||||
myDigitalOutputs[0] = new UserOutput::DigitalOutput(0, USER_DIGITAL_PIN_0);
|
||||
#else
|
||||
myDigitalOutputs[0] = new UserOutput::DigitalOutput();
|
||||
#endif
|
||||
#ifdef USER_DIGITAL_PIN_1
|
||||
pinMode(USER_DIGITAL_PIN_1, OUTPUT);
|
||||
sys_io_control(bit(1), false); // turn off
|
||||
myDigitalOutputs[1] = new UserOutput::DigitalOutput(1, USER_DIGITAL_PIN_1);
|
||||
#else
|
||||
myDigitalOutputs[1] = new UserOutput::DigitalOutput();
|
||||
#endif
|
||||
#ifdef USER_DIGITAL_PIN_2
|
||||
pinMode(USER_DIGITAL_PIN_2, OUTPUT);
|
||||
sys_io_control(bit(2), false); // turn off
|
||||
myDigitalOutputs[2] = new UserOutput::DigitalOutput(2, USER_DIGITAL_PIN_2);
|
||||
#else
|
||||
myDigitalOutputs[2] = new UserOutput::DigitalOutput();
|
||||
#endif
|
||||
#ifdef USER_DIGITAL_PIN_3
|
||||
pinMode(USER_DIGITAL_PIN_3, OUTPUT);
|
||||
sys_io_control(bit(3), false); // turn off
|
||||
myDigitalOutputs[3] = new UserOutput::DigitalOutput(3, USER_DIGITAL_PIN_3);
|
||||
#else
|
||||
myDigitalOutputs[3] = new UserOutput::DigitalOutput();
|
||||
#endif
|
||||
#ifdef USER_DIGITAL_PIN_4
|
||||
pinMode(USER_DIGITAL_PIN_4, OUTPUT);
|
||||
sys_io_control(bit(4), false); // turn off
|
||||
|
||||
// Setup M67 Pins
|
||||
#ifdef USER_ANALOG_PIN_0
|
||||
myAnalogOutputs[0] = new UserOutput::AnalogOutput(0, USER_ANALOG_PIN_0, USER_ANALOG_PIN_0_FREQ);
|
||||
#else
|
||||
myAnalogOutputs[0] = new UserOutput::AnalogOutput();
|
||||
#endif
|
||||
|
||||
#ifdef USER_ANALOG_PIN_1
|
||||
myAnalogOutputs[1] = new UserOutput::AnalogOutput(1, USER_ANALOG_PIN_1, USER_ANALOG_PIN_1_FREQ);
|
||||
#else
|
||||
myAnalogOutputs[1] = new UserOutput::AnalogOutput();
|
||||
#endif
|
||||
|
||||
#ifdef USER_ANALOG_PIN_2
|
||||
myAnalogOutputs[2] = new UserOutput::AnalogOutput(2, USER_ANALOG_PIN_2, USER_ANALOG_PIN_2_FREQ);
|
||||
#else
|
||||
myAnalogOutputs[2] = new UserOutput::AnalogOutput();
|
||||
#endif
|
||||
|
||||
#ifdef USER_ANALOG_PIN_3
|
||||
myAnalogOutputs[3] = new UserOutput::AnalogOutput(3, USER_ANALOG_PIN_3, USER_ANALOG_PIN_3_FREQ);
|
||||
#else
|
||||
myAnalogOutputs[3] = new UserOutput::AnalogOutput();
|
||||
#endif
|
||||
}
|
||||
|
||||
#ifdef ENABLE_CONTROL_SW_DEBOUNCE
|
||||
@ -135,7 +169,7 @@ void IRAM_ATTR isr_control_inputs() {
|
||||
xQueueSendFromISR(control_sw_queue, &evt, NULL);
|
||||
}
|
||||
#else
|
||||
uint8_t pin = system_control_get_state();
|
||||
uint8_t pin = system_control_get_state();
|
||||
system_exec_control_pin(pin);
|
||||
#endif
|
||||
}
|
||||
@ -371,41 +405,39 @@ int32_t system_convert_corexy_to_y_axis_steps(int32_t* steps) {
|
||||
|
||||
// io_num is the virtual pin# and has nothing to do with the actual esp32 GPIO_NUM_xx
|
||||
// It uses a mask so all can be turned of in ms_reset
|
||||
// This version waits until realtime commands have been executed
|
||||
void sys_io_control(uint8_t io_num_mask, bool turnOn) {
|
||||
protocol_buffer_synchronize();
|
||||
fast_sys_io_control(io_num_mask, turnOn);
|
||||
bool sys_io_control(uint8_t io_num_mask, bool turnOn, bool synchronized) {
|
||||
bool cmd_ok = true;
|
||||
if (synchronized)
|
||||
protocol_buffer_synchronize();
|
||||
|
||||
for (uint8_t io_num = 0; io_num < MaxUserDigitalPin; io_num++) {
|
||||
if (io_num_mask & bit(io_num)) {
|
||||
if (!myDigitalOutputs[io_num]->set_level(turnOn))
|
||||
cmd_ok = false;
|
||||
}
|
||||
}
|
||||
return cmd_ok;
|
||||
}
|
||||
|
||||
// This version works immediately, without waiting, to prevent deadlocks.
|
||||
// It is used when resetting via mc_reset()
|
||||
void fast_sys_io_control(uint8_t io_num_mask, bool turnOn) {
|
||||
#ifdef USER_DIGITAL_PIN_1
|
||||
if (io_num_mask & bit(1)) {
|
||||
digitalWrite(USER_DIGITAL_PIN_1, turnOn);
|
||||
return;
|
||||
// io_num is the virtual pin# and has nothing to do with the actual esp32 GPIO_NUM_xx
|
||||
// It uses a mask so all can be turned of in ms_reset
|
||||
bool sys_pwm_control(uint8_t io_num_mask, float duty, bool synchronized) {
|
||||
bool cmd_ok = true;
|
||||
if (synchronized)
|
||||
protocol_buffer_synchronize();
|
||||
|
||||
for (uint8_t io_num = 0; io_num < MaxUserDigitalPin; io_num++) {
|
||||
if (io_num_mask & bit(io_num)) {
|
||||
if (!myAnalogOutputs[io_num]->set_level(duty))
|
||||
cmd_ok = false;
|
||||
}
|
||||
}
|
||||
#endif
|
||||
#ifdef USER_DIGITAL_PIN_2
|
||||
if (io_num_mask & bit(2)) {
|
||||
digitalWrite(USER_DIGITAL_PIN_2, turnOn);
|
||||
return;
|
||||
}
|
||||
#endif
|
||||
#ifdef USER_DIGITAL_PIN_3
|
||||
if (io_num_mask & bit(3)) {
|
||||
digitalWrite(USER_DIGITAL_PIN_3, turnOn);
|
||||
return;
|
||||
}
|
||||
#endif
|
||||
#ifdef USER_DIGITAL_PIN_4
|
||||
if (io_num_mask & bit(4)) {
|
||||
digitalWrite(USER_DIGITAL_PIN_4, turnOn);
|
||||
return;
|
||||
}
|
||||
#endif
|
||||
return cmd_ok;
|
||||
}
|
||||
|
||||
|
||||
|
||||
|
||||
// Call this function to get an RMT channel number
|
||||
// returns -1 for error
|
||||
int8_t sys_get_next_RMT_chan_num() {
|
||||
@ -436,3 +468,20 @@ int8_t sys_get_next_PWM_chan_num() {
|
||||
return -1;
|
||||
}
|
||||
}
|
||||
|
||||
/*
|
||||
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 sys_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) { // TODO is there a named value for the 80MHz?
|
||||
precision++;
|
||||
}
|
||||
|
||||
return precision - 1;
|
||||
}
|
||||
|
@ -223,9 +223,10 @@ int32_t system_convert_corexy_to_y_axis_steps(int32_t* steps);
|
||||
void controlCheckTask(void* pvParameters);
|
||||
void system_exec_control_pin(uint8_t pin);
|
||||
|
||||
void sys_io_control(uint8_t io_num_mask, bool turnOn);
|
||||
void fast_sys_io_control(uint8_t io_num_mask, bool turnOn);
|
||||
bool sys_io_control(uint8_t io_num_mask, bool turnOn, bool synchronized);
|
||||
bool sys_pwm_control(uint8_t io_num_mask, float duty, bool synchronized);
|
||||
|
||||
//
|
||||
int8_t sys_get_next_RMT_chan_num();
|
||||
|
||||
int8_t sys_get_next_PWM_chan_num();
|
||||
uint8_t sys_calc_pwm_precision(uint32_t freq);
|
||||
|
109
Grbl_Esp32/src/UserOutput.cpp
Normal file
109
Grbl_Esp32/src/UserOutput.cpp
Normal file
@ -0,0 +1,109 @@
|
||||
/*
|
||||
UserOutput.cpp
|
||||
|
||||
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 "Grbl.h"
|
||||
|
||||
namespace UserOutput {
|
||||
DigitalOutput::DigitalOutput() {}
|
||||
|
||||
DigitalOutput::DigitalOutput(uint8_t number, uint8_t pin) {
|
||||
_number = number;
|
||||
_pin = pin;
|
||||
|
||||
init();
|
||||
}
|
||||
|
||||
void DigitalOutput::init() {
|
||||
pinMode(_pin, OUTPUT);
|
||||
digitalWrite(_pin, LOW);
|
||||
|
||||
config_message();
|
||||
}
|
||||
|
||||
void DigitalOutput::config_message() {
|
||||
grbl_msg_sendf(CLIENT_SERIAL, MsgLevel::Info, "User Digital Output:%d on Pin:%s", _number, pinName(_pin).c_str());
|
||||
}
|
||||
|
||||
bool DigitalOutput::set_level(bool isOn) {
|
||||
if (_number == UNDEFINED_PIN && isOn) {
|
||||
return false;
|
||||
}
|
||||
|
||||
digitalWrite(_pin, isOn);
|
||||
return true;
|
||||
}
|
||||
|
||||
// ==================================================================
|
||||
|
||||
AnalogOutput::AnalogOutput() {}
|
||||
|
||||
AnalogOutput::AnalogOutput(uint8_t number, uint8_t pin, float pwm_frequency) {
|
||||
_number = number;
|
||||
_pin = pin;
|
||||
_pwm_frequency = pwm_frequency;
|
||||
|
||||
// determine the highest bit precision allowed by frequency
|
||||
_resolution_bits = sys_calc_pwm_precision(_pwm_frequency);
|
||||
|
||||
init();
|
||||
}
|
||||
|
||||
void AnalogOutput::init() {
|
||||
_pwm_channel = sys_get_next_PWM_chan_num();
|
||||
if (_pwm_channel == -1) {
|
||||
grbl_msg_sendf(CLIENT_SERIAL, MsgLevel::Error, "Error: out of PWM channels");
|
||||
} else {
|
||||
ledcSetup(_pwm_channel, _pwm_frequency, _resolution_bits);
|
||||
ledcAttachPin(_pin, _pwm_channel);
|
||||
ledcWrite(_pwm_channel, 0);
|
||||
|
||||
config_message();
|
||||
}
|
||||
}
|
||||
|
||||
void AnalogOutput::config_message() {
|
||||
grbl_msg_sendf(CLIENT_SERIAL, MsgLevel::Info, "User Analog Output:%d on Pin:%s", _number, pinName(_pin).c_str());
|
||||
}
|
||||
|
||||
// returns true if able to set value
|
||||
bool AnalogOutput::set_level(float percent) {
|
||||
float duty;
|
||||
|
||||
// look for errors, but ignore if turning off to prevent mask turn off from generating errors
|
||||
if (_number == UNDEFINED_PIN && percent != 0.0) {
|
||||
return false;
|
||||
}
|
||||
|
||||
if (_pwm_channel == -1) {
|
||||
grbl_msg_sendf(CLIENT_SERIAL, MsgLevel::Info, "M67 PWM channel error");
|
||||
return false;
|
||||
}
|
||||
|
||||
if (_current_value == percent)
|
||||
return true;
|
||||
|
||||
_current_value = percent;
|
||||
|
||||
duty = (percent / 100.0) * (1 << _resolution_bits);
|
||||
|
||||
ledcWrite(_pwm_channel, duty);
|
||||
|
||||
return true;
|
||||
}
|
||||
}
|
57
Grbl_Esp32/src/UserOutput.h
Normal file
57
Grbl_Esp32/src/UserOutput.h
Normal file
@ -0,0 +1,57 @@
|
||||
#pragma once
|
||||
|
||||
/*
|
||||
UserOutput.h
|
||||
|
||||
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 "Grbl.h"
|
||||
|
||||
namespace UserOutput {
|
||||
class DigitalOutput {
|
||||
public:
|
||||
DigitalOutput();
|
||||
DigitalOutput(uint8_t number, uint8_t pin);
|
||||
|
||||
bool set_level(bool isOn);
|
||||
|
||||
protected:
|
||||
void init();
|
||||
void config_message();
|
||||
|
||||
uint8_t _number = UNDEFINED_PIN;
|
||||
uint8_t _pin = UNDEFINED_PIN;
|
||||
};
|
||||
|
||||
class AnalogOutput {
|
||||
public:
|
||||
AnalogOutput();
|
||||
AnalogOutput(uint8_t number, uint8_t pin, float pwm_frequency);
|
||||
bool set_level(float percent);
|
||||
|
||||
protected:
|
||||
void init();
|
||||
void config_message();
|
||||
|
||||
uint8_t _number = UNDEFINED_PIN;
|
||||
uint8_t _pin = UNDEFINED_PIN;
|
||||
uint8_t _pwm_channel = -1; // -1 means invalid or not setup
|
||||
float _pwm_frequency;
|
||||
uint8_t _resolution_bits;
|
||||
float _current_value;
|
||||
};
|
||||
}
|
45
Grbl_Esp32/src/tests/user_io.nc
Normal file
45
Grbl_Esp32/src/tests/user_io.nc
Normal file
@ -0,0 +1,45 @@
|
||||
(MSG, Starting User I/O tests)
|
||||
M62 P0
|
||||
G4 P0.5
|
||||
M62 P1
|
||||
G4 P0.5
|
||||
M62 P2
|
||||
G4 P0.5
|
||||
M62 P3
|
||||
(MSG Digital 1 and 2 on)
|
||||
G4 P2
|
||||
M63 P0
|
||||
M63 P1
|
||||
M63 P2
|
||||
M63 P3
|
||||
G4P1
|
||||
M67 E0 Q10
|
||||
M67 E1 Q100
|
||||
G4 P0.25
|
||||
M67 E0 Q20
|
||||
M67 E1 Q90
|
||||
G4 P0.25
|
||||
M67 E0 Q30
|
||||
M67 E1 Q80
|
||||
G4 P0.25
|
||||
M67 E0 Q40
|
||||
M67 E1 Q70
|
||||
G4 P0.25
|
||||
M67 E0 Q50
|
||||
M67 E1 Q60
|
||||
G4 P0.25
|
||||
M67 E0 Q60
|
||||
M67 E1 Q50
|
||||
G4 P0.25
|
||||
M67 E0 Q70
|
||||
M67 E1 Q40
|
||||
G4 P0.25
|
||||
M67 E0 Q80
|
||||
M67 E1 Q30
|
||||
G4 P0.25
|
||||
M67 E0 Q90
|
||||
M67 E1 Q20
|
||||
G4 P0.25
|
||||
M67 E0 Q0
|
||||
M67 E1 Q0
|
||||
G4 P0.25
|
92
Grbl_Esp32/src/user_io.md
Normal file
92
Grbl_Esp32/src/user_io.md
Normal file
@ -0,0 +1,92 @@
|
||||
## User I/O Commands
|
||||
|
||||
This is for generic I/O control. These could be for cooling fans, clamping, valves, etc. These could be digital (on/off) or analog (PWM). This allows you to do gcode rather than special coding.
|
||||
|
||||
### Types
|
||||
|
||||
- Digital I/O
|
||||
- Analog (PWM)
|
||||
|
||||
Commands
|
||||
|
||||
#### M62 - M65 Digital Output Control
|
||||
|
||||
M62 Synchronized Digital Output On
|
||||
|
||||
M63 Synchronized Digital Output Off
|
||||
|
||||
M64 Immediate Digital Output On
|
||||
|
||||
M65 Immediate Digital Output Off
|
||||
|
||||
Use P word to indicate digital output number (0-3)
|
||||
|
||||
Examples:
|
||||
|
||||
M62 P0
|
||||
|
||||
M63 P0
|
||||
|
||||
#### M67 - M68 Digital Output Control
|
||||
|
||||
M67 Synchronized Set Analog Value
|
||||
|
||||
M68 Immediate Set Analog Value
|
||||
|
||||
Use E word for analog output number (0-3)
|
||||
|
||||
Use Q word for analog value in percent duty.
|
||||
|
||||
Examples
|
||||
|
||||
M67 E1 Q23.87 (set set output#1 to 23.87% duty)
|
||||
|
||||
M67 E1 Q0 (to turn off the pin. 0% duty)
|
||||
|
||||
### Pin Numbering
|
||||
|
||||
Each pin will be given a number starting at 0. The numbers for the digital and analog are independent. If you use one of each, they should both be 0.
|
||||
|
||||
### Synchronized
|
||||
|
||||
Synchronized means all steps in the buffers must complete before the I/O is changed. Immediate does not wait. With streaming gcode, you should use the synchronized commands. There is no timing guarantee with immediate versions of the commands.
|
||||
|
||||
## Special Behaviors
|
||||
|
||||
- Power On - All pins will be set to the off state
|
||||
- Reset - All pins will be set to the off state
|
||||
- Alarm Mode - No change in pin state
|
||||
- Error - No change in pins state
|
||||
- End of File - TBD
|
||||
|
||||
### Setup
|
||||
|
||||
M62 - M65
|
||||
|
||||
```
|
||||
#define USER_DIGITAL_PIN_0 GPIO_NUM_xx
|
||||
#define USER_DIGITAL_PIN_1 GPIO_NUM_xx
|
||||
#define USER_DIGITAL_PIN_2 GPIO_NUM_xx
|
||||
#define USER_DIGITAL_PIN_3 GPIO_NUM_xx
|
||||
|
||||
#define USER_ANALOG_PIN_0 GPIO_NUM_xx
|
||||
#define USER_ANALOG_PIN_1 GPIO_NUM_xx
|
||||
#define USER_ANALOG_PIN_2 GPIO_NUM_xx
|
||||
#define USER_ANALOG_PIN_3 GPIO_NUM_xx
|
||||
|
||||
#define USER_ANALOG_PIN_1_FREQ 50 // Hz
|
||||
```
|
||||
|
||||
### Frequency
|
||||
|
||||
Defining a frequency is optional. If you do not define one for a pin the default of 5000 will be used. If you are using the PWM to control an RC Servo, you should set it to something around 50.
|
||||
|
||||
### Resolution
|
||||
|
||||
The resolution is dependent on the frequency used. The PWM is based on a 80MHz timer. If you have a 10KHz frequency, you have 80,000,000 / 10,000 you have a maximum of an 8,000 count resolution. The resolution is based on bits so you need to round down to the nearest bit value which would be 14 bit or 4096. The highest bit value allowed is 13 bits.
|
||||
|
||||
This is all done behind the scenes, you only have to provide the frequency and duty.
|
||||
|
||||
### Duty
|
||||
|
||||
The duty is a percentage of the period. It you are looking for a specific pulse width, you need to determine the period, which is 1/freq. If your frequency is 100Hz your period is 10ms. If you want a 1ms pulse, you would set the duty to 0.10%.
|
@ -9,8 +9,10 @@ trap "echo; exit 255" SIGINT
|
||||
# With -v, show all output. Otherwise, show just the result
|
||||
if [ "$1" = "-v" ]; then
|
||||
FILTER="cat"
|
||||
FILTER2="cat"
|
||||
else
|
||||
FILTER="grep -v Compiling | grep error\|Took"
|
||||
FILTER="grep -v Compiling"
|
||||
FILTER2="grep error\|Took"
|
||||
fi
|
||||
set -o pipefail
|
||||
NUM_ERRORS=0
|
||||
@ -20,7 +22,7 @@ BuildMachine () {
|
||||
BF="\"-DMACHINE_FILENAME=$basename\""
|
||||
displayname=$basename
|
||||
echo "Building machine $displayname"
|
||||
PLATFORMIO_BUILD_FLAGS=$BF platformio run 2>&1 | $FILTER
|
||||
PLATFORMIO_BUILD_FLAGS=$BF platformio run 2>&1 | $FILTER | $FILTER2
|
||||
local re=$?
|
||||
# check result
|
||||
if [ $re -ne 0 ]; then
|
||||
|
Loading…
x
Reference in New Issue
Block a user